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

#include <mavlink_orb_subscription.h>

Inheritance diagram for MavlinkOrbSubscription:
Collaboration diagram for MavlinkOrbSubscription:

Public Member Functions

 MavlinkOrbSubscription (const orb_id_t topic, int instance)
 
 ~MavlinkOrbSubscription ()=default
 
bool update (uint64_t *time, void *data)
 Check if subscription updated based on timestamp. More...
 
bool update (void *data)
 Copy topic data to given buffer. More...
 
bool update_if_changed (void *data)
 Check if the subscription has been updated. More...
 
bool is_published ()
 Check if the topic has been published. More...
 
void subscribe_from_beginning (bool from_beginning)
 
orb_id_t get_topic () const
 
int get_instance () const
 
- Public Member Functions inherited from ListNode< MavlinkOrbSubscription *>
void setSibling (MavlinkOrbSubscription * sibling)
 
const MavlinkOrbSubscriptiongetSibling () const
 

Private Attributes

uORB::Subscription _sub
 
bool _subscribe_from_beginning {false}
 we need to subscribe from the beginning, e.g. for vehicle_command_acks More...
 

Additional Inherited Members

- Protected Attributes inherited from ListNode< MavlinkOrbSubscription *>
MavlinkOrbSubscription_list_node_sibling
 

Detailed Description

Definition at line 48 of file mavlink_orb_subscription.h.

Constructor & Destructor Documentation

◆ MavlinkOrbSubscription()

MavlinkOrbSubscription::MavlinkOrbSubscription ( const orb_id_t  topic,
int  instance 
)
inline

Definition at line 52 of file mavlink_orb_subscription.h.

References ~MavlinkOrbSubscription().

Here is the call graph for this function:

◆ ~MavlinkOrbSubscription()

MavlinkOrbSubscription::~MavlinkOrbSubscription ( )
default

Referenced by MavlinkOrbSubscription().

Here is the caller graph for this function:

Member Function Documentation

◆ get_instance()

int MavlinkOrbSubscription::get_instance ( ) const
inline

Definition at line 93 of file mavlink_orb_subscription.h.

References _sub, and uORB::Subscription::get_instance().

Here is the call graph for this function:

◆ get_topic()

orb_id_t MavlinkOrbSubscription::get_topic ( ) const
inline

Definition at line 92 of file mavlink_orb_subscription.h.

References _sub, and uORB::Subscription::get_topic().

Here is the call graph for this function:

◆ is_published()

bool MavlinkOrbSubscription::is_published ( )

Check if the topic has been published.

This call will return true if the topic was ever published.

Returns
true if the topic has been published at least once. If no data is available the buffer will be filled with zeros.

Definition at line 43 of file mavlink_orb_subscription.cpp.

References _sub, _subscribe_from_beginning, uORB::Subscription::advertised(), and uORB::Subscription::subscribe().

Referenced by MavlinkStreamHomePosition::send(), and update_if_changed().

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

◆ subscribe_from_beginning()

void MavlinkOrbSubscription::subscribe_from_beginning ( bool  from_beginning)
inline

Definition at line 90 of file mavlink_orb_subscription.h.

References _subscribe_from_beginning.

Referenced by Mavlink::task_main().

Here is the caller graph for this function:

◆ update() [1/2]

bool MavlinkOrbSubscription::update ( uint64_t *  time,
void *  data 
)
inline

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 64 of file mavlink_orb_subscription.h.

References _sub, and uORB::Subscription::update().

Referenced by MavlinkStreamHeartbeat::send(), MavlinkStreamSysStatus::send(), MavlinkStreamHighresIMU::send(), MavlinkStreamScaledIMU::send(), MavlinkStreamScaledIMU2::send(), MavlinkStreamScaledIMU3::send(), MavlinkStreamAttitude::send(), MavlinkStreamAttitudeQuaternion::send(), MavlinkStreamVFRHUD::send(), MavlinkStreamGPSRawInt::send(), MavlinkStreamGPS2Raw::send(), MavlinkStreamADSBVehicle::send(), MavlinkStreamUTMGlobalPosition::send(), MavlinkStreamCollision::send(), MavlinkStreamCameraTrigger::send(), MavlinkStreamCameraImageCaptured::send(), MavlinkStreamGlobalPositionInt::send(), MavlinkStreamOdometry::send(), MavlinkStreamLocalPositionNED::send(), MavlinkStreamEstimatorStatus::send(), MavlinkStreamAttPosMocap::send(), MavlinkStreamHomePosition::send(), MavlinkStreamServoOutputRaw< N >::send(), MavlinkStreamActuatorControlTarget< N >::send(), MavlinkStreamHILActuatorControls::send(), MavlinkStreamPositionTargetGlobalInt::send(), MavlinkStreamLocalPositionSetpoint::send(), MavlinkStreamAttitudeTarget::send(), MavlinkStreamRCChannels::send(), MavlinkStreamManualControl::send(), MavlinkStreamTrajectoryRepresentationWaypoints::send(), MavlinkStreamOpticalFlowRad::send(), MavlinkStreamNamedValueFloat::send(), MavlinkStreamDebug::send(), MavlinkStreamDebugVect::send(), MavlinkStreamDebugFloatArray::send(), MavlinkStreamNavControllerOutput::send(), MavlinkStreamCameraCapture::send(), MavlinkStreamDistanceSensor::send(), MavlinkStreamExtendedSysState::send(), MavlinkStreamAltitude::send(), MavlinkStreamWind::send(), MavlinkStreamMountOrientation::send(), MavlinkStreamGroundTruth::send(), MavlinkStreamOrbitStatus::send(), MavlinkStreamObstacleDistance::send(), Mavlink::task_main(), MavlinkStreamHighLatency2::update_airspeed(), MavlinkStreamHighLatency2::update_global_position(), MavlinkStreamHighLatency2::update_gps(), MavlinkStreamHighLatency2::update_tecs_status(), MavlinkStreamHighLatency2::update_vehicle_status(), MavlinkStreamHighLatency2::update_wind_estimate(), MavlinkStreamHighLatency2::write_airspeed(), MavlinkStreamHighLatency2::write_attitude_sp(), MavlinkStreamHighLatency2::write_estimator_status(), MavlinkStreamHighLatency2::write_fw_ctrl_status(), MavlinkStreamHighLatency2::write_geofence_result(), MavlinkStreamHighLatency2::write_global_position(), MavlinkStreamHighLatency2::write_mission_result(), MavlinkStreamHighLatency2::write_tecs_status(), MavlinkStreamHighLatency2::write_vehicle_status(), MavlinkStreamHighLatency2::write_vehicle_status_flags(), and MavlinkStreamHighLatency2::write_wind_estimate().

Here is the call graph for this function:

◆ update() [2/2]

bool MavlinkOrbSubscription::update ( void *  data)
inline

Copy topic data to given buffer.

Returns
true only if topic data copied successfully.

Definition at line 71 of file mavlink_orb_subscription.h.

References _sub, and uORB::Subscription::copy().

Here is the call graph for this function:

◆ update_if_changed()

bool MavlinkOrbSubscription::update_if_changed ( void *  data)
inline

Check if the subscription has been updated.

Returns
true if there has been an update which has been copied successfully.

Definition at line 79 of file mavlink_orb_subscription.h.

References _sub, is_published(), and uORB::Subscription::update().

Referenced by MavlinkStreamCommandLong::send(), and Mavlink::task_main().

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

Member Data Documentation

◆ _sub

uORB::Subscription MavlinkOrbSubscription::_sub
private

◆ _subscribe_from_beginning

bool MavlinkOrbSubscription::_subscribe_from_beginning {false}
private

we need to subscribe from the beginning, e.g. for vehicle_command_acks

Definition at line 99 of file mavlink_orb_subscription.h.

Referenced by is_published(), and subscribe_from_beginning().


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