diff options
author | Thomas Gubler <thomasgubler@gmail.com> | 2014-11-25 09:56:18 +0100 |
---|---|---|
committer | Thomas Gubler <thomasgubler@gmail.com> | 2014-11-25 09:56:18 +0100 |
commit | 978013bbb8d67e295d92a54e16f7728013722e92 (patch) | |
tree | ac4774fb6b3ea1563408acd7f1d221cfe164cb36 /src/examples | |
parent | 0a3492fc328280422df9472d3d8a586d92242feb (diff) | |
download | px4-firmware-978013bbb8d67e295d92a54e16f7728013722e92.tar.gz px4-firmware-978013bbb8d67e295d92a54e16f7728013722e92.tar.bz2 px4-firmware-978013bbb8d67e295d92a54e16f7728013722e92.zip |
px4 wrapper for ros publisher
Diffstat (limited to 'src/examples')
-rw-r--r-- | src/examples/publisher/publisher.cpp | 5 |
1 files changed, 3 insertions, 2 deletions
diff --git a/src/examples/publisher/publisher.cpp b/src/examples/publisher/publisher.cpp index 91e063162..6869e765b 100644 --- a/src/examples/publisher/publisher.cpp +++ b/src/examples/publisher/publisher.cpp @@ -38,7 +38,7 @@ int main(int argc, char **argv) px4::init(argc, argv, "px4_publisher"); - ros::NodeHandle n; + px4::NodeHandle n; /** * The advertise() function is how you tell ROS that you want to @@ -57,7 +57,8 @@ int main(int argc, char **argv) * than we can send them, the number here specifies how many messages to * buffer up before throwing some away. */ - ros::Publisher rc_channels_pub = n.advertise<px4::rc_channels>("rc_channels", 1000); + px4::Publisher rc_channels_pub = n.advertise<px4::rc_channels>("rc_channels"); + px4::Rate loop_rate(10); |