VSM C++ SDK
Vehicle Specific Modules SDK
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
ugcs::vsm::Mavlink_decoder Class Reference

Decodes Mavlink 1.0 messages from byte stream. More...

#include <mavlink_decoder.h>

Public Types

typedef Callback_proxy< void,
Io_buffer::Ptr,
mavlink::MESSAGE_ID_TYPE,
uint8_t, uint8_t, uint32_t > 
Handler
 Handler type of the received Mavlink message. More...
 
typedef Callback_proxy< void,
Io_buffer::Ptr
Raw_data_handler
 Handler for the raw data going through the decoder. More...
 

Public Member Functions

template<class __Callable , typename... __Args>
 __DEFINE_CALLBACK_BUILDER_BODY (Make_decoder_handler,(Io_buffer::Ptr, mavlink::MESSAGE_ID_TYPE, uint8_t, uint8_t, uint32_t),(nullptr, mavlink::MESSAGE_ID::DEBUG_VALUE, mavlink::SYSTEM_ID_NONE, 0, 0)) template< class __Callable
 Convenience builder for Mavlink decoder handlers. More...
 
typename __Args __DEFINE_CALLBACK_BUILDER_BODY (Make_raw_data_handler,(Io_buffer::Ptr),(nullptr)) struct Stats
 Decoder statistics. More...
 
 Mavlink_decoder ()
 Default constructor. More...
 
 Mavlink_decoder (const Mavlink_decoder &)=delete
 Delete copy constructor. More...
 
void Disable ()
 Should be called prior to intention to delete the instance. More...
 
void Register_handler (Handler handler)
 Register handler for successfully decoded Mavlink messages.
 
void Register_raw_data_handler (Raw_data_handler handler)
 
void Decode (Io_buffer::Ptr buffer)
 Decode buffer from the wire. More...
 
size_t Get_next_read_size () const
 Get the exact number of bytes which should be read by underlying I/O subsystem and fed to the decoder. More...
 
const Mavlink_decoder::Stats Get_stats (int system_id)
 Get read-only access to statistics. More...
 
const Mavlink_decoder::Stats Get_common_stats ()
 Get read-only access to common statistics. More...
 

Detailed Description

Decodes Mavlink 1.0 messages from byte stream.

Member Typedef Documentation

Handler type of the received Mavlink message.

Arguments are:

  • Payload buffer
  • Message id
  • Sending system id
  • Sending component id

Handler for the raw data going through the decoder.

Constructor & Destructor Documentation

ugcs::vsm::Mavlink_decoder::Mavlink_decoder ( )
inline

Default constructor.

ugcs::vsm::Mavlink_decoder::Mavlink_decoder ( const Mavlink_decoder )
delete

Delete copy constructor.

Member Function Documentation

template<class __Callable , typename... __Args>
ugcs::vsm::Mavlink_decoder::__DEFINE_CALLBACK_BUILDER_BODY ( Make_decoder_handler  ,
(Io_buffer::Ptr, mavlink::MESSAGE_ID_TYPE, uint8_t, uint8_t, uint32_t)  ,
(nullptr, mavlink::MESSAGE_ID::DEBUG_VALUE, mavlink::SYSTEM_ID_NONE, 0, 0)   
)

Convenience builder for Mavlink decoder handlers.

Convenience builder for raw data handlers.

typename __Args ugcs::vsm::Mavlink_decoder::__DEFINE_CALLBACK_BUILDER_BODY ( Make_raw_data_handler  ,
(Io_buffer::Ptr ,
(nullptr)   
)
inline

Decoder statistics.

Messages processed by registered handler. Total and per system_id.

Messages without handler, dropped. Total and per system_id.

Messages with wrong checksum. Only total for the connection is counted.

Messages with wrong length, but correct checksum. Total and per system_id.

Messages with unknown id. Note that checksum is not verified for such messages. Only total for the connection is counted.

Total received bytes, including any error or not handled messages. Only total for the connection is counted.

Number of STX bytes found during decoding, i.e. how many times packet decode was tried to be started. Only total for the connection is counted.

void ugcs::vsm::Mavlink_decoder::Decode ( Io_buffer::Ptr  buffer)
inline

Decode buffer from the wire.

void ugcs::vsm::Mavlink_decoder::Disable ( )
inline

Should be called prior to intention to delete the instance.

const Mavlink_decoder::Stats ugcs::vsm::Mavlink_decoder::Get_common_stats ( )
inline

Get read-only access to common statistics.

size_t ugcs::vsm::Mavlink_decoder::Get_next_read_size ( ) const
inline

Get the exact number of bytes which should be read by underlying I/O subsystem and fed to the decoder.

Returns
Exact number of bytes to be read by next read operation.
const Mavlink_decoder::Stats ugcs::vsm::Mavlink_decoder::Get_stats ( int  system_id)
inline

Get read-only access to statistics.

Supports multiple system_ids on one connection.

Parameters
system_idsystem id to get statistics for. Use mavlink::SYSTEM_ID_ANY to get total for all system_ids.
Returns
Readonly reference to the Stats structure for given system_id.

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