PX4 Firmware
PX4 Autopilot Software http://px4.io
uORB.cpp File Reference

A lightweight object broker. More...

#include "uORB.h"
#include "uORBManager.hpp"
#include "uORBCommon.hpp"
Include dependency graph for uORB.cpp:

Go to the source code of this file.

Functions

orb_advert_t orb_advertise (const struct orb_metadata *meta, const void *data)
 
orb_advert_t orb_advertise_queue (const struct orb_metadata *meta, const void *data, unsigned int queue_size)
 
orb_advert_t orb_advertise_multi (const struct orb_metadata *meta, const void *data, int *instance, int priority)
 
orb_advert_t orb_advertise_multi_queue (const struct orb_metadata *meta, const void *data, int *instance, int priority, unsigned int queue_size)
 
int orb_unadvertise (orb_advert_t handle)
 
int orb_publish (const struct orb_metadata *meta, orb_advert_t handle, const void *data)
 
int orb_subscribe (const struct orb_metadata *meta)
 
int orb_subscribe_multi (const struct orb_metadata *meta, unsigned instance)
 
int orb_unsubscribe (int handle)
 
int orb_copy (const struct orb_metadata *meta, int handle, void *buffer)
 
int orb_check (int handle, bool *updated)
 
int orb_stat (int handle, uint64_t *time)
 
int orb_exists (const struct orb_metadata *meta, int instance)
 
int orb_group_count (const struct orb_metadata *meta)
 Get the number of published instances of a topic group. More...
 
int orb_priority (int handle, int32_t *priority)
 
int orb_set_interval (int handle, unsigned interval)
 
int orb_get_interval (int handle, unsigned *interval)
 

Detailed Description

A lightweight object broker.

Definition in file uORB.cpp.

Function Documentation

◆ orb_advertise()

◆ orb_advertise_multi()

orb_advert_t orb_advertise_multi ( const struct orb_metadata meta,
const void *  data,
int *  instance,
int  priority 
)
See also
uORB::Manager::orb_advertise_multi()

Definition at line 53 of file uORB.cpp.

References uORB::Manager::get_instance(), and uORB::Manager::orb_advertise_multi().

Referenced by rpi_rc_in::RcInput::_measure(), DfMS5607Wrapper::_publish(), DfMS5611Wrapper::_publish(), DfBmp280Wrapper::_publish(), DfBebopRangeFinderWrapper::_publish(), DfTROneWrapper::_publish(), DfAK8963Wrapper::_publish(), DfHmc5883Wrapper::_publish(), DfISL29501Wrapper::_publish(), DfMPU6050Wrapper::_publish(), DfBebopBusWrapper::_publish(), DfMpu9250Wrapper::_publish(), LSM303AGR::collect(), LPS22HB::collect(), RM3100::collect(), LIS3MDL::collect(), LPS25H::collect(), QMC5883::collect(), HMC5883::collect(), IST8310::collect(), mpu9x50::create_pubs(), Airspeed::init(), MPL3115A2::init(), PX4FLOW::init(), SF0X::init(), SF1XX::init(), SRF02::init(), VL53LXX::init(), MS5611::init(), Radar::init(), BMM150::init(), orb_publish_auto(), uORBTest::UnitTest::pub_test_multi2_main(), uORB::PublicationMulti< rate_ctrl_status_s >::publish(), UavcanCDevSensorBridgeBase::publish(), px4::Replay::publishTopic(), IRLOCK::read_device(), DfLsm9ds1Wrapper::start(), DfMpu9250Wrapper::start(), MK::task_main(), RoboClaw::taskMain(), uORBTest::UnitTest::test_multi(), uORBTest::UnitTest::test_multi_reversed(), and uORBTest::UnitTest::test_unadvertise().

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

◆ orb_advertise_multi_queue()

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

Definition at line 59 of file uORB.cpp.

References uORB::Manager::get_instance(), and uORB::Manager::orb_advertise_multi().

Here is the call graph for this function:

◆ orb_advertise_queue()

orb_advert_t orb_advertise_queue ( const struct orb_metadata meta,
const void *  data,
unsigned int  queue_size 
)
See also
uORB::Manager::orb_advertise()

Definition at line 48 of file uORB.cpp.

References uORB::Manager::get_instance(), and uORB::Manager::orb_advertise().

Referenced by buzzer_init(), led_init(), mavlink_vasprintf(), events::rc_loss::RC_Loss_Alarm::play_tune(), uORBTest::UnitTest::pub_test_queue_main(), uORB::PublicationQueued< vehicle_command_s >::publish(), publish_tune_control(), events::rc_loss::RC_Loss_Alarm::stop_tune(), MK::task_main(), uORBTest::UnitTest::test_queue(), and test_tone().

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

◆ orb_check()

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

Definition at line 95 of file uORB.cpp.

References uORB::Manager::get_instance(), and uORB::Manager::orb_check().

Referenced by vmount::OutputBase::_handle_position_update(), DfAK8963Wrapper::_publish(), DfHmc5883Wrapper::_publish(), DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfMpu9250Wrapper::_publish(), QShell::_wait_for_retval(), sensors::VotedSensorsUpdate::accelPoll(), arm_auth_update(), RoverPositionControl::attitude_setpoint_poll(), sensors::VotedSensorsUpdate::baroPoll(), build_gps_response(), calibrate_cancel_subscribe(), events::SubscriberHandler::check_for_updates(), TAP_ESC::cycle(), esc_calib_main(), frsky_telemetry_thread_main(), gyro_calibration_worker(), sensors::VotedSensorsUpdate::gyroPoll(), PX4IO::io_set_control_state(), sensors::VotedSensorsUpdate::magPoll(), RoverPositionControl::manual_control_setpoint_poll(), nshterm_main(), orb_publish_auto(), rc_receiver::parameter_update_poll(), mpu9x50::parameter_update_poll(), MuorbTestExample::PingPongTest(), Simulator::poll_topics(), RoverPositionControl::position_setpoint_triplet_poll(), prepare(), read_accelerometer_avg(), Sih::read_motors(), PCA9685::Run(), Simulator::send_controls(), CameraFeedback::task_main(), uart_esc::task_main(), linux_pwm_out::task_main(), snapdragon_pwm::task_main(), MK::task_main(), df_bebop_bus_wrapper::task_main(), uORBTest::UnitTest::test_multi2(), test_ppm_loopback(), uORBTest::UnitTest::test_queue(), test_rc(), uORBTest::UnitTest::test_single(), TemperatureCalibrationAccel::update_sensor_instance(), TemperatureCalibrationGyro::update_sensor_instance(), TemperatureCalibrationBaro::update_sensor_instance(), MicroBenchORB::ut_declare_test_c(), RoverPositionControl::vehicle_attitude_poll(), RoverPositionControl::vehicle_control_mode_poll(), and MEASAirspeed::voltage_correction().

Here is the call graph for this function:

◆ orb_copy()

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

Definition at line 90 of file uORB.cpp.

References uORB::Manager::get_instance(), and uORB::Manager::orb_copy().

Referenced by vmount::OutputBase::_calculate_output_angles(), vmount::OutputBase::_handle_position_update(), DfLtc2946Wrapper::_publish(), DfHmc5883Wrapper::_publish(), DfAK8963Wrapper::_publish(), DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfMpu9250Wrapper::_publish(), vmount::InputMavlinkROI::_read_control_data_from_position_setpoint_sub(), vmount::InputRC::_read_control_data_from_subscription(), QShell::_wait_for_retval(), sensors::VotedSensorsUpdate::accelPoll(), arm_auth_update(), RoverPositionControl::attitude_setpoint_poll(), sensors::VotedSensorsUpdate::baroPoll(), build_eam_response(), build_gam_response(), build_gps_response(), calibrate_cancel_check(), calibrate_cancel_subscribe(), events::rc_loss::RC_Loss_Alarm::check_for_updates(), events::status::StatusDisplay::check_for_updates(), commander_low_prio_loop(), TAP_ESC::cycle(), detect_orientation(), do_accel_calibration_measurements(), do_airspeed_calibration(), do_gyro_calibration(), do_level_calibration(), esc_calib_main(), frsky_telemetry_thread_main(), gyro_calibration_worker(), sensors::VotedSensorsUpdate::gyroPoll(), px4::ReplayEkf2::handleTopicUpdate(), PX4IO::io_set_control_state(), listener_print_topic(), mag_calibrate_all(), mag_calibration_worker(), sensors::VotedSensorsUpdate::magPoll(), QShell::main(), RoverPositionControl::manual_control_setpoint_poll(), nshterm_main(), orb_publish_auto(), rc_receiver::parameter_update_poll(), mpu9x50::parameter_update_poll(), sensors::VotedSensorsUpdate::parametersUpdate(), MuorbTestExample::PingPongTest(), Simulator::poll_topics(), RoverPositionControl::position_setpoint_triplet_poll(), prepare(), events::SendEvent::process_commands(), px4::logger::LogWriterMavlink::publish_message(), uORBTest::UnitTest::pubsublatency_main(), read_accelerometer_avg(), Sih::read_motors(), RoverPositionControl::run(), Navigator::run(), px4::logger::Logger::run(), PCA9685::Run(), Simulator::send_controls(), px4::logger::LogWriterMavlink::start_log(), TemperatureCalibration::task_main(), CameraFeedback::task_main(), uart_esc::task_main(), linux_pwm_out::task_main(), snapdragon_pwm::task_main(), MK::task_main(), df_bebop_bus_wrapper::task_main(), RoboClaw::taskMain(), uORBTest::UnitTest::test_multi(), uORBTest::UnitTest::test_multi2(), uORBTest::UnitTest::test_multi_reversed(), test_ppm_loopback(), uORBTest::UnitTest::test_queue(), uORBTest::UnitTest::test_queue_poll_notify(), test_rc(), uORBTest::UnitTest::test_single(), vmount::InputMavlinkROI::update_impl(), vmount::InputMavlinkCmdMount::update_impl(), TemperatureCalibrationAccel::update_sensor_instance(), TemperatureCalibrationGyro::update_sensor_instance(), TemperatureCalibrationBaro::update_sensor_instance(), MicroBenchORB::ut_declare_test_c(), RoverPositionControl::vehicle_attitude_poll(), RoverPositionControl::vehicle_control_mode_poll(), and MEASAirspeed::voltage_correction().

Here is the call graph for this function:

◆ orb_exists()

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

Definition at line 105 of file uORB.cpp.

References uORB::Manager::get_instance(), and uORB::Manager::orb_exists().

Referenced by PreFlightCheck::accelerometerCheck(), PreFlightCheck::baroCheck(), PreFlightCheck::gyroCheck(), sensors::VotedSensorsUpdate::initSensorClass(), listener(), PreFlightCheck::magnometerCheck(), orb_group_count(), orb_publish_auto(), and MicroBenchORB::ut_declare_test_c().

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

◆ orb_get_interval()

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

Definition at line 131 of file uORB.cpp.

References uORB::Manager::get_instance(), and uORB::Manager::orb_get_interval().

Referenced by orb_publish_auto().

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

◆ orb_group_count()

int orb_group_count ( const struct orb_metadata meta)

Get the number of published instances of a topic group.

Parameters
metaORB topic metadata.
Returns
The number of published instances of this topic

Definition at line 110 of file uORB.cpp.

References uORB::Manager::get_instance(), ll40ls::instance, OK, and orb_exists().

Referenced by do_accel_calibration_measurements(), do_gyro_calibration(), Heater::initialize_topics(), mag_calibrate_all(), orb_publish_auto(), TemperatureCalibration::task_main(), TemperatureCalibrationAccel::TemperatureCalibrationAccel(), and TemperatureCalibrationBaro::TemperatureCalibrationBaro().

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

◆ orb_priority()

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

Definition at line 121 of file uORB.cpp.

References uORB::Manager::get_instance(), and uORB::Manager::orb_priority().

Referenced by sensors::VotedSensorsUpdate::accelPoll(), sensors::VotedSensorsUpdate::baroPoll(), do_accel_calibration_measurements(), do_gyro_calibration(), sensors::VotedSensorsUpdate::gyroPoll(), mag_calibrate_all(), sensors::VotedSensorsUpdate::magPoll(), orb_publish_auto(), and uORBTest::UnitTest::test_multi().

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

◆ orb_publish()

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

Definition at line 70 of file uORB.cpp.

References uORB::Manager::get_instance(), and uORB::Manager::orb_publish().

Referenced by rpi_rc_in::RcInput::_measure(), linux_sbus::RcInput::_measure(), _param_notify_changes(), DfMS5607Wrapper::_publish(), DfMS5611Wrapper::_publish(), DfBmp280Wrapper::_publish(), DfBebopRangeFinderWrapper::_publish(), DfAK8963Wrapper::_publish(), DfHmc5883Wrapper::_publish(), DfTROneWrapper::_publish(), DfISL29501Wrapper::_publish(), DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfBebopBusWrapper::_publish(), DfMpu9250Wrapper::_publish(), MS5525::collect(), ETSAirspeed::collect(), SDP3X::collect(), MEASAirspeed::collect(), SRF02::collect(), Radar::collect(), MPL3115A2::collect(), SF1XX::collect(), PX4FLOW::collect(), SF0X::collect(), LSM303AGR::collect(), MS5611::collect(), LPS22HB::collect(), RM3100::collect(), LIS3MDL::collect(), LPS25H::collect(), QMC5883::collect(), HMC5883::collect(), BMM150::collect(), IST8310::collect(), TAP_ESC::cycle(), MuorbTestExample::DefaultTest(), CameraTrigger::engage(), uORBTest::UnitTest::latency_test(), mavlink_vasprintf(), VOXLPM::measure(), BMA180::measure(), orb_publish_auto(), MuorbTestExample::PingPongTest(), MK::play_beep(), events::rc_loss::RC_Loss_Alarm::play_tune(), power_button_state_notification_cb(), uORBTest::UnitTest::pub_test_multi2_main(), uORBTest::UnitTest::pub_test_queue_main(), uORB::Publication< vehicle_global_position_s >::publish(), uORB::PublicationQueued< vehicle_command_s >::publish(), uORB::PublicationMulti< rate_ctrl_status_s >::publish(), UavcanCDevSensorBridgeBase::publish(), publish_gam_message(), mpu9x50::publish_reports(), Sih::publish_sih(), publish_tune_control(), px4::Replay::publishTopic(), IRLOCK::read_device(), rgbled_set_color_and_mode(), FixedwingAttitudeControl::Run(), FixedwingPositionControl::Run(), BATT_SMBUS::Run(), Sih::send_gps(), set_tune(), set_tune_override(), events::rc_loss::RC_Loss_Alarm::stop_tune(), spektrum_rc::task_main(), rc_receiver::task_main(), uart_esc::task_main(), linux_pwm_out::task_main(), GPSSIM::task_main(), snapdragon_pwm::task_main(), MK::task_main(), df_bebop_bus_wrapper::task_main(), RoboClaw::taskMain(), TEST_F(), uORBTest::UnitTest::test_multi(), uORBTest::UnitTest::test_multi_reversed(), uORBTest::UnitTest::test_queue(), uORBTest::UnitTest::test_single(), test_tone(), PGA460::uORB_publish_results(), and FixedwingAttitudeControl::vehicle_manual_poll().

Here is the call graph for this function:

◆ orb_set_interval()

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

Definition at line 126 of file uORB.cpp.

References uORB::Manager::get_instance(), and uORB::Manager::orb_set_interval().

Referenced by RoboClaw::_parameters_update(), TAP_ESC::cycle(), vmount::InputMavlinkCmdMount::initialize(), listener(), mag_calibrate_all(), orb_publish_auto(), RoverPositionControl::run(), Navigator::run(), PCA9685::Run(), MK::task_main(), PX4IO::task_main(), and RoboClaw::taskMain().

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

◆ orb_stat()

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

Definition at line 100 of file uORB.cpp.

References uORB::Manager::get_instance(), and uORB::Manager::orb_stat().

Referenced by orb_publish_auto(), and MicroBenchORB::ut_declare_test_c().

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

◆ orb_subscribe()

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

Definition at line 75 of file uORB.cpp.

References uORB::Manager::get_instance(), and uORB::Manager::orb_subscribe().

Referenced by QShell::_wait_for_retval(), arm_auth_init(), calibrate_cancel_subscribe(), calibrate_from_orientation(), commander_low_prio_loop(), DfLtc2946Wrapper::DfLtc2946Wrapper(), do_accel_calibration_measurements(), do_airspeed_calibration(), do_gyro_calibration(), do_level_calibration(), esc_calib_main(), frsky_telemetry_thread_main(), TAP_ESC::init(), init_sub_messages(), vmount::InputMavlinkROI::initialize(), vmount::InputRC::initialize(), vmount::OutputBase::initialize(), vmount::InputMavlinkCmdMount::initialize(), listener(), mag_calibration_worker(), QShell::main(), Navigator::Navigator(), nshterm_main(), px4::ReplayEkf2::onEnterMainLoop(), orb_publish_auto(), MuorbTestExample::PingPongTest(), Simulator::poll_for_MAVLink_messages(), prepare(), Sih::run(), RoverPositionControl::run(), px4::logger::Logger::run(), PCA9685::Run(), DfAK8963Wrapper::start(), DfHmc5883Wrapper::start(), DfMPU6050Wrapper::start(), DfLsm9ds1Wrapper::start(), DfMpu9250Wrapper::start(), px4::logger::LogWriterMavlink::start_log(), events::SubscriberHandler::subscribe(), linux_pwm_out::subscribe(), snapdragon_pwm::subscribe(), CameraFeedback::task_main(), rc_receiver::task_main(), uart_esc::task_main(), linux_pwm_out::task_main(), mpu9x50::task_main(), MK::task_main(), df_bebop_bus_wrapper::task_main(), PX4IO::task_main(), RoboClaw::taskMain(), test_ppm_loopback(), uORBTest::UnitTest::test_queue(), uORBTest::UnitTest::test_queue_poll_notify(), test_rc(), uORBTest::UnitTest::test_single(), MicroBenchORB::ut_declare_test_c(), and MEASAirspeed::voltage_correction().

Here is the call graph for this function:

◆ orb_subscribe_multi()

int orb_subscribe_multi ( const struct orb_metadata meta,
unsigned  instance 
)

◆ orb_unadvertise()

◆ orb_unsubscribe()

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

Definition at line 85 of file uORB.cpp.

References uORB::Manager::get_instance(), and uORB::Manager::orb_unsubscribe().

Referenced by calibrate_cancel_unsubscribe(), sensors::VotedSensorsUpdate::deinit(), do_accel_calibration_measurements(), do_gyro_calibration(), TAP_ESC::init(), listener(), mag_calibrate_all(), px4::ReplayEkf2::onExitMainLoop(), orb_publish_auto(), Simulator::poll_for_MAVLink_messages(), uORBTest::UnitTest::pubsublatency_main(), uORB::SubscriptionCallback::registerCallback(), Sih::run(), RoverPositionControl::run(), px4::logger::Logger::run(), TemperatureCalibration::task_main(), CameraFeedback::task_main(), linux_pwm_out::task_main(), snapdragon_pwm::task_main(), df_bebop_bus_wrapper::task_main(), RoboClaw::taskMain(), uORBTest::UnitTest::test_multi(), uORBTest::UnitTest::test_multi2(), test_rc(), uORBTest::UnitTest::test_single(), events::SubscriberHandler::unsubscribe(), MicroBenchORB::ut_declare_test_c(), DfLtc2946Wrapper::~DfLtc2946Wrapper(), vmount::InputMavlinkCmdMount::~InputMavlinkCmdMount(), vmount::InputMavlinkROI::~InputMavlinkROI(), vmount::InputRC::~InputRC(), px4::logger::LogWriterMavlink::~LogWriterMavlink(), Navigator::~Navigator(), vmount::OutputBase::~OutputBase(), TAP_ESC::~TAP_ESC(), TemperatureCalibrationAccel::~TemperatureCalibrationAccel(), and TemperatureCalibrationBaro::~TemperatureCalibrationBaro().

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