PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <Subscription.hpp>
Public Member Functions | |
SubscriptionData (const orb_metadata *meta, uint8_t instance=0) | |
Constructor. More... | |
~SubscriptionData ()=default | |
SubscriptionData (const SubscriptionData &)=delete | |
SubscriptionData & | operator= (const SubscriptionData &)=delete |
SubscriptionData (SubscriptionData &&)=delete | |
SubscriptionData & | operator= (SubscriptionData &&)=delete |
bool | update () |
const T & | get () const |
Public Member Functions inherited from uORB::Subscription | |
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 |
Private Attributes | |
T | _data {} |
Additional Inherited Members | |
Protected Member Functions inherited from uORB::Subscription | |
DeviceNode * | get_node () |
bool | init () |
Protected Attributes inherited from uORB::Subscription | |
DeviceNode * | _node {nullptr} |
const orb_metadata * | _meta {nullptr} |
unsigned | _last_generation {0} |
Subscription's latest data generation. More... | |
uint8_t | _instance {0} |
Definition at line 148 of file Subscription.hpp.
|
inline |
Constructor.
meta | The uORB metadata (usually from the ORB_ID() macro) for the topic. |
instance | The instance for multi sub. |
Definition at line 157 of file Subscription.hpp.
|
default |
|
delete |
|
delete |
|
inline |
Definition at line 174 of file Subscription.hpp.
Referenced by CollisionPrevention::_calculateConstrainedSetpoint(), FlightTask::_checkEkfResetCounters(), FlightTask::_checkTakeoff(), FlightTaskAuto::_evaluateGlobalReference(), FlightTaskAuto::_evaluateTriplets(), FlightTask::_evaluateVehicleLocalPosition(), FlightTaskAuto::_getTargetVelocityXY(), FlightTask::_initEkfResetCounters(), FlightTaskManualPosition::_scaleSticks(), FlightTaskAuto::_set_heading_from_mode(), CollisionPrevention::_updateObstacleMap(), FlightTaskManualPosition::_updateXYlock(), FixedwingPositionControl::airspeed_poll(), BlockLocalPositionEstimator::baroMeasure(), RoverPositionControl::control_position(), FixedwingPositionControl::control_position(), FixedwingPositionControl::control_takeoff(), RoverPositionControl::control_velocity(), Commander::estimator_check(), BlockLocalPositionEstimator::flowCorrect(), BlockLocalPositionEstimator::flowMeasure(), frsky_send_frame1(), frsky_send_frame2(), frsky_send_frame3(), Navigator::get_acceptance_radius(), FixedwingAttitudeControl::get_airspeed_and_update_scaling(), Navigator::get_default_altitude_acceptance_radius(), Navigator::get_yaw_acceptance(), BlockLocalPositionEstimator::gpsCorrect(), BlockLocalPositionEstimator::gpsInit(), BlockLocalPositionEstimator::gpsMeasure(), Commander::handle_command(), MavlinkULog::handle_update(), ObstacleAvoidance::injectAvoidanceSetpoints(), BlockLocalPositionEstimator::landed(), BlockLocalPositionEstimator::landingTargetCorrect(), BlockLocalPositionEstimator::landingTargetMeasure(), BlockLocalPositionEstimator::lidarCorrect(), BlockLocalPositionEstimator::lidarMeasure(), BlockLocalPositionEstimator::mocapMeasure(), Commander::offboard_control_update(), BlockLocalPositionEstimator::predict(), BlockLocalPositionEstimator::publishGlobalPos(), BlockLocalPositionEstimator::publishLocalPos(), BlockLocalPositionEstimator::publishOdom(), Commander::reset_posvel_validity(), Commander::run(), BlockLocalPositionEstimator::Run(), Commander::set_home_position(), Commander::set_home_position_alt_only(), BlockLocalPositionEstimator::sonarCorrect(), BlockLocalPositionEstimator::sonarMeasure(), sPort_send_ALT(), sPort_send_BATV(), sPort_send_CUR(), sPort_send_flight_mode(), sPort_send_FUEL(), sPort_send_GPS_ALT(), sPort_send_GPS_CRS(), sPort_send_GPS_FIX(), sPort_send_GPS_info(), sPort_send_GPS_LAT(), sPort_send_GPS_LON(), sPort_send_GPS_SPD(), sPort_send_GPS_TIME(), sPort_send_NAV_STATE(), sPort_send_SPD(), FixedwingPositionControl::tecs_update_pitch_throttle(), Commander::update_control_mode(), BlockLocalPositionEstimator::visionCorrect(), and BlockLocalPositionEstimator::visionMeasure().
|
delete |
|
delete |
|
inline |
Definition at line 172 of file Subscription.hpp.
Referenced by CollisionPrevention::_updateObstacleMap(), FixedwingPositionControl::airspeed_poll(), Commander::estimator_check(), frsky_update_topics(), FixedwingAttitudeControl::get_airspeed_and_update_scaling(), MavlinkULog::handle_update(), ObstacleAvoidance::injectAvoidanceSetpoints(), BlockLocalPositionEstimator::landed(), MavlinkULog::MavlinkULog(), Commander::offboard_control_update(), Commander::run(), RoverPositionControl::run(), Navigator::run(), FixedwingPositionControl::Run(), BlockLocalPositionEstimator::Run(), sPort_update_topics(), FlightTaskAuto::updateInitialize(), and FlightTask::updateInitialize().
|
private |
Definition at line 178 of file Subscription.hpp.