diff --git a/CMakeLists.txt b/CMakeLists.txt index 144bdcbc34..de2907e6ab 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -84,6 +84,7 @@ catkin_package( # LIBRARIES px4 # CATKIN_DEPENDS roscpp rospy std_msgs # DEPENDS system_lib + CATKIN_DEPENDS message_runtime ) ########### diff --git a/include/px4.h b/include/px4.h index abc10276f1..4684cd256f 100644 --- a/include/px4.h +++ b/include/px4.h @@ -38,10 +38,16 @@ */ #if defined(__linux) || (defined(__APPLE__) && defined(__MACH__)) +/* + * Building for running within the ROS environment + */ #include "ros/ros.h" #define px4_warnx ROS_WARN #define px4_infox ROS_INFO #else +/* + * Building for NuttX + */ #define px4_warnx warnx #define px4_infox warnx #endif diff --git a/package.xml b/package.xml index 3575119be7..bc23cdd18f 100644 --- a/package.xml +++ b/package.xml @@ -4,7 +4,7 @@ 1.0.0 The PX4 Flight Stack package - + Lorenz Meier @@ -32,11 +32,11 @@ - + message_generation - + message_runtime catkin @@ -56,4 +56,4 @@ - \ No newline at end of file + diff --git a/src/examples/publisher/publisher.cpp b/src/examples/publisher/publisher.cpp index cc88cd543d..53fe2e9051 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)% diff --git a/src/examples/subscriber/subscriber.cpp b/src/examples/subscriber/subscriber.cpp index e46055306c..da69e6e25e 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)%