21 #include <mavconn/mavlink_dialect.h> 42 explicit MsgBuffer(
const mavlink::mavlink_message_t *msg) :
45 len = mavlink::mavlink_msg_to_send_buffer(data, msg);
47 assert(len < MAX_SIZE);
56 mavlink::mavlink_message_t msg;
62 mavlink::mavlink_finalize_message_buffer(&msg, sysid, compid, status, mi.min_length, mi.length, mi.crc_extra);
64 len = mavlink::mavlink_msg_to_send_buffer(data, &msg);
66 assert(len < MAX_SIZE);
77 assert(0 < nbytes && nbytes < MAX_SIZE);
78 memcpy(data, bytes, nbytes);
#define MAVLINK_MAX_PACKET_LEN
virtual void serialize(MsgMap &map) const =0
virtual Info get_message_info(void) const =0
MsgBuffer(const mavlink::Message &obj, mavlink::mavlink_status_t *status, uint8_t sysid, uint8_t compid)
Buffer constructor for mavlink::Message derived object.
MsgBuffer(const mavlink::mavlink_message_t *msg)
Buffer constructor from mavlink_message_t.
MsgBuffer(const uint8_t *bytes, ssize_t nbytes)
Buffer constructor for send_bytes()
Message buffer for internal use in libmavconn.
static constexpr ssize_t MAX_SIZE
Maximum buffer size with padding for CRC bytes (280 + padding)