template class ugcs::vsm::mavlink::Payload¶
Overview¶
Generalized MAVLink message payload. More…
#include <mavlink.h> template < class TData, internal::Field_descriptor* fields, const char* msg_name, MESSAGE_ID_TYPE msg_id, uint8_t extra_byte > class Payload: public ugcs::vsm::mavlink::Payload_base { public: // typedefs typedef std::shared_ptr<Payload> Ptr; typedef std::weak_ptr<Payload> Weak_ptr; // construction Payload(); Payload(const void* buf, size_t size); Payload(Io_buffer::Ptr buffer); // methods template <typename... Args> static Ptr Create(Args&&... args); virtual size_t Get_size_v1() const; virtual size_t Get_size_v2() const; virtual const char* Get_name() const; virtual MESSAGE_ID_TYPE Get_id() const; virtual uint8_t Get_extra_byte() const; virtual void Reset(); bool operator == (const Payload& rhs) const; bool operator != (const Payload& rhs) const; TData* operator -> (); const TData* operator -> () const; TData& operator * (); const TData& operator * () const; };
Inherited Members¶
public: // typedefs typedef std::shared_ptr<Payload_base> Ptr; typedef std::weak_ptr<Payload_base> Weak_ptr; // methods template <typename... Args> static Ptr Create(Args&&... args); virtual size_t Get_size_v1() const = 0; virtual size_t Get_size_v2() const = 0; Io_buffer::Ptr Get_buffer() const; std::string Dump() const; virtual const char* Get_name() const = 0; virtual MESSAGE_ID_TYPE Get_id() const = 0; virtual uint8_t Get_extra_byte() const = 0; virtual void Reset() = 0;
Detailed Documentation¶
Generalized MAVLink message payload.
Parameters:
TData |
Structure for payload data. |
Typedefs¶
typedef std::shared_ptr<Payload> Ptr
Pointer type.
typedef std::weak_ptr<Payload> Weak_ptr
Pointer type.
Construction¶
Payload()
All fields are initialized to default values.
Payload(const void* buf, size_t size)
Parse message from data buffer.
The buffer should contain data on wire (in network byte order). Data size can be less than expected payload size. In this case reminder bytes will be set to 0. This is for mavlink2 support which allows trimming trailing zero bytes.
Parameters:
buf |
Pointer to data buffer. |
size |
Size of data available. |
Payload(Io_buffer::Ptr buffer)
Convenience variation of previous constructor.
Parameters:
buffer |
Buffer with data. |
Methods¶
template <typename... Args> static Ptr Create(Args&&... args)
Create an instance.
virtual size_t Get_size_v1() const
Get size of the message payload without extensions in bytes.
virtual size_t Get_size_v2() const
Get size of the message payload in bytes including all extensions.
virtual const char* Get_name() const
Get message name.
virtual MESSAGE_ID_TYPE Get_id() const
Get message id.
virtual uint8_t Get_extra_byte() const
Get extra byte for CRC calculation.
virtual void Reset()
Reset all fields to UgCS default values.
bool operator == (const Payload& rhs) const
Compare if data in the payload is bit-same with another payload.
bool operator != (const Payload& rhs) const
Compare if data in the payload is not bit-same with another payload.
TData* operator -> ()
Pointer access semantics to payload.
const TData* operator -> () const
Constant pointer access semantics to payload.
TData& operator * ()
Dereference access semantics to payload.
const TData& operator * () const
Constant dereference access semantics to payload.