aboutsummaryrefslogtreecommitdiff
path: root/src/examples
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2015-01-22 16:47:28 +0100
committerThomas Gubler <thomasgubler@gmail.com>2015-01-22 16:47:28 +0100
commit49d41773fc990a6b878543fac2c5cda328bf7d78 (patch)
treec569a891afdaba69c6ba0975bd377134acbb984c /src/examples
parent8c4fce3654bbf4cb31314f1fb596f4fd17772589 (diff)
downloadpx4-firmware-49d41773fc990a6b878543fac2c5cda328bf7d78.tar.gz
px4-firmware-49d41773fc990a6b878543fac2c5cda328bf7d78.tar.bz2
px4-firmware-49d41773fc990a6b878543fac2c5cda328bf7d78.zip
ros wrapper port callback to methods and subscriber without callback
Diffstat (limited to 'src/examples')
-rw-r--r--src/examples/subscriber/subscriber_example.cpp20
-rw-r--r--src/examples/subscriber/subscriber_example.h2
2 files changed, 12 insertions, 10 deletions
diff --git a/src/examples/subscriber/subscriber_example.cpp b/src/examples/subscriber/subscriber_example.cpp
index 18f1a9eb9..217e4d48f 100644
--- a/src/examples/subscriber/subscriber_example.cpp
+++ b/src/examples/subscriber/subscriber_example.cpp
@@ -64,10 +64,11 @@ SubscriberExample::SubscriberExample() :
/* Function */
_n.subscribe<px4_rc_channels>(rc_channels_callback_function); //ROS version
- // [> Class Method <]
- // PX4_SUBSCRIBE(_n, rc_channels, SubscriberExample::rc_channels_callback, this, 1000);
- // [> No callback <]
- // _sub_rc_chan = PX4_SUBSCRIBE(_n, rc_channels, 500);
+ /* No callback */
+ _sub_rc_chan = _n.subscribe<px4_rc_channels>();
+
+ /* Class Method */
+ _n.subscribe<px4_rc_channels>(&SubscriberExample::rc_channels_callback, this);
PX4_INFO("subscribed");
}
@@ -76,8 +77,9 @@ SubscriberExample::SubscriberExample() :
* This tutorial demonstrates simple receipt of messages over the PX4 middleware system.
* Also the current value of the _sub_rc_chan subscription is printed
*/
-// 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().data().timestamp_last_valid);
-// }
+void SubscriberExample::rc_channels_callback(const px4_rc_channels &msg) {
+ PX4_INFO("Callback (method): [%llu]",
+ msg.data().timestamp_last_valid);
+ PX4_INFO("Callback (method): value of _sub_rc_chan: [%llu]",
+ _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 883d83be7..8da3df438 100644
--- a/src/examples/subscriber/subscriber_example.h
+++ b/src/examples/subscriber/subscriber_example.h
@@ -58,7 +58,7 @@ protected:
float _test_float;
px4::Subscriber<px4_rc_channels> * _sub_rc_chan;
- // void rc_channels_callback(const PX4_TOPIC_T(rc_channels) &msg);
+ void rc_channels_callback(const px4_rc_channels &msg);
};