PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <mavlink_orb_subscription.h>
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 MavlinkOrbSubscription * | getSibling () 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 |
Definition at line 48 of file mavlink_orb_subscription.h.
|
inline |
Definition at line 52 of file mavlink_orb_subscription.h.
References ~MavlinkOrbSubscription().
|
default |
|
inline |
Definition at line 93 of file mavlink_orb_subscription.h.
References _sub, and uORB::Subscription::get_instance().
|
inline |
Definition at line 92 of file mavlink_orb_subscription.h.
References _sub, and uORB::Subscription::get_topic().
bool MavlinkOrbSubscription::is_published | ( | ) |
Check if the topic has been published.
This call will return true if the topic was ever published.
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().
|
inline |
Definition at line 90 of file mavlink_orb_subscription.h.
References _subscribe_from_beginning.
Referenced by Mavlink::task_main().
|
inline |
Check if subscription updated based on timestamp.
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().
|
inline |
Copy topic data to given buffer.
Definition at line 71 of file mavlink_orb_subscription.h.
References _sub, and uORB::Subscription::copy().
|
inline |
Check if the subscription has been updated.
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().
|
private |
Definition at line 97 of file mavlink_orb_subscription.h.
Referenced by get_instance(), get_topic(), is_published(), update(), and update_if_changed().
|
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().