class ugcs::vsm::Mavlink_decoder¶
Overview¶
Decodes Mavlink 1.0 messages from byte stream. More…
#include <mavlink_decoder.h> class Mavlink_decoder { public: // typedefs typedef Callback_proxy<void, Io_buffer::Ptr, mavlink::MESSAGE_ID_TYPE, uint8_t, uint8_t, uint32_t> Handler; typedef Callback_proxy<void, Io_buffer::Ptr> Raw_data_handler; // construction Mavlink_decoder(); Mavlink_decoder(const Mavlink_decoder&); // methods 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) ); typename __Args __DEFINE_CALLBACK_BUILDER_BODY(Make_raw_data_handler, (Io_buffer::Ptr), (nullptr)); void Disable(); void Register_handler(Handler handler); void Register_raw_data_handler(Raw_data_handler handler); void Decode(Io_buffer::Ptr buffer); size_t Get_next_read_size() const; const Mavlink_decoder::Stats Get_stats(int system_id); const Mavlink_decoder::Stats Get_common_stats(); };
Detailed Documentation¶
Decodes Mavlink 1.0 messages from byte stream.
Typedefs¶
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.
Arguments are:
Payload buffer
Message id
Sending system id
Sending component id
typedef Callback_proxy<void, Io_buffer::Ptr> Raw_data_handler
Handler for the raw data going through the decoder.
Construction¶
Mavlink_decoder()
Default constructor.
Mavlink_decoder(const Mavlink_decoder&)
Delete copy constructor.
Methods¶
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) )
Convenience builder for Mavlink decoder handlers.
Convenience builder for raw data handlers.
typename __Args __DEFINE_CALLBACK_BUILDER_BODY( Make_raw_data_handler, (Io_buffer::Ptr), (nullptr) )
Decoder statistics.
void Disable()
Should be called prior to intention to delete the instance.
void Register_handler(Handler handler)
Register handler for successfully decoded Mavlink messages.
void Decode(Io_buffer::Ptr buffer)
Decode buffer from the wire.
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.
Returns:
Exact number of bytes to be read by next read operation.
const Mavlink_decoder::Stats Get_stats(int system_id)
Get read-only access to statistics.
Supports multiple system_ids on one connection.
Parameters:
system_id |
system 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.
const Mavlink_decoder::Stats Get_common_stats()
Get read-only access to common statistics.