PX4 Firmware
PX4 Autopilot Software http://px4.io
uORB::Manager Class Reference

This is implemented as a singleton. More...

#include <uORBManager.hpp>

Collaboration diagram for uORB::Manager:

Public Member Functions

uORB::DeviceMasterget_device_master ()
 Get the DeviceMaster. More...
 
orb_advert_t orb_advertise (const struct orb_metadata *meta, const void *data, unsigned int queue_size=1)
 Advertise as the publisher of a topic. More...
 
orb_advert_t orb_advertise_multi (const struct orb_metadata *meta, const void *data, int *instance, int priority, unsigned int queue_size=1)
 Advertise as the publisher of a topic. More...
 
int orb_unadvertise (orb_advert_t handle)
 Unadvertise a topic. More...
 
int orb_publish (const struct orb_metadata *meta, orb_advert_t handle, const void *data)
 Publish new data to a topic. More...
 
int orb_subscribe (const struct orb_metadata *meta)
 Subscribe to a topic. More...
 
int orb_subscribe_multi (const struct orb_metadata *meta, unsigned instance)
 Subscribe to a multi-instance of a topic. More...
 
int orb_unsubscribe (int handle)
 Unsubscribe from a topic. More...
 
int orb_copy (const struct orb_metadata *meta, int handle, void *buffer)
 Fetch data from a topic. More...
 
int orb_check (int handle, bool *updated)
 Check whether a topic has been published to since the last orb_copy. More...
 
int orb_stat (int handle, uint64_t *time)
 Return the last time that the topic was updated. More...
 
int orb_exists (const struct orb_metadata *meta, int instance)
 Check if a topic has already been created and published (advertised) More...
 
int orb_priority (int handle, int32_t *priority)
 Return the priority of the topic. More...
 
int orb_set_interval (int handle, unsigned interval)
 Set the minimum interval between which updates are seen for a subscription. More...
 
int orb_get_interval (int handle, unsigned *interval)
 Get the minimum interval between which updates are seen for a subscription. More...
 

Static Public Member Functions

static bool initialize ()
 Initialize the singleton. More...
 
static bool terminate ()
 Terminate the singleton. More...
 
static uORB::Managerget_instance ()
 Method to get the singleton instance for the uORB::Manager. More...
 

Private Member Functions

int node_advertise (const struct orb_metadata *meta, bool is_advertiser, int *instance=nullptr, int priority=ORB_PRIO_DEFAULT)
 Advertise a node; don't consider it an error if the node has already been advertised. More...
 
int node_open (const struct orb_metadata *meta, bool advertiser, int *instance=nullptr, int priority=ORB_PRIO_DEFAULT)
 Common implementation for orb_advertise and orb_subscribe. More...
 
 Manager ()
 
virtual ~Manager ()
 

Private Attributes

DeviceMaster_device_master {nullptr}
 

Static Private Attributes

static Manager_Instance = nullptr
 

Detailed Description

This is implemented as a singleton.

This class manages creating the uORB nodes for each uORB topics and also implements the behavor of the uORB Api's.

Definition at line 64 of file uORBManager.hpp.

Constructor & Destructor Documentation

◆ Manager()

uORB::Manager::Manager ( )
private

Definition at line 69 of file uORBManager.cpp.

◆ ~Manager()

uORB::Manager::~Manager ( )
privatevirtual

Definition at line 87 of file uORBManager.cpp.

References _device_master.

Member Function Documentation

◆ get_device_master()

uORB::DeviceMaster * uORB::Manager::get_device_master ( )

Get the DeviceMaster.

If it does not exist, it will be created and initialized. Note: the first call to this is not thread-safe.

Returns
nullptr if initialization failed (and errno will be set)

Definition at line 92 of file uORBManager.cpp.

References _device_master.

Referenced by get_instance(), node_advertise(), node_open(), orb_exists(), uORB::Subscription::subscribe(), and uorb_main().

Here is the caller graph for this function:

◆ get_instance()

static uORB::Manager* uORB::Manager::get_instance ( )
inlinestatic

Method to get the singleton instance for the uORB::Manager.

Make sure initialize() is called first.

Returns
uORB::Manager*

Definition at line 89 of file uORBManager.hpp.

References _Instance, and get_device_master().

Referenced by uORB::DeviceNode::add_internal_subscriber(), muorb_main(), orb_advertise(), orb_advertise_multi(), orb_advertise_multi_queue(), orb_advertise_queue(), orb_check(), orb_copy(), orb_exists(), orb_get_interval(), orb_group_count(), orb_priority(), orb_publish(), orb_set_interval(), orb_stat(), orb_subscribe(), orb_subscribe_multi(), orb_unadvertise(), orb_unsubscribe(), uORB::DeviceNode::publish(), px4muorb_orb_initialize(), uORB::DeviceNode::remove_internal_subscriber(), uORB::Subscription::subscribe(), uORB::DeviceNode::unadvertise(), and uorb_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ initialize()

bool uORB::Manager::initialize ( )
static

Initialize the singleton.

Call this before everything else.

Returns
true on success

Definition at line 49 of file uORBManager.cpp.

References _Instance.

Referenced by px4muorb_orb_initialize(), and uorb_main().

Here is the caller graph for this function:

◆ node_advertise()

int uORB::Manager::node_advertise ( const struct orb_metadata meta,
bool  is_advertiser,
int *  instance = nullptr,
int  priority = ORB_PRIO_DEFAULT 
)
private

Advertise a node; don't consider it an error if the node has already been advertised.

Definition at line 330 of file uORBManager.cpp.

References _device_master, uORB::DeviceMaster::advertise(), and get_device_master().

Referenced by node_open(), and orb_advertise().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ node_open()

int uORB::Manager::node_open ( const struct orb_metadata meta,
bool  advertiser,
int *  instance = nullptr,
int  priority = ORB_PRIO_DEFAULT 
)
private

Common implementation for orb_advertise and orb_subscribe.

Handles creation of the object and the initial publication for advertisers.

Definition at line 346 of file uORBManager.cpp.

References data, fd, get_device_master(), uORB::DeviceMaster::getDeviceNode(), node_advertise(), uORB::Utils::node_mkpath(), OK, uORB::orb_maxpath, px4_open(), uORBCommunicator::IChannel::register_handler(), and start().

Referenced by orb_advertise(), orb_advertise_multi(), orb_subscribe(), and orb_subscribe_multi().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ orb_advertise()

orb_advert_t uORB::Manager::orb_advertise ( const struct orb_metadata meta,
const void *  data,
unsigned int  queue_size = 1 
)
inline

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.

Internally this will call orb_advertise_multi with an instance of 0 and default priority.

Parameters
metaThe uORB metadata (usually from the ORB_ID() macro) for the topic.
dataA pointer to the initial data to be published. For topics updated by interrupt handlers, the advertisement must be performed from non-interrupt context.
queue_sizeMaximum number of buffered elements. If this is 1, no queuing is used.
Returns
nullptr on error, otherwise returns an object pointer 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 nullptr and set errno to ENOENT.

Definition at line 125 of file uORBManager.hpp.

References data, ll40ls::instance, node_advertise(), node_open(), orb_advert_t, orb_advertise_multi(), orb_check(), orb_copy(), orb_exists(), orb_get_interval(), ORB_PRIO_DEFAULT, orb_priority(), orb_publish(), orb_set_interval(), orb_stat(), orb_subscribe(), orb_subscribe_multi(), orb_unadvertise(), and orb_unsubscribe().

Referenced by orb_advertise(), and orb_advertise_queue().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ orb_advertise_multi()

orb_advert_t uORB::Manager::orb_advertise_multi ( const struct orb_metadata meta,
const void *  data,
int *  instance,
int  priority,
unsigned int  queue_size = 1 
)

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.

The multi can be used to create multiple independent instances of the same topic (each instance has its own buffer). This is useful for multiple publishers who publish the same topic. The subscriber then subscribes to all instances and chooses which source he wants to use.

Parameters
metaThe uORB metadata (usually from the ORB_ID() macro) for the topic.
dataA pointer to the initial data to be published. For topics updated by interrupt handlers, the advertisement must be performed from non-interrupt context.
instancePointer to an integer which will yield the instance ID (0-based) of the publication. This is an output parameter and will be set to the newly created instance, ie. 0 for the first advertiser, 1 for the next and so on.
priorityThe 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. The subscriber is responsible to check and handle different priorities (
See also
orb_priority()).
Parameters
queue_sizeMaximum number of buffered elements. If this is 1, no queuing is used.
Returns
PX4_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.

Definition at line 170 of file uORBManager.cpp.

References _Instance, fd, node_open(), orb_metadata::o_name, orb_advert_t, orb_publish(), ORBIOCGADVERTISER, ORBIOCSETQUEUESIZE, px4_close(), and px4_ioctl().

Referenced by orb_advertise(), orb_advertise_multi(), and orb_advertise_multi_queue().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ orb_check()

int uORB::Manager::orb_check ( int  handle,
bool *  updated 
)

Check whether a topic has been published to since the last orb_copy.

This check can be used to determine whether to copy the topic when not using poll(), or to avoid the overhead of calling poll() when the topic is likely to have updated.

Updates are tracked on a per-handle basis; this call will continue to return true until orb_copy is called using the same handle. This interface should be preferred over calling orb_stat due to the race window between stat and copy that can lead to missed updates.

Parameters
handleA handle returned from orb_subscribe.
updatedSet to true if the topic has been updated since the last time it was copied using this handle.
Returns
OK if the check was successful, PX4_ERROR otherwise with errno set accordingly.

Definition at line 301 of file uORBManager.cpp.

References ORBIOCUPDATED, and px4_ioctl().

Referenced by orb_advertise(), and orb_check().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ orb_copy()

int uORB::Manager::orb_copy ( const struct orb_metadata meta,
int  handle,
void *  buffer 
)

Fetch data from a topic.

This is the only operation that will reset the internal marker that indicates that a topic has been updated for a subscriber. Once poll or check return indicating that an updaet is available, this call must be used to update the subscription.

Parameters
metaThe uORB metadata (usually from the ORB_ID() macro) for the topic.
handleA handle returned from orb_subscribe.
bufferPointer to the buffer receiving the data, or NULL if the caller wants to clear the updated flag without using the data.
Returns
OK on success, PX4_ERROR otherwise with errno set accordingly.

Definition at line 283 of file uORBManager.cpp.

References orb_metadata::o_size, and px4_read().

Referenced by orb_advertise(), and orb_copy().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ orb_exists()

int uORB::Manager::orb_exists ( const struct orb_metadata meta,
int  instance 
)

Check if a topic has already been created and published (advertised)

Parameters
metaORB topic metadata.
instanceORB instance
Returns
OK if the topic exists, PX4_ERROR otherwise.

Definition at line 106 of file uORBManager.cpp.

References _device_master, fd, get_device_master(), uORB::DeviceMaster::getDeviceNode(), ll40ls::instance, uORB::DeviceNode::is_advertised(), uORB::Utils::node_mkpath(), orb_metadata::o_name, OK, uORB::orb_maxpath, ORB_MULTI_MAX_INSTANCES, ORBIOCISADVERTISED, px4_access(), px4_close(), px4_ioctl(), and px4_open().

Referenced by orb_advertise(), and orb_exists().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ orb_get_interval()

int uORB::Manager::orb_get_interval ( int  handle,
unsigned *  interval 
)

Get the minimum interval between which updates are seen for a subscription.

See also
orb_set_interval()
Parameters
handleA handle returned from orb_subscribe.
intervalThe returned interval period in milliseconds.
Returns
OK on success, PX4_ERROR otherwise with ERRNO set accordingly.

Definition at line 323 of file uORBManager.cpp.

References ORBIOCGETINTERVAL, and px4_ioctl().

Referenced by orb_advertise(), and orb_get_interval().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ orb_priority()

int uORB::Manager::orb_priority ( int  handle,
int32_t *  priority 
)

Return the priority of the topic.

Parameters
handleA handle returned from orb_subscribe.
priorityReturns 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 pick the topic with the highest priority, independent of the startup order of the associated publishers.
Returns
OK on success, PX4_ERROR otherwise with errno set accordingly.

Definition at line 313 of file uORBManager.cpp.

References ORBIOCGPRIORITY, and px4_ioctl().

Referenced by orb_advertise(), and orb_priority().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ orb_publish()

int uORB::Manager::orb_publish ( const struct orb_metadata meta,
orb_advert_t  handle,
const void *  data 
)

Publish new data to a topic.

The data is atomically published to the topic and any waiting subscribers will be notified. Subscribers that are not waiting can check the topic for updates using orb_check and/or orb_stat.

Parameters
metaThe uORB metadata (usually from the ORB_ID() macro) for the topic. The handle returned from orb_advertise.
dataA pointer to the data to be published.
Returns
OK on success, PX4_ERROR otherwise with errno set accordingly.

Definition at line 270 of file uORBManager.cpp.

References _Instance, and uORB::DeviceNode::publish().

Referenced by orb_advertise(), orb_advertise_multi(), and orb_publish().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ orb_set_interval()

int uORB::Manager::orb_set_interval ( int  handle,
unsigned  interval 
)

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 within the period.

Specifically, the first time an update is reported to the subscriber a timer is started. The update will continue to be reported via poll and orb_check, but once fetched via orb_copy another update will not be reported until the timer expires.

This feature can be used to pace a subscriber that is watching a topic that would otherwise update too quickly.

Parameters
handleA handle returned from orb_subscribe.
intervalAn interval period in milliseconds.
Returns
OK on success, PX4_ERROR otherwise with ERRNO set accordingly.

Definition at line 318 of file uORBManager.cpp.

References ORBIOCSETINTERVAL, and px4_ioctl().

Referenced by orb_advertise(), and orb_set_interval().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ orb_stat()

int uORB::Manager::orb_stat ( int  handle,
uint64_t *  time 
)

Return the last time that the topic was updated.

If a queue is used, it returns the timestamp of the latest element in the queue.

Parameters
handleA handle returned from orb_subscribe.
timeReturns the absolute time that the topic was updated, or zero if it has never been updated. Time is measured in microseconds.
Returns
OK on success, PX4_ERROR otherwise with errno set accordingly.

Definition at line 308 of file uORBManager.cpp.

References ORBIOCLASTUPDATE, and px4_ioctl().

Referenced by orb_advertise(), and orb_stat().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ orb_subscribe()

int uORB::Manager::orb_subscribe ( const struct orb_metadata meta)

Subscribe to a topic.

The returned value is a file descriptor that can be passed to poll() in order to wait for updates to a topic, as well as topic_read, orb_check and orb_stat.

If there were any publications of the topic prior to the subscription, an orb_check right after orb_subscribe will return true.

Subscription will succeed even if the topic has not been advertised; in this case the topic will have a timestamp of zero, it will never signal a poll() event, checking will always return false and it cannot be copied. When the topic is subsequently advertised, poll, check, stat and copy calls will react to the initial publication that is performed as part of the advertisement.

Subscription will fail if the topic is not known to the system, i.e. there is nothing in the system that has declared the topic and thus it can never be published.

Internally this will call orb_subscribe_multi with instance 0.

Parameters
metaThe uORB metadata (usually from the ORB_ID() macro) for the topic.
Returns
PX4_ERROR on error, otherwise returns a handle that can be used to read and update the topic.

Definition at line 254 of file uORBManager.cpp.

References node_open().

Referenced by orb_advertise(), and orb_subscribe().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ orb_subscribe_multi()

int uORB::Manager::orb_subscribe_multi ( const struct orb_metadata meta,
unsigned  instance 
)

Subscribe to a multi-instance of a topic.

The returned value is a file descriptor that can be passed to poll() in order to wait for updates to a topic, as well as topic_read, orb_check and orb_stat.

If there were any publications of the topic prior to the subscription, an orb_check right after orb_subscribe_multi will return true.

Subscription will succeed even if the topic has not been advertised; in this case the topic will have a timestamp of zero, it will never signal a poll() event, checking will always return false and it cannot be copied. When the topic is subsequently advertised, poll, check, stat and copy calls will react to the initial publication that is performed as part of the advertisement.

Subscription will fail if the topic is not known to the system, i.e. there is nothing in the system that has declared the topic and thus it can never be published.

If a publisher publishes multiple instances the subscriber should subscribe to each instance with orb_subscribe_multi (

See also
orb_advertise_multi()).
Parameters
metaThe uORB metadata (usually from the ORB_ID() macro) for the topic.
instanceThe instance of the topic. Instance 0 matches the topic of the orb_subscribe() call, higher indices are for topics created with orb_advertise_multi().
Returns
PX4_ERROR on error, otherwise returns a handle that can be used to read and update the topic. If the topic in question is not known (due to an ORB_DEFINE_OPTIONAL with no corresponding ORB_DECLARE) this function will return -1 and set errno to ENOENT.

Definition at line 259 of file uORBManager.cpp.

References ll40ls::instance, and node_open().

Referenced by orb_advertise(), and orb_subscribe_multi().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ orb_unadvertise()

int uORB::Manager::orb_unadvertise ( orb_advert_t  handle)

Unadvertise a topic.

Parameters
handlehandle returned by orb_advertise or orb_advertise_multi.
Returns
0 on success

Definition at line 241 of file uORBManager.cpp.

References _Instance, and uORB::DeviceNode::unadvertise().

Referenced by orb_advertise(), and orb_unadvertise().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ orb_unsubscribe()

int uORB::Manager::orb_unsubscribe ( int  handle)

Unsubscribe from a topic.

Parameters
handleA handle returned from orb_subscribe.
Returns
OK on success, PX4_ERROR otherwise with errno set accordingly.

Definition at line 265 of file uORBManager.cpp.

References px4_close().

Referenced by orb_advertise(), and orb_unsubscribe().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ terminate()

bool uORB::Manager::terminate ( )
static

Terminate the singleton.

Call this after everything else.

Returns
true on success

Definition at line 58 of file uORBManager.cpp.

References _Instance.

Member Data Documentation

◆ _device_master

DeviceMaster* uORB::Manager::_device_master {nullptr}
private

Definition at line 419 of file uORBManager.hpp.

Referenced by get_device_master(), node_advertise(), orb_exists(), and ~Manager().

◆ _Instance

uORB::Manager * uORB::Manager::_Instance = nullptr
staticprivate

The documentation for this class was generated from the following files: