aboutsummaryrefslogtreecommitdiff
path: root/apps/uORB
diff options
context:
space:
mode:
Diffstat (limited to 'apps/uORB')
-rw-r--r--apps/uORB/objects_common.cpp6
-rw-r--r--apps/uORB/topics/actuator_outputs.h68
-rw-r--r--apps/uORB/uORB.cpp88
-rw-r--r--apps/uORB/uORB.h21
4 files changed, 150 insertions, 33 deletions
diff --git a/apps/uORB/objects_common.cpp b/apps/uORB/objects_common.cpp
index d6b566b6a..6ff66fceb 100644
--- a/apps/uORB/objects_common.cpp
+++ b/apps/uORB/objects_common.cpp
@@ -114,3 +114,9 @@ ORB_DEFINE(actuator_controls_1, struct actuator_controls_s);
ORB_DEFINE(actuator_controls_2, struct actuator_controls_s);
ORB_DEFINE(actuator_controls_3, struct actuator_controls_s);
ORB_DEFINE(actuator_armed, struct actuator_armed_s);
+
+#include "topics/actuator_outputs.h"
+ORB_DEFINE(actuator_outputs_0, struct actuator_output_s);
+ORB_DEFINE(actuator_outputs_1, struct actuator_output_s);
+ORB_DEFINE(actuator_outputs_2, struct actuator_output_s);
+ORB_DEFINE(actuator_outputs_3, struct actuator_output_s);
diff --git a/apps/uORB/topics/actuator_outputs.h b/apps/uORB/topics/actuator_outputs.h
new file mode 100644
index 000000000..63441a059
--- /dev/null
+++ b/apps/uORB/topics/actuator_outputs.h
@@ -0,0 +1,68 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 actuator_outputs.h
+ *
+ * Actuator output values.
+ *
+ * Values published to these topics are the outputs of the control mixing
+ * system as sent to the actuators (servos, motors, etc.) that operate
+ * the vehicle.
+ *
+ * Each topic can be published by a single output driver.
+ */
+
+#ifndef TOPIC_ACTUATOR_OUTPUTS_H
+#define TOPIC_ACTUATOR_OUTPUTS_H
+
+#include <stdint.h>
+#include "../uORB.h"
+
+#define NUM_ACTUATOR_OUTPUTS 16
+#define NUM_ACTUATOR_OUTPUT_GROUPS 4 /**< for sanity checking */
+
+struct actuator_output_s {
+ float output[NUM_ACTUATOR_OUTPUTS];
+};
+
+/* actuator output sets; this list can be expanded as more drivers emerge */
+ORB_DECLARE(actuator_outputs_0);
+ORB_DECLARE(actuator_outputs_1);
+ORB_DECLARE(actuator_outputs_2);
+ORB_DECLARE(actuator_outputs_3);
+
+/* output sets with pre-defined applications */
+#define ORB_ID_VEHICLE_CONTROLS ORB_ID(actuator_outputs_0)
+
+#endif \ No newline at end of file
diff --git a/apps/uORB/uORB.cpp b/apps/uORB/uORB.cpp
index 1e7cdc8db..c4434e4ed 100644
--- a/apps/uORB/uORB.cpp
+++ b/apps/uORB/uORB.cpp
@@ -112,6 +112,8 @@ public:
virtual ssize_t write(struct file *filp, const char *buffer, size_t buflen);
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+ static ssize_t publish(const orb_metadata *meta, orb_advert_t handle, const void *data);
+
protected:
virtual pollevent_t poll_state(struct file *filp);
virtual void poll_notify_one(struct pollfd *fds, pollevent_t events);
@@ -298,6 +300,8 @@ ORBDevNode::write(struct file *filp, const char *buffer, size_t buflen)
*
* Writes outside interrupt context will allocate the object
* if it has not yet been allocated.
+ *
+ * Note that filp will usually be NULL.
*/
if (nullptr == _data) {
if (!up_interrupt_context()) {
@@ -353,12 +357,42 @@ ORBDevNode::ioctl(struct file *filp, int cmd, unsigned long arg)
sd->update_interval = arg;
return OK;
+ case ORBIOCGADVERTISER:
+ *(uintptr_t *)arg = (uintptr_t)this;
+ return OK;
+
default:
/* give it to the superclass */
return CDev::ioctl(filp, cmd, arg);
}
}
+ssize_t
+ORBDevNode::publish(const orb_metadata *meta, orb_advert_t handle, const void *data)
+{
+ ORBDevNode *devnode = (ORBDevNode *)handle;
+ int ret;
+
+ /* this is a bit risky, since we are trusting the handle in order to deref it */
+ if (devnode->_meta != meta) {
+ errno = EINVAL;
+ return ERROR;
+ }
+
+ /* call the devnode write method with no file pointer */
+ ret = devnode->write(nullptr, (const char *)data, meta->o_size);
+
+ if (ret < 0)
+ return ERROR;
+
+ if (ret != (int)meta->o_size) {
+ errno = EIO;
+ return ERROR;
+ }
+
+ return OK;
+}
+
pollevent_t
ORBDevNode::poll_state(struct file *filp)
{
@@ -614,7 +648,7 @@ test()
if (pfd < 0)
return test_fail("advertise failed: %d", errno);
- test_note("publish fd %d", pfd);
+ test_note("publish handle 0x%08x", pfd);
sfd = orb_subscribe(ORB_ID(orb_test));
if (sfd < 0)
@@ -877,29 +911,35 @@ node_open(Flavor f, const struct orb_metadata *meta, const void *data, bool adve
return ERROR;
}
- /* the advertiser must perform an initial publish to initialise the object */
- if (advertiser) {
- ret = orb_publish(meta, fd, data);
-
- if (ret != OK) {
- /* save errno across the close */
- ret = errno;
- close(fd);
- errno = ret;
- return ERROR;
- }
- }
-
/* everything has been OK, we can return the handle now */
return fd;
}
} // namespace
-int
+orb_advert_t
orb_advertise(const struct orb_metadata *meta, const void *data)
{
- return node_open(PUBSUB, meta, data, true);
+ int result, fd;
+ orb_advert_t advertiser;
+
+ /* open the node as an advertiser */
+ fd = node_open(PUBSUB, meta, data, true);
+ if (fd == ERROR)
+ return ERROR;
+
+ /* get the advertiser handle and close the node */
+ result = ioctl(fd, ORBIOCGADVERTISER, (unsigned long)&advertiser);
+ close(fd);
+ if (result == ERROR)
+ return ERROR;
+
+ /* the advertiser must perform an initial publish to initialise the object */
+ result= orb_publish(meta, advertiser, data);
+ if (result == ERROR)
+ return ERROR;
+
+ return advertiser;
}
int
@@ -915,21 +955,9 @@ orb_unsubscribe(int handle)
}
int
-orb_publish(const struct orb_metadata *meta, int handle, const void *data)
+orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data)
{
- int ret;
-
- ret = write(handle, data, meta->o_size);
-
- if (ret < 0)
- return ERROR;
-
- if (ret != (int)meta->o_size) {
- errno = EIO;
- return ERROR;
- }
-
- return OK;
+ return ORBDevNode::publish(meta, handle, data);
}
int
diff --git a/apps/uORB/uORB.h b/apps/uORB/uORB.h
index c36d0044f..eb068d2b7 100644
--- a/apps/uORB/uORB.h
+++ b/apps/uORB/uORB.h
@@ -106,11 +106,26 @@ struct orb_metadata {
__BEGIN_DECLS
/**
+ * ORB topic advertiser handle.
+ *
+ * Advertiser handles are global; once obtained they can be shared freely
+ * and do not need to be closed or released.
+ *
+ * This permits publication from interrupt context and other contexts where
+ * a file-descriptor-based handle would not otherwise be in scope for the
+ * publisher.
+ */
+typedef intptr_t orb_advert_t;
+
+/**
* Advertise as the publisher of a topic.
*
* This performs the initial advertisement of a topic; it creates the topic
* node in /obj if required and publishes the initial data.
*
+ * Any number of advertisers may publish to a topic; publications are atomic
+ * but co-ordination between publishers is not provided by the ORB.
+ *
* @param meta The uORB metadata (usually from the ORB_ID() macro)
* for the topic.
* @param data A pointer to the initial data to be published.
@@ -122,7 +137,7 @@ __BEGIN_DECLS
* ORB_DEFINE with no corresponding ORB_DECLARE)
* this function will return -1 and set errno to ENOENT.
*/
-extern int orb_advertise(const struct orb_metadata *meta, const void *data) __EXPORT;
+extern orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data) __EXPORT;
/**
* Publish new data to a topic.
@@ -131,13 +146,13 @@ extern int orb_advertise(const struct orb_metadata *meta, const void *data) __EX
* will be notified. Subscribers that are not waiting can check the topic
* for updates using orb_check and/or orb_stat.
*
- * @handle The handle returned from orb_advertise.
* @param meta The uORB metadata (usually from the ORB_ID() macro)
* for the topic.
+ * @handle The handle returned from orb_advertise.
* @param data A pointer to the data to be published.
* @return OK on success, ERROR otherwise with errno set accordingly.
*/
-extern int orb_publish(const struct orb_metadata *meta, int handle, const void *data) __EXPORT;
+extern int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data) __EXPORT;
/**
* Subscribe to a topic.