aboutsummaryrefslogtreecommitdiff
path: root/src/examples
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2015-01-18 18:43:45 +0100
committerThomas Gubler <thomasgubler@gmail.com>2015-01-21 14:26:22 +0100
commit7c3223b8609ee418b520d19cae7e52d2a7a85e99 (patch)
treebe6f98c262b390494c06b26ee12a28400b3cc105 /src/examples
parent81215746321756665dfee562615e353c003cedd9 (diff)
downloadpx4-firmware-7c3223b8609ee418b520d19cae7e52d2a7a85e99.tar.gz
px4-firmware-7c3223b8609ee418b520d19cae7e52d2a7a85e99.tar.bz2
px4-firmware-7c3223b8609ee418b520d19cae7e52d2a7a85e99.zip
added a messageplayer prototype for ros
Diffstat (limited to 'src/examples')
-rw-r--r--src/examples/publisher/publisher_example.cpp19
-rw-r--r--src/examples/publisher/publisher_example.h1
-rw-r--r--src/examples/subscriber/subscriber_example.cpp14
-rw-r--r--src/examples/subscriber/subscriber_example.h3
4 files changed, 25 insertions, 12 deletions
diff --git a/src/examples/publisher/publisher_example.cpp b/src/examples/publisher/publisher_example.cpp
index 2e5779ebe..e85e42b38 100644
--- a/src/examples/publisher/publisher_example.cpp
+++ b/src/examples/publisher/publisher_example.cpp
@@ -45,7 +45,8 @@ using namespace px4;
PublisherExample::PublisherExample() :
_n(),
- _rc_channels_pub(PX4_ADVERTISE(_n, rc_channels))
+ _rc_channels_pub(_n.advertise<px4_rc_channels>())
+ // _rc_channels_pub(PX4_ADVERTISE(_n, rc_channels))
{
}
@@ -55,11 +56,19 @@ int PublisherExample::main()
px4::Rate loop_rate(10);
while (px4::ok()) {
- PX4_TOPIC_T(rc_channels) msg;
- msg.timestamp_last_valid = px4::get_time_micros();
- PX4_INFO("%llu", msg.timestamp_last_valid);
+ // PX4_TOPIC_T(rc_channels) msg;
+ // msg.timestamp_last_valid = px4::get_time_micros();
+ // PX4_INFO("%llu", msg.timestamp_last_valid);
+
+ // _rc_channels_pub->publish(msg);
+
+ //XXX
+ px4_rc_channels msg2;
+ msg2.data().timestamp_last_valid = px4::get_time_micros();
+ PX4_INFO("%llu", msg2.data().timestamp_last_valid);
+ // msg2.pub->publish2();
+ _rc_channels_pub->publish(msg2);
- _rc_channels_pub->publish(msg);
_n.spinOnce();
loop_rate.sleep();
diff --git a/src/examples/publisher/publisher_example.h b/src/examples/publisher/publisher_example.h
index 304ecef47..86586d0d3 100644
--- a/src/examples/publisher/publisher_example.h
+++ b/src/examples/publisher/publisher_example.h
@@ -48,5 +48,6 @@ public:
int main();
protected:
px4::NodeHandle _n;
+ // px4::Publisher<px4::px4_rc_channels> * _rc_channels_pub;
px4::Publisher * _rc_channels_pub;
};
diff --git a/src/examples/subscriber/subscriber_example.cpp b/src/examples/subscriber/subscriber_example.cpp
index 3c80561ca..1c8f4c62b 100644
--- a/src/examples/subscriber/subscriber_example.cpp
+++ b/src/examples/subscriber/subscriber_example.cpp
@@ -62,11 +62,13 @@ SubscriberExample::SubscriberExample() :
/* Do some subscriptions */
/* Function */
- PX4_SUBSCRIBE(_n, rc_channels, rc_channels_callback_function, _interval);
- /* Class Method */
- PX4_SUBSCRIBE(_n, rc_channels, SubscriberExample::rc_channels_callback, this, 1000);
- /* No callback */
- _sub_rc_chan = PX4_SUBSCRIBE(_n, rc_channels, 500);
+ // PX4_SUBSCRIBE(_n, rc_channels, rc_channels_callback_function, _interval);
+ _n.subscribe<px4_rc_channels>(rc_channels_callback_function);
+
+ // [> Class Method <]
+ // PX4_SUBSCRIBE(_n, rc_channels, SubscriberExample::rc_channels_callback, this, 1000);
+ // [> No callback <]
+ // _sub_rc_chan = PX4_SUBSCRIBE(_n, rc_channels, 500);
PX4_INFO("subscribed");
}
@@ -78,5 +80,5 @@ SubscriberExample::SubscriberExample() :
void SubscriberExample::rc_channels_callback(const PX4_TOPIC_T(rc_channels) &msg) {
PX4_INFO("Subscriber callback: [%llu], value of _sub_rc_chan: [%llu]",
msg.timestamp_last_valid,
- _sub_rc_chan->get().timestamp_last_valid);
+ _sub_rc_chan->get().data().timestamp_last_valid);
}
diff --git a/src/examples/subscriber/subscriber_example.h b/src/examples/subscriber/subscriber_example.h
index eb2c956e0..b52ae991b 100644
--- a/src/examples/subscriber/subscriber_example.h
+++ b/src/examples/subscriber/subscriber_example.h
@@ -56,7 +56,8 @@ protected:
int32_t _interval;
px4_param_t _p_test_float;
float _test_float;
- px4::PX4_SUBSCRIBER(rc_channels) * _sub_rc_chan;
+ // px4::PX4_SUBSCRIBER(rc_channels) * _sub_rc_chan;
+ px4::Subscriber<px4_rc_channels> * _sub_rc_chan;
void rc_channels_callback(const PX4_TOPIC_T(rc_channels) &msg);