From ee534b827a51a7356e565b665e280f765bd8d302 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Wed, 26 Nov 2014 13:18:28 +0100 Subject: move spin functions to nodehandle --- src/examples/publisher/publisher.cpp | 2 +- src/examples/subscriber/subscriber.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) (limited to 'src/examples') diff --git a/src/examples/publisher/publisher.cpp b/src/examples/publisher/publisher.cpp index 5ee8b459b..521c7c838 100644 --- a/src/examples/publisher/publisher.cpp +++ b/src/examples/publisher/publisher.cpp @@ -90,7 +90,7 @@ PX4_MAIN_FUNCTION(publisher) */ rc_channels_pub->publish(msg); - px4::spin_once(); + n.spinOnce(); loop_rate.sleep(); ++count; diff --git a/src/examples/subscriber/subscriber.cpp b/src/examples/subscriber/subscriber.cpp index 093697d8e..0d0a81d7e 100644 --- a/src/examples/subscriber/subscriber.cpp +++ b/src/examples/subscriber/subscriber.cpp @@ -85,7 +85,7 @@ PX4_MAIN_FUNCTION(subscriber) * callbacks will be called from within this thread (the main one). px4::spin() * will exit when Ctrl-C is pressed, or the node is shutdown by the master. */ - px4::spin(); + n.spin(); return 0; } -- cgit v1.2.3