forked from Archive/PX4-Autopilot
ros example: send rc_channels message
This commit is contained in:
parent
53a40dc986
commit
1e9f431cf1
|
@ -84,6 +84,7 @@ catkin_package(
|
|||
# LIBRARIES px4
|
||||
# CATKIN_DEPENDS roscpp rospy std_msgs
|
||||
# DEPENDS system_lib
|
||||
CATKIN_DEPENDS message_runtime
|
||||
)
|
||||
|
||||
###########
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
<version>1.0.0</version>
|
||||
<description>The PX4 Flight Stack package</description>
|
||||
|
||||
<!-- One maintainer tag required, multiple allowed, one person per tag -->
|
||||
<!-- One maintainer tag required, multiple allowed, one person per tag -->
|
||||
<!-- Example: -->
|
||||
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
|
||||
<maintainer email="lorenz@px4.io">Lorenz Meier</maintainer>
|
||||
|
@ -32,11 +32,11 @@
|
|||
<!-- Dependencies can be catkin packages or system dependencies -->
|
||||
<!-- Examples: -->
|
||||
<!-- Use build_depend for packages you need at compile time: -->
|
||||
<!-- <build_depend>message_generation</build_depend> -->
|
||||
<build_depend>message_generation</build_depend>
|
||||
<!-- Use buildtool_depend for build tool packages: -->
|
||||
<!-- <buildtool_depend>catkin</buildtool_depend> -->
|
||||
<!-- Use run_depend for packages you need at runtime: -->
|
||||
<!-- <run_depend>message_runtime</run_depend> -->
|
||||
<run_depend>message_runtime</run_depend>
|
||||
<!-- Use test_depend for packages you need only for testing: -->
|
||||
<!-- <test_depend>gtest</test_depend> -->
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
|
@ -56,4 +56,4 @@
|
|||
<!-- Other tools can request additional information be placed here -->
|
||||
|
||||
</export>
|
||||
</package>
|
||||
</package>
|
||||
|
|
|
@ -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)%
|
||||
// %EndTag(FULLTEXT)%
|
||||
|
|
|
@ -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)%
|
||||
// %EndTag(FULLTEXT)%
|
||||
|
|
Loading…
Reference in New Issue