40 #include <px4_platform_common/log.h> 41 #include <px4_platform_common/module.h> 48 PRINT_MODULE_DESCRIPTION(
51 uORB is the internal pub-sub messaging system, used for communication between modules. 53 It is typically started as one of the very first modules and most other modules depend on it. 56 No thread or work queue is needed, the module start only makes sure to initialize the shared global state. 57 Communication is done via shared memory. 58 The implementation is asynchronous and lock-free, ie. a publisher does not wait for a subscriber and vice versa. 59 This is achieved by having a separate buffer between a publisher and a subscriber. 61 The code is optimized to minimize the memory footprint and the latency to exchange messages. 63 The interface is based on file descriptors: internally it uses `read`, `write` and `ioctl`. Except for the 64 publications, which use `orb_advert_t` handles, so that they can be used from interrupts as well (on NuttX). 66 Messages are defined in the `/msg` directory. They are converted into C/C++ code at build-time. 68 If compiled with ORB_USE_PUBLISHER_RULES, a file with uORB publication rules can be used to configure which 69 modules are allowed to publish which topics. This is used for system-wide replay. 72 Monitor topic publication rates. Besides `top`, this is an important command for general system inspection: 76 PRINT_MODULE_USAGE_NAME("uorb",
"communication");
77 PRINT_MODULE_USAGE_COMMAND(
"start");
78 PRINT_MODULE_USAGE_COMMAND_DESCR(
"status",
"Print topic statistics");
79 PRINT_MODULE_USAGE_COMMAND_DESCR(
"top",
"Monitor topic publication rates");
80 PRINT_MODULE_USAGE_PARAM_FLAG(
'a',
"print all instead of only currently publishing topics",
true);
81 PRINT_MODULE_USAGE_PARAM_FLAG(
'1',
"run only once, then exit",
true);
82 PRINT_MODULE_USAGE_ARG(
"<filter1> [<filter2>]",
"topic(s) to match (implies -a)",
true);
96 if (!strcmp(argv[1],
"start")) {
98 if (g_dev !=
nullptr) {
99 PX4_WARN(
"already loaded");
105 PX4_ERR(
"uorb manager alloc failed");
112 if (g_dev ==
nullptr) {
116 #if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_EXCELSIOR) 120 px4_log_initialize();
129 if (!strcmp(argv[1],
"status")) {
130 if (g_dev !=
nullptr) {
134 PX4_INFO(
"uorb is not running");
140 if (!strcmp(argv[1],
"top")) {
141 if (g_dev !=
nullptr) {
142 g_dev->
showTop(argv + 2, argc - 2);
145 PX4_INFO(
"uorb is not running");
static uORB::Manager * get_instance()
Method to get the singleton instance for the uORB::Manager.
API for the uORB lightweight object broker.
uORB::DeviceMaster * get_device_master()
Get the DeviceMaster.
static uORB::DeviceMaster * g_dev
static bool initialize()
Initialize the singleton.
__EXPORT int uorb_main(int argc, char *argv[])
void showTop(char **topic_filter, int num_filters)
Continuously print statistics, like the unix top command for processes.
Master control device for ObjDev.
void printStatistics(bool reset)
Print statistics for each existing topic.