aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2015-01-24 15:50:53 +0100
committerLorenz Meier <lm@inf.ethz.ch>2015-01-29 16:33:52 +0100
commit8de411619a0ce05cc9f34f5a9f756908dbd21db8 (patch)
tree3ee1672fe23989a61dfe491ad580cdd4b2b7a9f3 /src
parent2c644715002516ebe998bd952aa97baf9b80d64f (diff)
downloadpx4-firmware-8de411619a0ce05cc9f34f5a9f756908dbd21db8.tar.gz
px4-firmware-8de411619a0ce05cc9f34f5a9f756908dbd21db8.tar.bz2
px4-firmware-8de411619a0ce05cc9f34f5a9f756908dbd21db8.zip
Initial stab at supporting multiple publications on the same base name and auto-enumeration of additional publications.
Diffstat (limited to 'src')
-rw-r--r--src/drivers/drv_orb_dev.h9
-rw-r--r--src/modules/uORB/Publication.cpp2
-rw-r--r--src/modules/uORB/Publication.hpp2
-rw-r--r--src/modules/uORB/Subscription.cpp2
-rw-r--r--src/modules/uORB/Subscription.hpp2
-rw-r--r--src/modules/uORB/module.mk5
-rw-r--r--src/modules/uORB/objects_common.cpp2
-rw-r--r--src/modules/uORB/uORB.cpp260
-rw-r--r--src/modules/uORB/uORB.h65
9 files changed, 266 insertions, 83 deletions
diff --git a/src/drivers/drv_orb_dev.h b/src/drivers/drv_orb_dev.h
index 713618545..e0b16fa5c 100644
--- a/src/drivers/drv_orb_dev.h
+++ b/src/drivers/drv_orb_dev.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-2015 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
@@ -35,7 +35,9 @@
#define _DRV_UORB_H
/**
- * @file uORB published object driver.
+ * @file drv_orb_dev.h
+ *
+ * uORB published object driver.
*/
#include <sys/types.h>
@@ -84,4 +86,7 @@
/** Get the global advertiser handle for the topic */
#define ORBIOCGADVERTISER _ORBIOC(13)
+/** Get the priority for the topic */
+#define ORBIOCGPRIORITY _ORBIOC(14)
+
#endif /* _DRV_UORB_H */
diff --git a/src/modules/uORB/Publication.cpp b/src/modules/uORB/Publication.cpp
index 71757e1f4..d33f93060 100644
--- a/src/modules/uORB/Publication.cpp
+++ b/src/modules/uORB/Publication.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-2015 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
diff --git a/src/modules/uORB/Publication.hpp b/src/modules/uORB/Publication.hpp
index 8650b3df8..b64559734 100644
--- a/src/modules/uORB/Publication.hpp
+++ b/src/modules/uORB/Publication.hpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-2015 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
diff --git a/src/modules/uORB/Subscription.cpp b/src/modules/uORB/Subscription.cpp
index 44b6debc7..8884e5a3a 100644
--- a/src/modules/uORB/Subscription.cpp
+++ b/src/modules/uORB/Subscription.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-2015 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
diff --git a/src/modules/uORB/Subscription.hpp b/src/modules/uORB/Subscription.hpp
index 34e9a83e0..75cf36254 100644
--- a/src/modules/uORB/Subscription.hpp
+++ b/src/modules/uORB/Subscription.hpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-2015 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
diff --git a/src/modules/uORB/module.mk b/src/modules/uORB/module.mk
index 9385ce253..71ad09130 100644
--- a/src/modules/uORB/module.mk
+++ b/src/modules/uORB/module.mk
@@ -1,6 +1,6 @@
############################################################################
#
-# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+# Copyright (c) 2012-2015 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
@@ -37,8 +37,7 @@
MODULE_COMMAND = uorb
-# XXX probably excessive, 2048 should be sufficient
-MODULE_STACKSIZE = 4096
+MODULE_STACKSIZE = 2048
SRCS = uORB.cpp \
objects_common.cpp \
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index 78fdf4de7..20a9bcc43 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012-2014 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-2015 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
diff --git a/src/modules/uORB/uORB.cpp b/src/modules/uORB/uORB.cpp
index 3373aac83..cfea12f04 100644
--- a/src/modules/uORB/uORB.cpp
+++ b/src/modules/uORB/uORB.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (Cc) 2012-2015 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-2015 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
@@ -51,6 +51,7 @@
#include <stdio.h>
#include <math.h>
#include <unistd.h>
+#include <systemlib/err.h>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
@@ -68,6 +69,7 @@
namespace
{
+/* internal use only */
static const unsigned orb_maxpath = 64;
/* oddly, ERROR is not defined for c++ */
@@ -81,17 +83,30 @@ enum Flavor {
PARAM
};
+struct orb_advertdata {
+ const struct orb_metadata *meta;
+ int *instance;
+ int priority;
+};
+
int
-node_mkpath(char *buf, Flavor f, const struct orb_metadata *meta)
+node_mkpath(char *buf, Flavor f, const struct orb_metadata *meta, int *instance = nullptr)
{
unsigned len;
- len = snprintf(buf, orb_maxpath, "/%s/%s",
- (f == PUBSUB) ? "obj" : "param",
- meta->o_name);
+ unsigned index = 0;
+
+ if (instance != nullptr) {
+ index = *instance;
+ }
+
+ len = snprintf(buf, orb_maxpath, "/%s/%s%d",
+ (f == PUBSUB) ? "obj" : "param",
+ meta->o_name, index);
- if (len >= orb_maxpath)
+ if (len >= orb_maxpath) {
return -ENAMETOOLONG;
+ }
return OK;
}
@@ -104,7 +119,7 @@ node_mkpath(char *buf, Flavor f, const struct orb_metadata *meta)
class ORBDevNode : public device::CDev
{
public:
- ORBDevNode(const struct orb_metadata *meta, const char *name, const char *path);
+ ORBDevNode(const struct orb_metadata *meta, const char *name, const char *path, int priority);
~ORBDevNode();
virtual int open(struct file *filp);
@@ -126,6 +141,7 @@ private:
struct hrt_call update_call; /**< deferred wakeup call if update_period is nonzero */
void *poll_priv; /**< saved copy of fds->f_priv while poll is active */
bool update_reported; /**< true if we have reported the update via poll/check */
+ int priority; /**< priority of publisher */
};
const struct orb_metadata *_meta; /**< object metadata information */
@@ -133,6 +149,7 @@ private:
hrt_abstime _last_update; /**< time the object was last updated */
volatile unsigned _generation; /**< object generation count */
pid_t _publisher; /**< if nonzero, current publisher */
+ const int _priority; /**< priority of topic */
SubscriberData *filp_to_sd(struct file *filp) {
SubscriberData *sd = (SubscriberData *)(filp->f_priv);
@@ -160,13 +177,14 @@ private:
bool appears_updated(SubscriberData *sd);
};
-ORBDevNode::ORBDevNode(const struct orb_metadata *meta, const char *name, const char *path) :
+ORBDevNode::ORBDevNode(const struct orb_metadata *meta, const char *name, const char *path, int priority) :
CDev(name, path),
_meta(meta),
_data(nullptr),
_last_update(0),
_generation(0),
- _publisher(0)
+ _publisher(0),
+ _priority(priority)
{
// enable debug() calls
_debug_enabled = true;
@@ -176,6 +194,7 @@ ORBDevNode::~ORBDevNode()
{
if (_data != nullptr)
delete[] _data;
+
}
int
@@ -225,6 +244,9 @@ ORBDevNode::open(struct file *filp)
/* default to no pending update */
sd->generation = _generation;
+ /* set priority */
+ sd->priority = _priority;
+
filp->f_priv = (void *)sd;
ret = CDev::open(filp);
@@ -283,6 +305,9 @@ ORBDevNode::read(struct file *filp, char *buffer, size_t buflen)
/* track the last generation that the file has seen */
sd->generation = _generation;
+ /* set priority */
+ sd->priority = _priority;
+
/*
* Clear the flag that indicates that an update has been reported, as
* we have just collected it.
@@ -364,6 +389,10 @@ ORBDevNode::ioctl(struct file *filp, int cmd, unsigned long arg)
*(uintptr_t *)arg = (uintptr_t)this;
return OK;
+ case ORBIOCGPRIORITY:
+ *(int *)arg = sd->priority;
+ return OK;
+
default:
/* give it to the superclass */
return CDev::ioctl(filp, cmd, arg);
@@ -556,40 +585,73 @@ ORBDevMaster::ioctl(struct file *filp, int cmd, unsigned long arg)
switch (cmd) {
case ORBIOCADVERTISE: {
- const struct orb_metadata *meta = (const struct orb_metadata *)arg;
+ const struct orb_advertdata *adv = (const struct orb_advertdata *)arg;
+ const struct orb_metadata *meta = adv->meta;
const char *objname;
+ const char *devpath;
char nodepath[orb_maxpath];
ORBDevNode *node;
/* construct a path to the node - this also checks the node name */
- ret = node_mkpath(nodepath, _flavor, meta);
+ ret = node_mkpath(nodepath, _flavor, meta, adv->instance);
- if (ret != OK)
+ if (ret != OK) {
return ret;
+ }
/* driver wants a permanent copy of the node name, so make one here */
objname = strdup(meta->o_name);
- if (objname == nullptr)
+ if (objname == nullptr) {
return -ENOMEM;
+ }
- /* construct the new node */
- node = new ORBDevNode(meta, objname, nodepath);
+ /* ensure that only one advertiser runs through this critical section */
+ lock();
- /* initialise the node - this may fail if e.g. a node with this name already exists */
- if (node != nullptr)
+ ret = ERROR;
+
+ /* try for topic groups */
+ const unsigned max_group_tries = (adv->instance != nullptr) ? ORB_MULTI_MAX_INSTANCES : 1;
+ unsigned group_tries = 0;
+ do {
+ /* if path is modifyable change try index */
+ if (adv->instance != nullptr) {
+ /* replace the number at the end of the string */
+ nodepath[strlen(nodepath) - 1] = '0' + group_tries;
+ *(adv->instance) = group_tries;
+ }
+
+ /* driver wants a permanent copy of the path, so make one here */
+ devpath = strdup(nodepath);
+
+ /* construct the new node */
+ node = new ORBDevNode(meta, objname, devpath, adv->priority);
+
+ /* if we didn't get a device, that's bad */
+ if (node == nullptr) {
+ unlock();
+ return -ENOMEM;
+ }
+
+ /* initialise the node - this may fail if e.g. a node with this name already exists */
ret = node->init();
+
+ /* if init failed, discard the node and its name */
+ if (ret != OK) {
+ delete node;
+ free((void *)objname);
+ }
- /* if we didn't get a device, that's bad */
- if (node == nullptr)
- return -ENOMEM;
+ } while (ret != OK && (group_tries++ < max_group_tries));
- /* if init failed, discard the node and its name */
- if (ret != OK) {
- delete node;
- free((void *)objname);
+ if (group_tries >= max_group_tries) {
+ ret = -ENOMEM;
}
+ /* the file handle for the driver has been created, unlock */
+ unlock();
+
return ret;
}
@@ -614,6 +676,7 @@ struct orb_test {
};
ORB_DEFINE(orb_test, struct orb_test);
+ORB_DEFINE(orb_multitest, struct orb_test);
int
test_fail(const char *fmt, ...)
@@ -643,8 +706,6 @@ test_note(const char *fmt, ...)
return OK;
}
-ORB_DECLARE(sensor_combined);
-
int
test()
{
@@ -700,48 +761,65 @@ test()
orb_unsubscribe(sfd);
close(pfd);
-#if 0
- /* this is a hacky test that exploits the sensors app to test rate-limiting */
+ /* this routine tests the multi-topic support */
+ test_note("try multi-topic support");
- sfd = orb_subscribe(ORB_ID(sensor_combined));
+ int instance0;
+ int pfd0 = orb_advertise_multi(ORB_ID(orb_multitest), &t, &instance0, ORB_PRIO_MAX);
- hrt_abstime start, end;
- unsigned count;
+ test_note("advertised");
+ usleep(300000);
- start = hrt_absolute_time();
- count = 0;
+ int instance1;
+ int pfd1 = orb_advertise_multi(ORB_ID(orb_multitest), &t, &instance1, ORB_PRIO_MIN);
- do {
- orb_check(sfd, &updated);
+ if (instance0 != 0)
+ return test_fail("mult. id0: %d", instance0);
- if (updated) {
- orb_copy(ORB_ID(sensor_combined), sfd, nullptr);
- count++;
- }
- } while (count < 100);
+ if (instance1 != 1)
+ return test_fail("mult. id1: %d", instance1);
- end = hrt_absolute_time();
- test_note("full-speed, 100 updates in %llu", end - start);
+ t.val = 103;
+ if (OK != orb_publish(ORB_ID(orb_multitest), pfd0, &t))
+ return test_fail("mult. pub0 fail");
- orb_set_interval(sfd, 10);
+ test_note("published");
+ usleep(300000);
- start = hrt_absolute_time();
- count = 0;
+ t.val = 203;
+ if (OK != orb_publish(ORB_ID(orb_multitest), pfd1, &t))
+ return test_fail("mult. pub1 fail");
- do {
- orb_check(sfd, &updated);
+ /* subscribe to both topics and ensure valid data is received */
+ int sfd0 = orb_subscribe_multi(ORB_ID(orb_multitest), 0);
- if (updated) {
- orb_copy(ORB_ID(sensor_combined), sfd, nullptr);
- count++;
- }
- } while (count < 100);
+ if (OK != orb_copy(ORB_ID(orb_multitest), sfd0, &t))
+ return test_fail("sub #0 copy failed: %d", errno);
- end = hrt_absolute_time();
- test_note("100Hz, 100 updates in %llu", end - start);
+ if (t.val != 103)
+ return test_fail("sub #0 val. mismatch: %d", t.val);
- orb_unsubscribe(sfd);
-#endif
+ int sfd1 = orb_subscribe_multi(ORB_ID(orb_multitest), 1);
+
+ if (OK != orb_copy(ORB_ID(orb_multitest), sfd1, &t))
+ return test_fail("sub #1 copy failed: %d", errno);
+
+ if (t.val != 203)
+ return test_fail("sub #1 val. mismatch: %d", t.val);
+
+ /* test priorities */
+ int prio;
+ if (OK != orb_priority(sfd0, &prio))
+ return test_fail("prio #0");
+
+ if (prio != ORB_PRIO_MAX)
+ return test_fail("prio: %d", prio);
+
+ if (OK != orb_priority(sfd1, &prio))
+ return test_fail("prio #1");
+
+ if (prio != ORB_PRIO_MIN)
+ return test_fail("prio: %d", prio);
return test_note("PASS");
}
@@ -771,7 +849,7 @@ uorb_main(int argc, char *argv[])
if (!strcmp(argv[1], "start")) {
if (g_dev != nullptr) {
- fprintf(stderr, "[uorb] already loaded\n");
+ warnx("already loaded");
/* user wanted to start uorb, its already running, no error */
return 0;
}
@@ -780,18 +858,17 @@ uorb_main(int argc, char *argv[])
g_dev = new ORBDevMaster(PUBSUB);
if (g_dev == nullptr) {
- fprintf(stderr, "[uorb] driver alloc failed\n");
+ warnx("driver alloc failed");
return -ENOMEM;
}
if (OK != g_dev->init()) {
- fprintf(stderr, "[uorb] driver init failed\n");
+ warnx("driver init failed");
delete g_dev;
g_dev = nullptr;
return -EIO;
}
- printf("[uorb] ready\n");
return OK;
}
@@ -807,8 +884,7 @@ uorb_main(int argc, char *argv[])
if (!strcmp(argv[1], "status"))
return info();
- fprintf(stderr, "unrecognised command, try 'start', 'test' or 'status'\n");
- return -EINVAL;
+ errx(-EINVAL, "unrecognized command, try 'start', 'test' or 'status'");
}
/*
@@ -825,11 +901,14 @@ namespace
* we tried to advertise.
*/
int
-node_advertise(const struct orb_metadata *meta)
+node_advertise(const struct orb_metadata *meta, int *instance = nullptr, int priority = ORB_PRIO_DEFAULT)
{
int fd = -1;
int ret = ERROR;
+ /* fill advertiser data */
+ const struct orb_advertdata adv = { meta, instance, priority };
+
/* open the control device */
fd = open(TOPIC_MASTER_DEVICE_PATH, 0);
@@ -837,11 +916,12 @@ node_advertise(const struct orb_metadata *meta)
goto out;
/* advertise the object */
- ret = ioctl(fd, ORBIOCADVERTISE, (unsigned long)(uintptr_t)meta);
+ ret = ioctl(fd, ORBIOCADVERTISE, (unsigned long)(uintptr_t)&adv);
/* it's OK if it already exists */
- if ((OK != ret) && (EEXIST == errno))
+ if ((OK != ret) && (EEXIST == errno)) {
ret = OK;
+ }
out:
@@ -858,7 +938,7 @@ out:
* advertisers.
*/
int
-node_open(Flavor f, const struct orb_metadata *meta, const void *data, bool advertiser)
+node_open(Flavor f, const struct orb_metadata *meta, const void *data, bool advertiser, int *instance = nullptr, int priority = ORB_PRIO_DEFAULT)
{
char path[orb_maxpath];
int fd, ret;
@@ -883,7 +963,7 @@ node_open(Flavor f, const struct orb_metadata *meta, const void *data, bool adve
/*
* Generate the path to the node and try to open it.
*/
- ret = node_mkpath(path, f, meta);
+ ret = node_mkpath(path, f, meta, instance);
if (ret != OK) {
errno = -ret;
@@ -893,15 +973,34 @@ node_open(Flavor f, const struct orb_metadata *meta, const void *data, bool adve
/* open the path as either the advertiser or the subscriber */
fd = open(path, (advertiser) ? O_WRONLY : O_RDONLY);
+ /* if we want to advertise and the node existed, we have to re-try again */
+ if ((fd >= 0) && (instance != nullptr) && (advertiser)) {
+ /* close the fd, we want a new one */
+ close(fd);
+ /* the node_advertise call will automatically go for the next free entry */
+ fd = -1;
+ }
+
/* we may need to advertise the node... */
if (fd < 0) {
/* try to create the node */
- ret = node_advertise(meta);
+ ret = node_advertise(meta, instance, priority);
+
+ if (ret == OK) {
+ /* update the path, as it might have been updated during the node_advertise call */
+ ret = node_mkpath(path, f, meta, instance);
+
+ if (ret != OK) {
+ errno = -ret;
+ return ERROR;
+ }
+ }
/* on success, try the open again */
- if (ret == OK)
+ if (ret == OK) {
fd = open(path, (advertiser) ? O_WRONLY : O_RDONLY);
+ }
}
if (fd < 0) {
@@ -918,11 +1017,17 @@ node_open(Flavor f, const struct orb_metadata *meta, const void *data, bool adve
orb_advert_t
orb_advertise(const struct orb_metadata *meta, const void *data)
{
+ return orb_advertise_multi(meta, data, nullptr, ORB_PRIO_DEFAULT);
+}
+
+orb_advert_t
+orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance, int priority)
+{
int result, fd;
orb_advert_t advertiser;
/* open the node as an advertiser */
- fd = node_open(PUBSUB, meta, data, true);
+ fd = node_open(PUBSUB, meta, data, true, instance, priority);
if (fd == ERROR)
return ERROR;
@@ -933,7 +1038,7 @@ orb_advertise(const struct orb_metadata *meta, const void *data)
return ERROR;
/* the advertiser must perform an initial publish to initialise the object */
- result= orb_publish(meta, advertiser, data);
+ result = orb_publish(meta, advertiser, data);
if (result == ERROR)
return ERROR;
@@ -947,6 +1052,13 @@ orb_subscribe(const struct orb_metadata *meta)
}
int
+orb_subscribe_multi(const struct orb_metadata *meta, unsigned instance)
+{
+ int inst = instance;
+ return node_open(PUBSUB, meta, nullptr, false, &inst);
+}
+
+int
orb_unsubscribe(int handle)
{
return close(handle);
@@ -989,6 +1101,12 @@ orb_stat(int handle, uint64_t *time)
}
int
+orb_priority(int handle, int *priority)
+{
+ return ioctl(handle, ORBIOCGPRIORITY, (unsigned long)(uintptr_t)priority);
+}
+
+int
orb_set_interval(int handle, unsigned interval)
{
return ioctl(handle, ORBIOCSETINTERVAL, interval * 1000);
diff --git a/src/modules/uORB/uORB.h b/src/modules/uORB/uORB.h
index beb23f61d..a0ad75273 100644
--- a/src/modules/uORB/uORB.h
+++ b/src/modules/uORB/uORB.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-2015 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
@@ -57,6 +57,25 @@ struct orb_metadata {
typedef const struct orb_metadata *orb_id_t;
/**
+ * Maximum number of multi topic instances
+ */
+#define ORB_MULTI_MAX_INSTANCES 4
+
+/**
+ * Topic priority.
+ * Relevant for multi-topics / topic groups
+ */
+enum ORB_PRIO {
+ ORB_PRIO_MIN = 0,
+ ORB_PRIO_VERY_LOW = 25,
+ ORB_PRIO_LOW = 50,
+ ORB_PRIO_DEFAULT = 75,
+ ORB_PRIO_HIGH = 100,
+ ORB_PRIO_VERY_HIGH = 125,
+ ORB_PRIO_MAX = 255
+};
+
+/**
* Generates a pointer to the uORB metadata structure for
* a given topic.
*
@@ -128,7 +147,7 @@ typedef const struct orb_metadata *orb_id_t;
#define ORB_DEFINE(_name, _struct) \
const struct orb_metadata __orb_##_name = { \
#_name, \
- sizeof(_struct) \
+ sizeof(_struct), \
}; struct hack
__BEGIN_DECLS
@@ -168,6 +187,34 @@ typedef intptr_t orb_advert_t;
extern orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data) __EXPORT;
/**
+ * 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.
+ * For topics updated by interrupt handlers, the advertisement
+ * must be performed from non-interrupt context.
+ * @param instance Pointer to an integer which will yield the instance ID (0-based)
+ * of the publication.
+ * @param priority The priority of the instance. If a subscriber subscribes multiple
+ * instances, the priority allows the subscriber to prioritize the best
+ * data source as long as its available.
+ * @return ERROR on error, otherwise returns a handle
+ * that can be used to publish to the topic.
+ * If the topic in question is not known (due to an
+ * ORB_DEFINE with no corresponding ORB_DECLARE)
+ * this function will return -1 and set errno to ENOENT.
+ */
+extern orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance, int priority) __EXPORT;
+
+
+/**
* Publish new data to a topic.
*
* The data is atomically published to the topic and any waiting subscribers
@@ -210,6 +257,8 @@ extern int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, con
*/
extern int orb_subscribe(const struct orb_metadata *meta) __EXPORT;
+extern int orb_subscribe_multi(const struct orb_metadata *meta, unsigned instance) __EXPORT;
+
/**
* Unsubscribe from a topic.
*
@@ -267,6 +316,18 @@ extern int orb_check(int handle, bool *updated) __EXPORT;
extern int orb_stat(int handle, uint64_t *time) __EXPORT;
/**
+ * Return the priority of the topic
+ *
+ * @param handle A handle returned from orb_subscribe.
+ * @param priority Returns the priority of this topic. This is only relevant for
+ * topics which are published by multiple publishers (e.g. mag0, mag1, etc.)
+ * and allows a subscriber to automatically pick the topic with the highest
+ * priority, independent of the startup order of the associated publishers.
+ * @return OK on success, ERROR otherwise with errno set accordingly.
+ */
+extern int orb_priority(int handle, int *priority) __EXPORT;
+
+/**
* Set the minimum interval between which updates are seen for a subscription.
*
* If this interval is set, the subscriber will not see more than one update