mavlink_msg_encapsulated_data.h 5.6 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3
// MESSAGE ENCAPSULATED_DATA PACKING

#define MAVLINK_MSG_ID_ENCAPSULATED_DATA 171
lm's avatar
lm committed
4 5
#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN 255
#define MAVLINK_MSG_171_LEN 255
lm's avatar
lm committed
6 7
#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_KEY 0x87
#define MAVLINK_MSG_171_KEY 0x87
James Goppert's avatar
James Goppert committed
8 9 10

typedef struct __mavlink_encapsulated_data_t 
{
lm's avatar
lm committed
11 12
	uint16_t seqnr;	///< sequence number (starting with 0 on every transmission)
	uint8_t data[253];	///< image data bytes
James Goppert's avatar
James Goppert committed
13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28

} mavlink_encapsulated_data_t;
#define MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN 253

/**
 * @brief Pack a encapsulated_data message
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 *
 * @param seqnr sequence number (starting with 0 on every transmission)
 * @param data image data bytes
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_encapsulated_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t seqnr, const uint8_t* data)
{
lm's avatar
lm committed
29
	mavlink_encapsulated_data_t *p = (mavlink_encapsulated_data_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
30 31
	msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA;

lm's avatar
lm committed
32 33
	p->seqnr = seqnr;	// uint16_t:sequence number (starting with 0 on every transmission)
	memcpy(p->data, data, sizeof(p->data));	// uint8_t[253]:image data bytes
James Goppert's avatar
James Goppert committed
34

lm's avatar
lm committed
35
	return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
James Goppert's avatar
James Goppert committed
36 37 38 39 40 41 42 43 44 45 46 47 48 49
}

/**
 * @brief Pack a encapsulated_data message
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param chan The MAVLink channel this message was sent over
 * @param msg The MAVLink message to compress the data into
 * @param seqnr sequence number (starting with 0 on every transmission)
 * @param data image data bytes
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_encapsulated_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t seqnr, const uint8_t* data)
{
lm's avatar
lm committed
50
	mavlink_encapsulated_data_t *p = (mavlink_encapsulated_data_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
51 52
	msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA;

lm's avatar
lm committed
53 54
	p->seqnr = seqnr;	// uint16_t:sequence number (starting with 0 on every transmission)
	memcpy(p->data, data, sizeof(p->data));	// uint8_t[253]:image data bytes
James Goppert's avatar
James Goppert committed
55

lm's avatar
lm committed
56
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
James Goppert's avatar
James Goppert committed
57 58 59 60 61 62 63 64 65 66 67 68 69 70 71
}

/**
 * @brief Encode a encapsulated_data struct into a message
 *
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 * @param encapsulated_data C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_encapsulated_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data)
{
	return mavlink_msg_encapsulated_data_pack(system_id, component_id, msg, encapsulated_data->seqnr, encapsulated_data->data);
}

lm's avatar
lm committed
72 73

#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
James Goppert's avatar
James Goppert committed
74 75 76 77 78 79 80
/**
 * @brief Send a encapsulated_data message
 * @param chan MAVLink channel to send the message
 *
 * @param seqnr sequence number (starting with 0 on every transmission)
 * @param data image data bytes
 */
lm's avatar
lm committed
81 82 83 84 85
static inline void mavlink_msg_encapsulated_data_send(mavlink_channel_t chan, uint16_t seqnr, const uint8_t* data)
{
	mavlink_header_t hdr;
	mavlink_encapsulated_data_t payload;

lm's avatar
lm committed
86 87 88
	MAVLINK_BUFFER_CHECK_START( chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN )
	payload.seqnr = seqnr;	// uint16_t:sequence number (starting with 0 on every transmission)
	memcpy(payload.data, data, sizeof(payload.data));	// uint8_t[253]:image data bytes
lm's avatar
lm committed
89 90 91 92 93 94 95 96 97

	hdr.STX = MAVLINK_STX;
	hdr.len = MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN;
	hdr.msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA;
	hdr.sysid = mavlink_system.sysid;
	hdr.compid = mavlink_system.compid;
	hdr.seq = mavlink_get_channel_status(chan)->current_tx_seq;
	mavlink_get_channel_status(chan)->current_tx_seq = hdr.seq + 1;
	mavlink_send_mem(chan, (uint8_t *)&hdr.STX, MAVLINK_NUM_HEADER_BYTES );
98
	mavlink_send_mem(chan, (uint8_t *)&payload, sizeof(payload) );
lm's avatar
lm committed
99

lm's avatar
lm committed
100 101 102 103 104 105
	crc_init(&hdr.ck);
	crc_calculate_mem((uint8_t *)&hdr.len, &hdr.ck, MAVLINK_CORE_HEADER_LEN);
	crc_calculate_mem((uint8_t *)&payload, &hdr.ck, hdr.len );
	crc_accumulate( 0x87, &hdr.ck); /// include key in X25 checksum
	mavlink_send_mem(chan, (uint8_t *)&hdr.ck, MAVLINK_NUM_CHECKSUM_BYTES);
	MAVLINK_BUFFER_CHECK_END
James Goppert's avatar
James Goppert committed
106 107 108 109 110 111 112 113 114 115 116 117
}

#endif
// MESSAGE ENCAPSULATED_DATA UNPACKING

/**
 * @brief Get field seqnr from encapsulated_data message
 *
 * @return sequence number (starting with 0 on every transmission)
 */
static inline uint16_t mavlink_msg_encapsulated_data_get_seqnr(const mavlink_message_t* msg)
{
lm's avatar
lm committed
118 119
	mavlink_encapsulated_data_t *p = (mavlink_encapsulated_data_t *)&msg->payload[0];
	return (uint16_t)(p->seqnr);
James Goppert's avatar
James Goppert committed
120 121 122 123 124 125 126
}

/**
 * @brief Get field data from encapsulated_data message
 *
 * @return image data bytes
 */
lm's avatar
lm committed
127
static inline uint16_t mavlink_msg_encapsulated_data_get_data(const mavlink_message_t* msg, uint8_t* data)
James Goppert's avatar
James Goppert committed
128
{
lm's avatar
lm committed
129
	mavlink_encapsulated_data_t *p = (mavlink_encapsulated_data_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
130

lm's avatar
lm committed
131 132
	memcpy(data, p->data, sizeof(p->data));
	return sizeof(p->data);
James Goppert's avatar
James Goppert committed
133 134 135 136 137 138 139 140 141 142
}

/**
 * @brief Decode a encapsulated_data message into a struct
 *
 * @param msg The message to decode
 * @param encapsulated_data C-struct to decode the message contents into
 */
static inline void mavlink_msg_encapsulated_data_decode(const mavlink_message_t* msg, mavlink_encapsulated_data_t* encapsulated_data)
{
lm's avatar
lm committed
143
	memcpy( encapsulated_data, msg->payload, sizeof(mavlink_encapsulated_data_t));
James Goppert's avatar
James Goppert committed
144
}