Firmware
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
MavlinkStream Class Referenceabstract
Inheritance diagram for MavlinkStream:
ListNode< MavlinkStream *> MavlinkStreamActuatorControlTarget< N > MavlinkStreamADSBVehicle MavlinkStreamAltitude MavlinkStreamAttitude MavlinkStreamAttitudeQuaternion MavlinkStreamAttitudeTarget MavlinkStreamAttPosMocap MavlinkStreamCameraCapture MavlinkStreamCameraImageCaptured MavlinkStreamCameraTrigger MavlinkStreamCollision MavlinkStreamCommandLong MavlinkStreamDebug MavlinkStreamDebugFloatArray MavlinkStreamDebugVect MavlinkStreamDistanceSensor MavlinkStreamEstimatorStatus MavlinkStreamExtendedSysState MavlinkStreamGlobalPositionInt MavlinkStreamGPS2Raw MavlinkStreamGPSRawInt MavlinkStreamGroundTruth MavlinkStreamHeartbeat MavlinkStreamHighLatency2 MavlinkStreamHighresIMU MavlinkStreamHILActuatorControls MavlinkStreamHomePosition MavlinkStreamLocalPositionNED MavlinkStreamLocalPositionSetpoint MavlinkStreamManualControl MavlinkStreamMountOrientation MavlinkStreamNamedValueFloat MavlinkStreamNavControllerOutput MavlinkStreamOdometry MavlinkStreamOpticalFlowRad MavlinkStreamOrbitStatus MavlinkStreamPing MavlinkStreamPositionTargetGlobalInt MavlinkStreamRCChannels MavlinkStreamScaledIMU MavlinkStreamScaledIMU2 MavlinkStreamScaledIMU3 MavlinkStreamServoOutputRaw< N > MavlinkStreamStatustext MavlinkStreamSysStatus MavlinkStreamSystemTime MavlinkStreamTimesync MavlinkStreamTrajectoryRepresentationWaypoints MavlinkStreamUTMGlobalPosition MavlinkStreamVFRHUD MavlinkStreamWind

Public Member Functions

 MavlinkStream (Mavlink *mavlink)
 
 MavlinkStream (const MavlinkStream &)=delete
 
MavlinkStreamoperator= (const MavlinkStream &)=delete
 
 MavlinkStream (MavlinkStream &&)=delete
 
MavlinkStreamoperator= (MavlinkStream &&)=delete
 
void set_interval (const int interval)
 Get the interval. More...
 
int get_interval ()
 Get the interval. More...
 
int update (const hrt_abstime &t)
 Update subscriptions and send message if necessary. More...
 
virtual const char * get_name () const =0
 
virtual uint16_t get_id ()=0
 
virtual bool const_rate ()
 
virtual unsigned get_size ()=0
 Get maximal total messages size on update.
 
virtual unsigned get_size_avg ()
 Get the average message size. More...
 
bool first_message_sent () const
 
void reset_last_sent ()
 Reset the time of last sent to 0. More...
 
- Public Member Functions inherited from ListNode< MavlinkStream *>
void setSibling (MavlinkStream * sibling)
 
const MavlinkStreamgetSibling () const
 

Protected Member Functions

virtual bool send (const hrt_abstime t)=0
 
virtual void update_data ()
 Function to collect/update data for the streams at a high rate independant of actual stream rate. More...
 

Protected Attributes

Mavlink *const _mavlink
 
int _interval {1000000}
 if set to negative value = unlimited rate
 
- Protected Attributes inherited from ListNode< MavlinkStream *>
MavlinkStream_sibling
 

Member Function Documentation

§ const_rate()

virtual bool MavlinkStream::const_rate ( )
inlinevirtual

§ first_message_sent()

bool MavlinkStream::first_message_sent ( ) const
inline
Returns
true if the first message of this stream has been sent

§ get_interval()

int MavlinkStream::get_interval ( )
inline

Get the interval.

Returns
the inveral in microseconds (us) between messages

§ get_size_avg()

virtual unsigned MavlinkStream::get_size_avg ( )
inlinevirtual

Get the average message size.

For a normal stream this equals the message size, for something like a parameter or mission message this equals usually zero, as no bandwidth needs to be reserved

§ reset_last_sent()

void MavlinkStream::reset_last_sent ( )
inline

Reset the time of last sent to 0.

Can be used if a message over this stream needs to be sent immediately.

§ set_interval()

void MavlinkStream::set_interval ( const int  interval)
inline

Get the interval.

Parameters
intervalthe interval in microseconds (us) between messages

§ update()

int MavlinkStream::update ( const hrt_abstime t)

Update subscriptions and send message if necessary.

Returns
0 if updated / sent, -1 if unchanged

§ update_data()

virtual void MavlinkStream::update_data ( )
inlineprotectedvirtual

Function to collect/update data for the streams at a high rate independant of actual stream rate.

This function is called at every iteration of the mavlink module.

Reimplemented in MavlinkStreamHighLatency2.


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