aboutsummaryrefslogtreecommitdiff
path: root/src/examples/publisher/publisher.cpp
diff options
context:
space:
mode:
Diffstat (limited to 'src/examples/publisher/publisher.cpp')
-rw-r--r--src/examples/publisher/publisher.cpp138
1 files changed, 48 insertions, 90 deletions
diff --git a/src/examples/publisher/publisher.cpp b/src/examples/publisher/publisher.cpp
index 53fe2e905..91e063162 100644
--- a/src/examples/publisher/publisher.cpp
+++ b/src/examples/publisher/publisher.cpp
@@ -26,112 +26,70 @@
*/
#include <px4.h>
-
-// %EndTag(ROS_HEADER)%
-// %Tag(MSG_HEADER)%
-#include "std_msgs/String.h"
-// %EndTag(MSG_HEADER)%
+#include <px4/rc_channels.h>
#include <sstream>
-#include <px4/rc_channels.h>
/**
- * This tutorial demonstrates simple sending of messages over the ROS system.
+ * This tutorial demonstrates simple sending of messages over the PX4 middleware system.
*/
int main(int argc, char **argv)
{
- /**
- * The ros::init() function needs to see argc and argv so that it can perform
- * any ROS arguments and name remapping that were provided at the command line. For programmatic
- * remappings you can use a different version of init() which takes remappings
- * directly, but for most command-line programs, passing argc and argv is the easiest
- * way to do it. The third argument to init() is the name of the node.
- *
- * You must call one of the versions of ros::init() before using any other
- * part of the ROS system.
- */
-// %Tag(INIT)%
- ros::init(argc, argv, "px4_publisher");
-// %EndTag(INIT)%
- /**
- * NodeHandle is the main access point to communications with the ROS system.
- * The first NodeHandle constructed will fully initialize this node, and the last
- * NodeHandle destructed will close down the node.
- */
-// %Tag(NODEHANDLE)%
- ros::NodeHandle n;
-// %EndTag(NODEHANDLE)%
+ px4::init(argc, argv, "px4_publisher");
+
+ ros::NodeHandle n;
- /**
- * The advertise() function is how you tell ROS that you want to
- * publish on a given topic name. This invokes a call to the ROS
- * master node, which keeps a registry of who is publishing and who
- * is subscribing. After this advertise() call is made, the master
- * node will notify anyone who is trying to subscribe to this topic name,
- * and they will in turn negotiate a peer-to-peer connection with this
- * node. advertise() returns a Publisher object which allows you to
- * publish messages on that topic through a call to publish(). Once
- * all copies of the returned Publisher object are destroyed, the topic
- * will be automatically unadvertised.
- *
- * The second parameter to advertise() is the size of the message queue
- * used for publishing messages. If messages are published more quickly
- * than we can send them, the number here specifies how many messages to
- * buffer up before throwing some away.
- */
-// %Tag(PUBLISHER)%
- ros::Publisher rc_channels_pub = n.advertise<px4::rc_channels>("rc_channels", 1000);
-// %EndTag(PUBLISHER)%
+ /**
+ * The advertise() function is how you tell ROS that you want to
+ * publish on a given topic name. This invokes a call to the ROS
+ * master node, which keeps a registry of who is publishing and who
+ * is subscribing. After this advertise() call is made, the master
+ * node will notify anyone who is trying to subscribe to this topic name,
+ * and they will in turn negotiate a peer-to-peer connection with this
+ * node. advertise() returns a Publisher object which allows you to
+ * publish messages on that topic through a call to publish(). Once
+ * all copies of the returned Publisher object are destroyed, the topic
+ * will be automatically unadvertised.
+ *
+ * The second parameter to advertise() is the size of the message queue
+ * used for publishing messages. If messages are published more quickly
+ * 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);
-// %Tag(LOOP_RATE)%
- ros::Rate loop_rate(10);
-// %EndTag(LOOP_RATE)%
+ px4::Rate loop_rate(10);
- /**
- * A count of how many messages we have sent. This is used to create
- * a unique string for each message.
- */
-// %Tag(ROS_OK)%
- int count = 0;
- while (ros::ok())
- {
-// %EndTag(ROS_OK)%
- /**
- * This is a message object. You stuff it with data, and then publish it.
- */
-// %Tag(FILL_MESSAGE)%
- px4::rc_channels msg;
+ /**
+ * A count of how many messages we have sent. This is used to create
+ * a unique string for each message.
+ */
+ int count = 0;
- ros::Time time = ros::Time::now();
- msg.timestamp_last_valid = time.sec * 1e6 + time.nsec;
-// %EndTag(FILL_MESSAGE)%
+ while (px4::ok()) {
+ /**
+ * This is a message object. You stuff it with data, and then publish it.
+ */
+ px4::rc_channels msg;
-// %Tag(ROSCONSOLE)%
- px4_warnx("%lu", msg.timestamp_last_valid);
-// %EndTag(ROSCONSOLE)%
+ msg.timestamp_last_valid = px4::get_time_micros();
+ PX4_INFO("%lu", msg.timestamp_last_valid);
- /**
- * The publish() function is how you send messages. The parameter
- * is the message object. The type of this object must agree with the type
- * given as a template parameter to the advertise<>() call, as was done
- * in the constructor above.
- */
-// %Tag(PUBLISH)%
- rc_channels_pub.publish(msg);
-// %EndTag(PUBLISH)%
+ /**
+ * The publish() function is how you send messages. The parameter
+ * is the message object. The type of this object must agree with the type
+ * given as a template parameter to the advertise<>() call, as was done
+ * in the constructor above.
+ */
+ rc_channels_pub.publish(msg);
-// %Tag(SPINONCE)%
- ros::spinOnce();
-// %EndTag(SPINONCE)%
+ px4::spin_once();
-// %Tag(RATE_SLEEP)%
- loop_rate.sleep();
-// %EndTag(RATE_SLEEP)%
- ++count;
- }
+ loop_rate.sleep();
+ ++count;
+ }
- return 0;
+ return 0;
}
-// %EndTag(FULLTEXT)%