diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2014-11-10 07:31:55 +0100 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2014-11-10 07:31:55 +0100 |
commit | 2bbc98067a16621b49f103fc3e1ae099ab957aa8 (patch) | |
tree | af4b6171e2fea35e736b04b56bea25429f835fb5 /src/examples | |
parent | f36f54c621cb5b36d345c5a26f72e89fc948fa65 (diff) | |
download | px4-firmware-2bbc98067a16621b49f103fc3e1ae099ab957aa8.tar.gz px4-firmware-2bbc98067a16621b49f103fc3e1ae099ab957aa8.tar.bz2 px4-firmware-2bbc98067a16621b49f103fc3e1ae099ab957aa8.zip |
Complementing ROS wrapper, not compiling yetros_wrapper
Diffstat (limited to 'src/examples')
-rw-r--r-- | src/examples/publisher/publisher.cpp | 4 | ||||
-rw-r--r-- | src/examples/subscriber/subscriber.cpp | 6 |
2 files changed, 5 insertions, 5 deletions
diff --git a/src/examples/publisher/publisher.cpp b/src/examples/publisher/publisher.cpp index 91e063162..7e2b2f0d4 100644 --- a/src/examples/publisher/publisher.cpp +++ b/src/examples/publisher/publisher.cpp @@ -67,7 +67,7 @@ int main(int argc, char **argv) */ int count = 0; - while (px4::ok()) { + while (n.ok()) { /** * This is a message object. You stuff it with data, and then publish it. */ @@ -84,7 +84,7 @@ int main(int argc, char **argv) */ 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 bf16bf84e..626ceeb25 100644 --- a/src/examples/subscriber/subscriber.cpp +++ b/src/examples/subscriber/subscriber.cpp @@ -57,7 +57,7 @@ int main(int argc, char **argv) * The first NodeHandle constructed will fully initialize this node, and the last * NodeHandle destructed will close down the node. */ - ros::NodeHandle n; + px4::NodeHandle n; /** * The subscribe() call is how you tell ROS that you want to receive messages @@ -74,14 +74,14 @@ int main(int argc, char **argv) * is the number of messages that will be buffered up before beginning to throw * away the oldest ones. */ - ros::Subscriber sub = n.subscribe("rc_channels", 1000, rc_channels_callback); + px4::Subscriber sub = n.subscribe("rc_channels", 1000, rc_channels_callback); /** * px4::spin() will enter a loop, pumping callbacks. With this version, all * 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; } |