VSM C++ SDK
Vehicle Specific Modules SDK
ugcs::vsm::mavlink::Payload< TData, fields, msg_name, msg_id, extra_byte > Class Template Reference

Generalized MAVLink message payload. More...

#include <mavlink.h>

Inheritance diagram for ugcs::vsm::mavlink::Payload< TData, fields, msg_name, msg_id, extra_byte >:
ugcs::vsm::mavlink::Payload_base

Public Types

typedef std::shared_ptr< PayloadPtr
 Pointer type.
 
typedef std::weak_ptr< PayloadWeak_ptr
 Pointer type.
 

Public Member Functions

 Payload ()=default
 All fields are initialized to default values. More...
 
 Payload (const void *buf, size_t size)
 Parse message from data buffer. More...
 
 Payload (Io_buffer::Ptr buffer)
 Convenience variation of previous constructor. More...
 
virtual size_t Get_size () const override
 Get size of the message payload in bytes. More...
 
virtual const char * Get_name () const override
 Get message name. More...
 
virtual MESSAGE_ID_TYPE Get_id () const override
 Get message id. More...
 
virtual uint8_t Get_extra_byte () const override
 Get extra byte for CRC calculation. More...
 
virtual void Reset () override
 Reset all fields to UgCS default values. More...
 
bool operator== (const Payload &rhs) const
 Compare if data in the payload is bit-same with another payload. More...
 
bool operator!= (const Payload &rhs) const
 Compare if data in the payload is not bit-same with another payload. More...
 
TData * operator-> ()
 Pointer access semantics to payload. More...
 
const TData * operator-> () const
 Constant pointer access semantics to payload. More...
 
TData & operator* ()
 Dereference access semantics to payload. More...
 
const TData & operator* () const
 Constant dereference access semantics to payload. More...
 

Static Public Member Functions

template<typename... Args>
static Ptr Create (Args &&...args)
 Create an instance. More...
 
static constexpr size_t Get_payload_size ()
 Get payload size in bytes for this type of message. More...
 

Additional Inherited Members

Detailed Description

template<class TData, internal::Field_descriptor * fields, const char * msg_name, MESSAGE_ID_TYPE msg_id, uint8_t extra_byte>
class ugcs::vsm::mavlink::Payload< TData, fields, msg_name, msg_id, extra_byte >

Generalized MAVLink message payload.

Parameters
TDataStructure for payload data.

Constructor & Destructor Documentation

template<class TData , internal::Field_descriptor * fields, const char * msg_name, MESSAGE_ID_TYPE msg_id, uint8_t extra_byte>
ugcs::vsm::mavlink::Payload< TData, fields, msg_name, msg_id, extra_byte >::Payload ( )
default

All fields are initialized to default values.

template<class TData , internal::Field_descriptor * fields, const char * msg_name, MESSAGE_ID_TYPE msg_id, uint8_t extra_byte>
ugcs::vsm::mavlink::Payload< TData, fields, msg_name, msg_id, extra_byte >::Payload ( const void *  buf,
size_t  size 
)
inline

Parse message from data buffer.

The buffer should contain data on wire (in network byte order). Data size should not be less than expected payload size otherwise Invalid_param_exception is thrown.

Parameters
bufPointer to data buffer.
sizeSize of data available.
Exceptions
Invalid_param_exceptionif size is less than expected payload size;
template<class TData , internal::Field_descriptor * fields, const char * msg_name, MESSAGE_ID_TYPE msg_id, uint8_t extra_byte>
ugcs::vsm::mavlink::Payload< TData, fields, msg_name, msg_id, extra_byte >::Payload ( Io_buffer::Ptr  buffer)
inline

Convenience variation of previous constructor.

Parameters
bufferBuffer with data.

Member Function Documentation

template<class TData , internal::Field_descriptor * fields, const char * msg_name, MESSAGE_ID_TYPE msg_id, uint8_t extra_byte>
template<typename... Args>
static Ptr ugcs::vsm::mavlink::Payload< TData, fields, msg_name, msg_id, extra_byte >::Create ( Args &&...  args)
inlinestatic

Create an instance.

template<class TData , internal::Field_descriptor * fields, const char * msg_name, MESSAGE_ID_TYPE msg_id, uint8_t extra_byte>
virtual uint8_t ugcs::vsm::mavlink::Payload< TData, fields, msg_name, msg_id, extra_byte >::Get_extra_byte ( ) const
inlineoverridevirtual

Get extra byte for CRC calculation.

Implements ugcs::vsm::mavlink::Payload_base.

template<class TData , internal::Field_descriptor * fields, const char * msg_name, MESSAGE_ID_TYPE msg_id, uint8_t extra_byte>
virtual MESSAGE_ID_TYPE ugcs::vsm::mavlink::Payload< TData, fields, msg_name, msg_id, extra_byte >::Get_id ( ) const
inlineoverridevirtual

Get message id.

Implements ugcs::vsm::mavlink::Payload_base.

template<class TData , internal::Field_descriptor * fields, const char * msg_name, MESSAGE_ID_TYPE msg_id, uint8_t extra_byte>
virtual const char* ugcs::vsm::mavlink::Payload< TData, fields, msg_name, msg_id, extra_byte >::Get_name ( ) const
inlineoverridevirtual

Get message name.

Implements ugcs::vsm::mavlink::Payload_base.

template<class TData , internal::Field_descriptor * fields, const char * msg_name, MESSAGE_ID_TYPE msg_id, uint8_t extra_byte>
static constexpr size_t ugcs::vsm::mavlink::Payload< TData, fields, msg_name, msg_id, extra_byte >::Get_payload_size ( )
inlinestatic

Get payload size in bytes for this type of message.

template<class TData , internal::Field_descriptor * fields, const char * msg_name, MESSAGE_ID_TYPE msg_id, uint8_t extra_byte>
virtual size_t ugcs::vsm::mavlink::Payload< TData, fields, msg_name, msg_id, extra_byte >::Get_size ( ) const
inlineoverridevirtual

Get size of the message payload in bytes.

Implements ugcs::vsm::mavlink::Payload_base.

template<class TData , internal::Field_descriptor * fields, const char * msg_name, MESSAGE_ID_TYPE msg_id, uint8_t extra_byte>
bool ugcs::vsm::mavlink::Payload< TData, fields, msg_name, msg_id, extra_byte >::operator!= ( const Payload< TData, fields, msg_name, msg_id, extra_byte > &  rhs) const
inline

Compare if data in the payload is not bit-same with another payload.

template<class TData , internal::Field_descriptor * fields, const char * msg_name, MESSAGE_ID_TYPE msg_id, uint8_t extra_byte>
TData& ugcs::vsm::mavlink::Payload< TData, fields, msg_name, msg_id, extra_byte >::operator* ( )
inline

Dereference access semantics to payload.

template<class TData , internal::Field_descriptor * fields, const char * msg_name, MESSAGE_ID_TYPE msg_id, uint8_t extra_byte>
const TData& ugcs::vsm::mavlink::Payload< TData, fields, msg_name, msg_id, extra_byte >::operator* ( ) const
inline

Constant dereference access semantics to payload.

template<class TData , internal::Field_descriptor * fields, const char * msg_name, MESSAGE_ID_TYPE msg_id, uint8_t extra_byte>
TData* ugcs::vsm::mavlink::Payload< TData, fields, msg_name, msg_id, extra_byte >::operator-> ( )
inline

Pointer access semantics to payload.

template<class TData , internal::Field_descriptor * fields, const char * msg_name, MESSAGE_ID_TYPE msg_id, uint8_t extra_byte>
const TData* ugcs::vsm::mavlink::Payload< TData, fields, msg_name, msg_id, extra_byte >::operator-> ( ) const
inline

Constant pointer access semantics to payload.

template<class TData , internal::Field_descriptor * fields, const char * msg_name, MESSAGE_ID_TYPE msg_id, uint8_t extra_byte>
bool ugcs::vsm::mavlink::Payload< TData, fields, msg_name, msg_id, extra_byte >::operator== ( const Payload< TData, fields, msg_name, msg_id, extra_byte > &  rhs) const
inline

Compare if data in the payload is bit-same with another payload.

template<class TData , internal::Field_descriptor * fields, const char * msg_name, MESSAGE_ID_TYPE msg_id, uint8_t extra_byte>
virtual void ugcs::vsm::mavlink::Payload< TData, fields, msg_name, msg_id, extra_byte >::Reset ( )
inlineoverridevirtual

Reset all fields to UgCS default values.

Implements ugcs::vsm::mavlink::Payload_base.


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