aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-11-05 15:03:00 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-11-05 15:03:00 +0100
commit1e9f431cf1d93b64f26fb9c3e42329e7237bad0e (patch)
tree03b911ae7cffc68c1bb7db939d26769e7b360cfb /src
parent53a40dc986bfd359dc193a9b48e4799033a321b1 (diff)
downloadpx4-firmware-1e9f431cf1d93b64f26fb9c3e42329e7237bad0e.tar.gz
px4-firmware-1e9f431cf1d93b64f26fb9c3e42329e7237bad0e.tar.bz2
px4-firmware-1e9f431cf1d93b64f26fb9c3e42329e7237bad0e.zip
ros example: send rc_channels message
Diffstat (limited to 'src')
-rw-r--r--src/examples/publisher/publisher.cpp16
-rw-r--r--src/examples/subscriber/subscriber.cpp9
2 files changed, 13 insertions, 12 deletions
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 <sstream>
+#include <px4/rc_channels.h>
/**
* 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<std_msgs::String>("chatter", 1000);
+ ros::Publisher rc_channels_pub = n.advertise<px4::rc_channels>("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)%
diff --git a/src/examples/subscriber/subscriber.cpp b/src/examples/subscriber/subscriber.cpp
index e46055306..da69e6e25 100644
--- a/src/examples/subscriber/subscriber.cpp
+++ b/src/examples/subscriber/subscriber.cpp
@@ -28,14 +28,15 @@
// %Tag(FULLTEXT)%
#include "ros/ros.h"
#include "std_msgs/String.h"
+#include "px4/rc_channels.h"
/**
* This tutorial demonstrates simple receipt of messages over the ROS system.
*/
// %Tag(CALLBACK)%
-void chatterCallback(const std_msgs::String::ConstPtr& msg)
+void rc_channels_callback(const px4::rc_channels::ConstPtr& msg)
{
- ROS_INFO("I heard: [%s]", msg->data.c_str());
+ ROS_INFO("I heard: [%lu]", msg->timestamp_last_valid);
}
// %EndTag(CALLBACK)%
@@ -76,7 +77,7 @@ int main(int argc, char **argv)
* away the oldest ones.
*/
// %Tag(SUBSCRIBER)%
- ros::Subscriber sub = n.subscribe("chatter", 1000, chatterCallback);
+ ros::Subscriber sub = n.subscribe("rc_channels", 1000, rc_channels_callback);
// %EndTag(SUBSCRIBER)%
/**
@@ -90,4 +91,4 @@ int main(int argc, char **argv)
return 0;
}
-// %EndTag(FULLTEXT)% \ No newline at end of file
+// %EndTag(FULLTEXT)%