aboutsummaryrefslogtreecommitdiff
path: root/src/examples/subscriber
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-11-24 15:58:06 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-11-24 15:58:06 +0100
commit3f36d30a3413cd70096e953a2c9ea0ded65bf24e (patch)
tree4a1569cecb1cfe0507fed5334523ea3d57cf396a /src/examples/subscriber
parent1e36de61579dd35fe46a069520b7c8970c3cb7cd (diff)
downloadpx4-firmware-3f36d30a3413cd70096e953a2c9ea0ded65bf24e.tar.gz
px4-firmware-3f36d30a3413cd70096e953a2c9ea0ded65bf24e.tar.bz2
px4-firmware-3f36d30a3413cd70096e953a2c9ea0ded65bf24e.zip
wrapped subscriber
Diffstat (limited to 'src/examples/subscriber')
-rw-r--r--src/examples/subscriber/subscriber.cpp4
1 files changed, 2 insertions, 2 deletions
diff --git a/src/examples/subscriber/subscriber.cpp b/src/examples/subscriber/subscriber.cpp
index bf16bf84e..39059daa3 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,7 +74,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.
*/
- ros::Subscriber sub = n.subscribe("rc_channels", 1000, rc_channels_callback);
+ px4::Subscriber* sub = n.subscribe("rc_channels", rc_channels_callback);
/**
* px4::spin() will enter a loop, pumping callbacks. With this version, all