From 1e9f431cf1d93b64f26fb9c3e42329e7237bad0e Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Wed, 5 Nov 2014 15:03:00 +0100 Subject: ros example: send rc_channels message --- src/examples/publisher/publisher.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) (limited to 'src/examples/publisher') diff --git a/src/examples/publisher/publisher.cpp b/src/examples/publisher/publisher.cpp index cc88cd543..53fe2e905 100644 --- a/src/examples/publisher/publisher.cpp +++ b/src/examples/publisher/publisher.cpp @@ -33,6 +33,7 @@ // %EndTag(MSG_HEADER)% #include +#include /** * This tutorial demonstrates simple sending of messages over the ROS system. @@ -80,7 +81,7 @@ int main(int argc, char **argv) * buffer up before throwing some away. */ // %Tag(PUBLISHER)% - ros::Publisher chatter_pub = n.advertise("chatter", 1000); + ros::Publisher rc_channels_pub = n.advertise("rc_channels", 1000); // %EndTag(PUBLISHER)% // %Tag(LOOP_RATE)% @@ -100,15 +101,14 @@ int main(int argc, char **argv) * This is a message object. You stuff it with data, and then publish it. */ // %Tag(FILL_MESSAGE)% - std_msgs::String msg; + px4::rc_channels msg; - std::stringstream ss; - ss << "hello world " << count; - msg.data = ss.str(); + ros::Time time = ros::Time::now(); + msg.timestamp_last_valid = time.sec * 1e6 + time.nsec; // %EndTag(FILL_MESSAGE)% // %Tag(ROSCONSOLE)% - px4_warnx("%s", msg.data.c_str()); + px4_warnx("%lu", msg.timestamp_last_valid); // %EndTag(ROSCONSOLE)% /** @@ -118,7 +118,7 @@ int main(int argc, char **argv) * in the constructor above. */ // %Tag(PUBLISH)% - chatter_pub.publish(msg); + rc_channels_pub.publish(msg); // %EndTag(PUBLISH)% // %Tag(SPINONCE)% @@ -134,4 +134,4 @@ int main(int argc, char **argv) return 0; } -// %EndTag(FULLTEXT)% \ No newline at end of file +// %EndTag(FULLTEXT)% -- cgit v1.2.3