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

#include <Subscription.hpp>

Inheritance diagram for uORB::Subscription:
Collaboration diagram for uORB::Subscription:

Public Member Functions

 Subscription (const orb_metadata *meta, uint8_t instance=0)
 Constructor. More...
 
 ~Subscription ()
 
bool subscribe ()
 
void unsubscribe ()
 
bool valid () const
 
bool advertised ()
 
bool updated ()
 Check if there is a new update. More...
 
bool update (void *dst)
 Update the struct. More...
 
bool update (uint64_t *time, void *dst)
 Check if subscription updated based on timestamp. More...
 
bool copy (void *dst)
 Copy the struct. More...
 
uint8_t get_instance () const
 
orb_id_t get_topic () const
 

Protected Member Functions

DeviceNodeget_node ()
 
bool init ()
 

Protected Attributes

DeviceNode_node {nullptr}
 
const orb_metadata_meta {nullptr}
 
unsigned _last_generation {0}
 Subscription's latest data generation. More...
 
uint8_t _instance {0}
 

Friends

class SubscriptionCallback
 

Detailed Description

Definition at line 54 of file Subscription.hpp.

Constructor & Destructor Documentation

◆ Subscription()

uORB::Subscription::Subscription ( const orb_metadata meta,
uint8_t  instance = 0 
)
inline

Constructor.

Parameters
metaThe uORB metadata (usually from the ORB_ID() macro) for the topic.
instanceThe instance for multi sub.

Definition at line 64 of file Subscription.hpp.

References subscribe().

Here is the call graph for this function:

◆ ~Subscription()

uORB::Subscription::~Subscription ( )
inline

Definition at line 69 of file Subscription.hpp.

References subscribe(), and unsubscribe().

Here is the call graph for this function:

Member Function Documentation

◆ advertised()

bool uORB::Subscription::advertised ( )
inline

Definition at line 78 of file Subscription.hpp.

References _node, init(), uORB::DeviceNode::is_advertised(), and valid().

Referenced by uORB::SubscriptionInterval::advertised(), copy(), Heater::initialize_topics(), MavlinkOrbSubscription::is_published(), update(), and updated().

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

◆ copy()

bool uORB::Subscription::copy ( void *  dst)
inline

Copy the struct.

Parameters
dataThe uORB message struct we are updating.

Definition at line 121 of file Subscription.hpp.

References _last_generation, _node, advertised(), and uORB::DeviceNode::copy().

Referenced by landing_target_estimator::LandingTargetEstimator::_check_params(), land_detector::LandDetector::_update_params(), FlightTasks::_updateCommand(), CollisionPrevention::_updateObstacleMap(), Navigator::abort_landing(), BatteryStatus::adc_poll(), Commander::battery_status_check(), Navigator::check_traffic(), uORB::SubscriptionInterval::copy(), TAP_ESC::cycle(), Commander::data_link_check(), MavlinkReceiver::handle_message_set_actuator_control_target(), MavlinkReceiver::handle_message_set_attitude_target(), MavlinkReceiver::handle_message_set_position_target_global_int(), MavlinkReceiver::handle_message_set_position_target_local_ned(), GPS::handleInjectDataTopic(), Heater::initialize_topics(), PX4IO::io_set_arming_state(), FollowTarget::on_active(), ToneAlarm::orb_update(), Sensors::parameter_update_poll(), BatteryStatus::parameter_update_poll(), MulticopterPositionControl::parameters_update(), Sih::parameters_update_poll(), VehicleAcceleration::ParametersUpdate(), VehicleAngularVelocity::ParametersUpdate(), MulticopterPositionControl::poll_subscriptions(), PWMSim::Run(), MulticopterRateControl::Run(), MulticopterAttitudeControl::Run(), AttitudeEstimatorQ::Run(), RGBLED::Run(), RGBLED_NPC5623C::Run(), AirspeedModule::Run(), FixedwingAttitudeControl::Run(), Commander::run(), VtolAttitudeControl::Run(), Sensors::run(), Ekf2::Run(), Navigator::run(), BatteryStatus::Run(), px4::logger::Logger::run(), PX4FMU::Run(), px4::bst::BST::Run(), FixedwingPositionControl::Run(), UavcanNode::Run(), MavlinkReceiver::Run(), BlinkM::Run(), MavlinkReceiver::send_flight_information(), VehicleAcceleration::SensorBiasUpdate(), VehicleAngularVelocity::SensorBiasUpdate(), VehicleAcceleration::SensorCorrectionsUpdate(), VehicleAngularVelocity::SensorCorrectionsUpdate(), uORB::SubscriptionData< vehicle_land_detected_s >::SubscriptionData(), PX4IO::task_main(), MavlinkOrbSubscription::update(), LedController::update(), update(), CameraTrigger::update_distance(), AttitudeEstimatorQ::update_parameters(), Heater::update_params(), OSDatxxxx::update_topics(), VtolAttitudeControl::vehicle_cmd_poll(), FixedwingPositionControl::vehicle_command_poll(), FixedwingPositionControl::vehicle_control_mode_poll(), FixedwingAttitudeControl::vehicle_land_detected_poll(), FixedwingAttitudeControl::vehicle_manual_poll(), and RoverPositionControl::~RoverPositionControl().

Here is the call graph for this function:

◆ get_instance()

uint8_t uORB::Subscription::get_instance ( ) const
inline

Definition at line 123 of file Subscription.hpp.

References _instance.

Referenced by MavlinkOrbSubscription::get_instance(), uORB::SubscriptionInterval::get_instance(), and uORB::SubscriptionCallback::registerCallback().

Here is the caller graph for this function:

◆ get_node()

DeviceNode* uORB::Subscription::get_node ( )
inlineprotected

Definition at line 130 of file Subscription.hpp.

References _node, and init().

Referenced by uORB::SubscriptionCallback::registerCallback(), and uORB::SubscriptionCallback::unregisterCallback().

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

◆ get_topic()

orb_id_t uORB::Subscription::get_topic ( ) const
inline

Definition at line 124 of file Subscription.hpp.

References _meta.

Referenced by MavlinkOrbSubscription::get_topic(), uORB::SubscriptionInterval::get_topic(), and uORB::SubscriptionCallback::registerCallback().

Here is the caller graph for this function:

◆ init()

bool uORB::Subscription::init ( )
protected

Definition at line 97 of file Subscription.cpp.

References _last_generation, _meta, _node, and subscribe().

Referenced by advertised(), and get_node().

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

◆ subscribe()

bool uORB::Subscription::subscribe ( )

Definition at line 46 of file Subscription.cpp.

References _instance, _last_generation, _meta, _node, uORB::DeviceNode::add_internal_subscriber(), uORB::Manager::get_device_master(), uORB::Manager::get_instance(), uORB::DeviceNode::get_queue_size(), uORB::DeviceMaster::getDeviceNode(), and uORB::DeviceNode::published_message_count().

Referenced by init(), MavlinkOrbSubscription::is_published(), MixingOutput::MixingOutput(), Commander::offboard_control_update(), uORB::SubscriptionCallback::registerCallback(), uORB::SubscriptionInterval::subscribe(), Subscription(), and ~Subscription().

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

◆ unsubscribe()

void uORB::Subscription::unsubscribe ( )

Definition at line 86 of file Subscription.cpp.

References _last_generation, _node, and uORB::DeviceNode::remove_internal_subscriber().

Referenced by ~Subscription().

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

◆ update() [1/2]

bool uORB::Subscription::update ( void *  dst)
inline

Update the struct.

Parameters
dataThe uORB message struct we are updating.

Definition at line 104 of file Subscription.hpp.

References copy(), and updated().

Referenced by land_detector::VtolLandDetector::_update_topics(), land_detector::FixedwingLandDetector::_update_topics(), land_detector::MulticopterLandDetector::_update_topics(), landing_target_estimator::LandingTargetEstimator::_update_topics(), land_detector::LandDetector::_update_topics(), UavcanGnssBridge::broadcast_from_orb(), MulticopterAttitudeControl::control_attitude(), RCInput::cycle(), Commander::data_link_check(), Sensors::diff_pres_poll(), PX4IO::handle_motor_test(), px4::logger::Logger::handle_vehicle_command_update(), PX4IO::io_set_control_state(), MixingOutput::motorTest(), PrecLand::on_active(), MulticopterPositionControl::poll_subscriptions(), AirspeedModule::poll_topics(), MulticopterRateControl::Run(), MulticopterAttitudeControl::Run(), CameraCapture::Run(), AirspeedModule::Run(), FixedwingAttitudeControl::Run(), VtolAttitudeControl::Run(), Ekf2::Run(), Navigator::run(), FixedwingPositionControl::Run(), Heater::Run(), land_detector::LandDetector::Run(), CameraTrigger::Run(), MavlinkMissionManager::send(), CRSFTelemetry::send_attitude(), CRSFTelemetry::send_battery(), CRSFTelemetry::send_flight_mode(), CRSFTelemetry::send_gps(), MavlinkParametersManager::send_uavcan(), MavlinkParametersManager::send_untransmitted(), px4::logger::Logger::start_stop_logging(), FixedwingPositionControl::tecs_update_pitch_throttle(), MavlinkOrbSubscription::update(), MixingOutput::update(), uORB::SubscriptionData< vehicle_land_detected_s >::update(), MavlinkOrbSubscription::update_if_changed(), DShotOutput::update_params(), FixedwingPositionControl::vehicle_attitude_poll(), FixedwingAttitudeControl::vehicle_attitude_setpoint_poll(), FixedwingAttitudeControl::vehicle_control_mode_poll(), FixedwingAttitudeControl::vehicle_rates_setpoint_poll(), MulticopterRateControl::vehicle_status_poll(), MulticopterAttitudeControl::vehicle_status_poll(), FixedwingAttitudeControl::vehicle_status_poll(), and FixedwingPositionControl::vehicle_status_poll().

Here is the call graph for this function:

◆ update() [2/2]

bool uORB::Subscription::update ( uint64_t *  time,
void *  dst 
)

Check if subscription updated based on timestamp.

Returns
true only if topic was updated based on a timestamp and copied to buffer successfully. If topic was not updated since last check it will return false but still copy the data. If no data available data buffer will be filled with zeros.

Definition at line 117 of file Subscription.cpp.

References _last_generation, _node, advertised(), and uORB::DeviceNode::copy_and_get_timestamp().

Here is the call graph for this function:

◆ updated()

bool uORB::Subscription::updated ( )
inline

Check if there is a new update.

Definition at line 98 of file Subscription.hpp.

References _last_generation, _node, advertised(), and uORB::DeviceNode::published_message_count().

Referenced by landing_target_estimator::LandingTargetEstimator::_check_params(), FlightTasks::_updateCommand(), Navigator::abort_landing(), Commander::battery_status_check(), Navigator::check_traffic(), TAP_ESC::cycle(), Commander::data_link_check(), GPS::handleInjectDataTopic(), Commander::offboard_control_update(), FollowTarget::on_active(), ToneAlarm::orb_update(), Sensors::parameter_update_poll(), BatteryStatus::parameter_update_poll(), MulticopterPositionControl::parameters_update(), Sih::parameters_update_poll(), VehicleAcceleration::ParametersUpdate(), VehicleAngularVelocity::ParametersUpdate(), MulticopterPositionControl::poll_subscriptions(), PWMSim::Run(), MulticopterRateControl::Run(), MulticopterAttitudeControl::Run(), AttitudeEstimatorQ::Run(), RGBLED::Run(), RGBLED_NPC5623C::Run(), FixedwingAttitudeControl::Run(), Commander::run(), VtolAttitudeControl::Run(), Sensors::run(), Ekf2::Run(), Navigator::run(), BatteryStatus::Run(), px4::logger::Logger::run(), DShotOutput::Run(), PX4FMU::Run(), px4::bst::BST::Run(), FixedwingPositionControl::Run(), land_detector::LandDetector::Run(), UavcanNode::Run(), MavlinkReceiver::Run(), BlinkM::Run(), MavlinkParametersManager::send_untransmitted(), VehicleAcceleration::SensorBiasUpdate(), VehicleAngularVelocity::SensorBiasUpdate(), VehicleAcceleration::SensorCorrectionsUpdate(), VehicleAngularVelocity::SensorCorrectionsUpdate(), PX4IO::task_main(), LedController::update(), update(), AttitudeEstimatorQ::update_parameters(), Heater::update_params(), OSDatxxxx::update_topics(), uORB::SubscriptionInterval::updated(), VtolAttitudeControl::vehicle_cmd_poll(), FixedwingPositionControl::vehicle_command_poll(), FixedwingPositionControl::vehicle_control_mode_poll(), FixedwingAttitudeControl::vehicle_land_detected_poll(), and RoverPositionControl::~RoverPositionControl().

Here is the call graph for this function:

◆ valid()

bool uORB::Subscription::valid ( ) const
inline

Definition at line 77 of file Subscription.hpp.

References _node.

Referenced by advertised(), and uORB::SubscriptionInterval::valid().

Here is the caller graph for this function:

Friends And Related Function Documentation

◆ SubscriptionCallback

friend class SubscriptionCallback
friend

Definition at line 128 of file Subscription.hpp.

Member Data Documentation

◆ _instance

uint8_t uORB::Subscription::_instance {0}
protected

Definition at line 143 of file Subscription.hpp.

Referenced by get_instance(), and subscribe().

◆ _last_generation

unsigned uORB::Subscription::_last_generation {0}
protected

Subscription's latest data generation.

Also used to track (and rate limit) subscription attempts if the topic has not yet been published.

Definition at line 142 of file Subscription.hpp.

Referenced by copy(), init(), subscribe(), unsubscribe(), update(), and updated().

◆ _meta

const orb_metadata* uORB::Subscription::_meta {nullptr}
protected

Definition at line 135 of file Subscription.hpp.

Referenced by get_topic(), init(), and subscribe().

◆ _node

DeviceNode* uORB::Subscription::_node {nullptr}
protected

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