aboutsummaryrefslogtreecommitdiff
path: root/src/examples/publisher
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-12-10 16:22:19 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-12-10 16:22:19 +0100
commit8ae1c9763d649470ae7c55e35507509dbb2612ff (patch)
treef4ed384d4c7bcd0e6bda38f8f587981b597ae092 /src/examples/publisher
parentcb77c16601338d2d0b22dc71ef057ec4d91652c4 (diff)
downloadpx4-firmware-8ae1c9763d649470ae7c55e35507509dbb2612ff.tar.gz
px4-firmware-8ae1c9763d649470ae7c55e35507509dbb2612ff.tar.bz2
px4-firmware-8ae1c9763d649470ae7c55e35507509dbb2612ff.zip
write publisher example as class
Diffstat (limited to 'src/examples/publisher')
-rw-r--r--src/examples/publisher/module.mk3
-rw-r--r--src/examples/publisher/publisher.cpp100
-rw-r--r--src/examples/publisher/publisher_example.cpp67
-rw-r--r--src/examples/publisher/publisher_example.h51
-rw-r--r--src/examples/publisher/publisher_main.cpp112
5 files changed, 232 insertions, 101 deletions
diff --git a/src/examples/publisher/module.mk b/src/examples/publisher/module.mk
index 0fc4316ec..4f941cd43 100644
--- a/src/examples/publisher/module.mk
+++ b/src/examples/publisher/module.mk
@@ -37,6 +37,7 @@
MODULE_COMMAND = publisher
-SRCS = publisher.cpp
+SRCS = publisher_main.cpp \
+ publisher_example.cpp
MODULE_STACKSIZE = 1200
diff --git a/src/examples/publisher/publisher.cpp b/src/examples/publisher/publisher.cpp
deleted file mode 100644
index 8ef147493..000000000
--- a/src/examples/publisher/publisher.cpp
+++ /dev/null
@@ -1,100 +0,0 @@
-/*
- * Copyright (C) 2008, Morgan Quigley and Willow Garage, Inc.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * * Redistributions of source code must retain the above copyright notice,
- * this list of conditions and the following disclaimer.
- * * 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.
- * * Neither the names of Stanford University or Willow Garage, Inc. 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.
- */
-
-#include <px4.h>
-
-using namespace px4;
-
-/**
- * This tutorial demonstrates simple sending of messages over the PX4 middleware system.
- */
-
-namespace px4
-{
-bool task_should_exit = false;
-}
-
-PX4_MAIN_FUNCTION(publisher)
-{
-
- px4::init(argc, argv, "px4_publisher");
-
- px4::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.
- */
- px4::Publisher * rc_channels_pub = PX4_ADVERTISE(n, rc_channels);
-
-
- 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.
- */
- int count = 0;
-
- while (px4::ok()) {
- /**
- * This is a message object. You stuff it with data, and then publish it.
- */
- PX4_TOPIC_T(rc_channels) msg;
-
- msg.timestamp_last_valid = px4::get_time_micros();
- PX4_INFO("%llu", 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.
- */
- rc_channels_pub->publish(msg);
-
- n.spinOnce();
-
- loop_rate.sleep();
- ++count;
- }
-
- return 0;
-}
diff --git a/src/examples/publisher/publisher_example.cpp b/src/examples/publisher/publisher_example.cpp
new file mode 100644
index 000000000..3c716291b
--- /dev/null
+++ b/src/examples/publisher/publisher_example.cpp
@@ -0,0 +1,67 @@
+
+/****************************************************************************
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file publisher_example.cpp
+ * Example subscriber for ros and px4
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#include "publisher_example.h"
+
+PublisherExample::PublisherExample() :
+ _n(),
+ _rc_channels_pub(PX4_ADVERTISE(_n, rc_channels))
+{
+
+}
+
+int PublisherExample::main()
+{
+ px4::Rate loop_rate(10);
+
+ while (px4::ok()) {
+ PX4_TOPIC_T(rc_channels) msg;
+ msg.timestamp_last_valid = px4::get_time_micros();
+ PX4_INFO("%llu", msg.timestamp_last_valid);
+
+ _rc_channels_pub->publish(msg);
+
+ _n.spinOnce();
+ loop_rate.sleep();
+ }
+
+ return 0;
+}
diff --git a/src/examples/publisher/publisher_example.h b/src/examples/publisher/publisher_example.h
new file mode 100644
index 000000000..78c1ffc89
--- /dev/null
+++ b/src/examples/publisher/publisher_example.h
@@ -0,0 +1,51 @@
+/****************************************************************************
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file publisher.h
+ * Example publisher for ros and px4
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+#include <px4.h>
+class PublisherExample {
+public:
+ PublisherExample();
+
+ ~PublisherExample() {};
+
+ int main();
+protected:
+ px4::NodeHandle _n;
+ px4::Publisher * _rc_channels_pub;
+};
diff --git a/src/examples/publisher/publisher_main.cpp b/src/examples/publisher/publisher_main.cpp
new file mode 100644
index 000000000..e1034fec5
--- /dev/null
+++ b/src/examples/publisher/publisher_main.cpp
@@ -0,0 +1,112 @@
+/****************************************************************************
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file publisher_main.cpp
+ * Example publisher for ros and px4
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+#include <string.h>
+#include <cstdlib>
+#include "publisher_example.h"
+
+static bool thread_running = false; /**< Deamon status flag */
+static int daemon_task; /**< Handle of deamon task / thread */
+namespace px4
+{
+bool task_should_exit = false;
+}
+using namespace px4;
+
+int publisher_task_main(int argc, char *argv[]);
+
+PX4_MAIN_FUNCTION(publisher)
+{
+ px4::init(argc, argv, "publisher");
+
+ if (argc < 1) {
+ errx(1, "usage: publisher {start|stop|status}");
+ }
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (thread_running) {
+ warnx("already running");
+ /* this is not an error */
+ exit(0);
+ }
+
+ task_should_exit = false;
+
+ daemon_task = task_spawn_cmd("publisher",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 5,
+ 2000,
+ publisher_task_main,
+ (argv) ? (const char **)&argv[2] : (const char **)NULL);
+
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ task_should_exit = true;
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (thread_running) {
+ warnx("is running");
+
+ } else {
+ warnx("not started");
+ }
+
+ exit(0);
+ }
+
+ warnx("unrecognized command");
+ return 1;
+}
+
+int publisher_task_main(int argc, char *argv[])
+{
+ warnx("starting");
+ PublisherExample p;
+ thread_running = true;
+ p.main();
+
+ warnx("exiting.");
+ thread_running = false;
+ return 0;
+}