diff options
author | Thomas Gubler <thomasgubler@gmail.com> | 2014-11-26 11:36:23 +0100 |
---|---|---|
committer | Thomas Gubler <thomasgubler@gmail.com> | 2014-11-26 11:36:23 +0100 |
commit | e7c1e5b1ff7b1bbdc11ab2cae6b99fe459487119 (patch) | |
tree | ed69515032079068a3f9fcbf46356a0f860e2f48 /src/examples/subscriber | |
parent | 3c6f6618e8709c22ac21f8f0353f292f25da22f7 (diff) | |
download | px4-firmware-e7c1e5b1ff7b1bbdc11ab2cae6b99fe459487119.tar.gz px4-firmware-e7c1e5b1ff7b1bbdc11ab2cae6b99fe459487119.tar.bz2 px4-firmware-e7c1e5b1ff7b1bbdc11ab2cae6b99fe459487119.zip |
wip, working on the nuttx wrapper
Diffstat (limited to 'src/examples/subscriber')
-rw-r--r-- | src/examples/subscriber/subscriber.cpp | 11 |
1 files changed, 6 insertions, 5 deletions
diff --git a/src/examples/subscriber/subscriber.cpp b/src/examples/subscriber/subscriber.cpp index b91859027..cdadaf2bc 100644 --- a/src/examples/subscriber/subscriber.cpp +++ b/src/examples/subscriber/subscriber.cpp @@ -26,19 +26,20 @@ */ #include <px4.h> -#include "px4/rc_channels.h" + +using namespace px4; /** * This tutorial demonstrates simple receipt of messages over the PX4 middleware system. */ -void rc_channels_callback(const px4::rc_channels::ConstPtr &msg) +void rc_channels_callback(const PX4_TOPIC_T(rc_channels) *msg) { PX4_INFO("I heard: [%lu]", msg->timestamp_last_valid); } -PX4_MAIN_FUNCTION(subscriber) +// __EXPORT bool task_should_exit; -int main(int argc, char **argv) +PX4_MAIN_FUNCTION(subscriber) { /** * The ros::init() function needs to see argc and argv so that it can perform @@ -74,7 +75,7 @@ int main(int argc, char **argv) * is the number of messages that will be buffered up before beginning to throw * away the oldest ones. */ - px4::Subscriber sub = n.subscribe(PX4_TOPIC(rc_channels), rc_channels_callback); + n.subscribe(PX4_TOPIC(rc_channels), rc_channels_callback); PX4_INFO("subscribed"); /** |