diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2014-11-09 11:57:34 +0100 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2014-11-09 11:57:34 +0100 |
commit | f36f54c621cb5b36d345c5a26f72e89fc948fa65 (patch) | |
tree | 9cc8f0a8765ca0deb7ec2e73393f99cb8754e43a /src/examples/subscriber | |
parent | 1e9f431cf1d93b64f26fb9c3e42329e7237bad0e (diff) | |
download | px4-firmware-f36f54c621cb5b36d345c5a26f72e89fc948fa65.tar.gz px4-firmware-f36f54c621cb5b36d345c5a26f72e89fc948fa65.tar.bz2 px4-firmware-f36f54c621cb5b36d345c5a26f72e89fc948fa65.zip |
Restructuring of generic middleware support files, wrapping of the main ROS calls, skeletons for publishers / subscribers
Diffstat (limited to 'src/examples/subscriber')
-rw-r--r-- | src/examples/subscriber/module.mk | 42 | ||||
-rw-r--r-- | src/examples/subscriber/subscriber.cpp | 99 |
2 files changed, 88 insertions, 53 deletions
diff --git a/src/examples/subscriber/module.mk b/src/examples/subscriber/module.mk new file mode 100644 index 000000000..44d3d03a9 --- /dev/null +++ b/src/examples/subscriber/module.mk @@ -0,0 +1,42 @@ +############################################################################ +# +# Copyright (c) 2014 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +# +# Subscriber Example Application +# + +MODULE_COMMAND = subscriber + +SRCS = subscriber.cpp + +MODULE_STACKSIZE = 1200 diff --git a/src/examples/subscriber/subscriber.cpp b/src/examples/subscriber/subscriber.cpp index da69e6e25..bf16bf84e 100644 --- a/src/examples/subscriber/subscriber.cpp +++ b/src/examples/subscriber/subscriber.cpp @@ -25,70 +25,63 @@ * POSSIBILITY OF SUCH DAMAGE. */ -// %Tag(FULLTEXT)% -#include "ros/ros.h" -#include "std_msgs/String.h" +#include <px4.h> #include "px4/rc_channels.h" /** - * This tutorial demonstrates simple receipt of messages over the ROS system. + * This tutorial demonstrates simple receipt of messages over the PX4 middleware system. */ -// %Tag(CALLBACK)% -void rc_channels_callback(const px4::rc_channels::ConstPtr& msg) +void rc_channels_callback(const px4::rc_channels::ConstPtr &msg) { - ROS_INFO("I heard: [%lu]", msg->timestamp_last_valid); + PX4_INFO("I heard: [%lu]", msg->timestamp_last_valid); } -// %EndTag(CALLBACK)% + +PX4_MAIN_FUNCTION(subscriber) 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. - */ - ros::init(argc, argv, "listener"); + /** + * 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 px4::init() before using any other + * part of the PX4/ ROS system. + */ + px4::init(argc, argv, "listener"); - /** - * 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. - */ - ros::NodeHandle n; + /** + * 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. + */ + ros::NodeHandle n; - /** - * The subscribe() call is how you tell ROS that you want to receive messages - * on a given topic. This invokes a call to the ROS - * master node, which keeps a registry of who is publishing and who - * is subscribing. Messages are passed to a callback function, here - * called chatterCallback. subscribe() returns a Subscriber object that you - * must hold on to until you want to unsubscribe. When all copies of the Subscriber - * object go out of scope, this callback will automatically be unsubscribed from - * this topic. - * - * The second parameter to the subscribe() function is the size of the message - * queue. If messages are arriving faster than they are being processed, this - * is the number of messages that will be buffered up before beginning to throw - * away the oldest ones. - */ -// %Tag(SUBSCRIBER)% - ros::Subscriber sub = n.subscribe("rc_channels", 1000, rc_channels_callback); -// %EndTag(SUBSCRIBER)% + /** + * The subscribe() call is how you tell ROS that you want to receive messages + * on a given topic. This invokes a call to the ROS + * master node, which keeps a registry of who is publishing and who + * is subscribing. Messages are passed to a callback function, here + * called chatterCallback. subscribe() returns a Subscriber object that you + * must hold on to until you want to unsubscribe. When all copies of the Subscriber + * object go out of scope, this callback will automatically be unsubscribed from + * this topic. + * + * The second parameter to the subscribe() function is the size of the message + * queue. If messages are arriving faster than they are being processed, this + * is the number of messages that will be buffered up before beginning to throw + * away the oldest ones. + */ + ros::Subscriber sub = n.subscribe("rc_channels", 1000, rc_channels_callback); - /** - * ros::spin() will enter a loop, pumping callbacks. With this version, all - * callbacks will be called from within this thread (the main one). ros::spin() - * will exit when Ctrl-C is pressed, or the node is shutdown by the master. - */ -// %Tag(SPIN)% - ros::spin(); -// %EndTag(SPIN)% + /** + * px4::spin() will enter a loop, pumping callbacks. With this version, all + * callbacks will be called from within this thread (the main one). px4::spin() + * will exit when Ctrl-C is pressed, or the node is shutdown by the master. + */ + px4::spin(); - return 0; + return 0; } -// %EndTag(FULLTEXT)% |