4#define MAVLINK_MSG_ID_VISION_POSITION_DELTA 11011
7typedef struct __mavlink_vision_position_delta_t {
9 uint64_t time_delta_usec;
11 float position_delta[3];
13}) mavlink_vision_position_delta_t;
15#define MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN 44
16#define MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN 44
17#define MAVLINK_MSG_ID_11011_LEN 44
18#define MAVLINK_MSG_ID_11011_MIN_LEN 44
20#define MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC 106
21#define MAVLINK_MSG_ID_11011_CRC 106
23#define MAVLINK_MSG_VISION_POSITION_DELTA_FIELD_ANGLE_DELTA_LEN 3
24#define MAVLINK_MSG_VISION_POSITION_DELTA_FIELD_POSITION_DELTA_LEN 3
26#if MAVLINK_COMMAND_24BIT
27#define MAVLINK_MESSAGE_INFO_VISION_POSITION_DELTA { \
29 "VISION_POSITION_DELTA", \
31 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_delta_t, time_usec) }, \
32 { "time_delta_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_vision_position_delta_t, time_delta_usec) }, \
33 { "angle_delta", NULL, MAVLINK_TYPE_FLOAT, 3, 16, offsetof(mavlink_vision_position_delta_t, angle_delta) }, \
34 { "position_delta", NULL, MAVLINK_TYPE_FLOAT, 3, 28, offsetof(mavlink_vision_position_delta_t, position_delta) }, \
35 { "confidence", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_vision_position_delta_t, confidence) }, \
39#define MAVLINK_MESSAGE_INFO_VISION_POSITION_DELTA { \
40 "VISION_POSITION_DELTA", \
42 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_delta_t, time_usec) }, \
43 { "time_delta_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_vision_position_delta_t, time_delta_usec) }, \
44 { "angle_delta", NULL, MAVLINK_TYPE_FLOAT, 3, 16, offsetof(mavlink_vision_position_delta_t, angle_delta) }, \
45 { "position_delta", NULL, MAVLINK_TYPE_FLOAT, 3, 28, offsetof(mavlink_vision_position_delta_t, position_delta) }, \
46 { "confidence", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_vision_position_delta_t, confidence) }, \
64static inline uint16_t mavlink_msg_vision_position_delta_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
65 uint64_t time_usec, uint64_t time_delta_usec,
const float *angle_delta,
const float *position_delta,
float confidence)
67#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
68 char buf[MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN];
69 _mav_put_uint64_t(buf, 0, time_usec);
70 _mav_put_uint64_t(buf, 8, time_delta_usec);
71 _mav_put_float(buf, 40, confidence);
72 _mav_put_float_array(buf, 16, angle_delta, 3);
73 _mav_put_float_array(buf, 28, position_delta, 3);
74 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN);
76 mavlink_vision_position_delta_t packet;
77 packet.time_usec = time_usec;
78 packet.time_delta_usec = time_delta_usec;
79 packet.confidence = confidence;
80 mav_array_memcpy(packet.angle_delta, angle_delta,
sizeof(
float)*3);
81 mav_array_memcpy(packet.position_delta, position_delta,
sizeof(
float)*3);
82 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN);
85 msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_DELTA;
86 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
102static inline uint16_t mavlink_msg_vision_position_delta_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
103 mavlink_message_t* msg,
104 uint64_t time_usec,uint64_t time_delta_usec,
const float *angle_delta,
const float *position_delta,
float confidence)
106#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
107 char buf[MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN];
108 _mav_put_uint64_t(buf, 0, time_usec);
109 _mav_put_uint64_t(buf, 8, time_delta_usec);
110 _mav_put_float(buf, 40, confidence);
111 _mav_put_float_array(buf, 16, angle_delta, 3);
112 _mav_put_float_array(buf, 28, position_delta, 3);
113 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN);
115 mavlink_vision_position_delta_t packet;
116 packet.time_usec = time_usec;
117 packet.time_delta_usec = time_delta_usec;
118 packet.confidence = confidence;
119 mav_array_memcpy(packet.angle_delta, angle_delta,
sizeof(
float)*3);
120 mav_array_memcpy(packet.position_delta, position_delta,
sizeof(
float)*3);
121 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN);
124 msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_DELTA;
125 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
136static inline uint16_t mavlink_msg_vision_position_delta_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_vision_position_delta_t* vision_position_delta)
138 return mavlink_msg_vision_position_delta_pack(system_id, component_id, msg, vision_position_delta->time_usec, vision_position_delta->time_delta_usec, vision_position_delta->angle_delta, vision_position_delta->position_delta, vision_position_delta->confidence);
150static inline uint16_t mavlink_msg_vision_position_delta_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_vision_position_delta_t* vision_position_delta)
152 return mavlink_msg_vision_position_delta_pack_chan(system_id, component_id, chan, msg, vision_position_delta->time_usec, vision_position_delta->time_delta_usec, vision_position_delta->angle_delta, vision_position_delta->position_delta, vision_position_delta->confidence);
165#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
167static inline void mavlink_msg_vision_position_delta_send(mavlink_channel_t chan, uint64_t time_usec, uint64_t time_delta_usec,
const float *angle_delta,
const float *position_delta,
float confidence)
169#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
170 char buf[MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN];
171 _mav_put_uint64_t(buf, 0, time_usec);
172 _mav_put_uint64_t(buf, 8, time_delta_usec);
173 _mav_put_float(buf, 40, confidence);
174 _mav_put_float_array(buf, 16, angle_delta, 3);
175 _mav_put_float_array(buf, 28, position_delta, 3);
176 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_DELTA, buf, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
178 mavlink_vision_position_delta_t packet;
179 packet.time_usec = time_usec;
180 packet.time_delta_usec = time_delta_usec;
181 packet.confidence = confidence;
182 mav_array_memcpy(packet.angle_delta, angle_delta,
sizeof(
float)*3);
183 mav_array_memcpy(packet.position_delta, position_delta,
sizeof(
float)*3);
184 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_DELTA, (
const char *)&packet, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
193static inline void mavlink_msg_vision_position_delta_send_struct(mavlink_channel_t chan,
const mavlink_vision_position_delta_t* vision_position_delta)
195#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
196 mavlink_msg_vision_position_delta_send(chan, vision_position_delta->time_usec, vision_position_delta->time_delta_usec, vision_position_delta->angle_delta, vision_position_delta->position_delta, vision_position_delta->confidence);
198 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_DELTA, (
const char *)vision_position_delta, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
202#if MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
210static inline void mavlink_msg_vision_position_delta_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint64_t time_delta_usec,
const float *angle_delta,
const float *position_delta,
float confidence)
212#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
213 char *buf = (
char *)msgbuf;
214 _mav_put_uint64_t(buf, 0, time_usec);
215 _mav_put_uint64_t(buf, 8, time_delta_usec);
216 _mav_put_float(buf, 40, confidence);
217 _mav_put_float_array(buf, 16, angle_delta, 3);
218 _mav_put_float_array(buf, 28, position_delta, 3);
219 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_DELTA, buf, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
221 mavlink_vision_position_delta_t *packet = (mavlink_vision_position_delta_t *)msgbuf;
222 packet->time_usec = time_usec;
223 packet->time_delta_usec = time_delta_usec;
224 packet->confidence = confidence;
225 mav_array_memcpy(packet->angle_delta, angle_delta,
sizeof(
float)*3);
226 mav_array_memcpy(packet->position_delta, position_delta,
sizeof(
float)*3);
227 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_DELTA, (
const char *)packet, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
242static inline uint64_t mavlink_msg_vision_position_delta_get_time_usec(
const mavlink_message_t* msg)
244 return _MAV_RETURN_uint64_t(msg, 0);
252static inline uint64_t mavlink_msg_vision_position_delta_get_time_delta_usec(
const mavlink_message_t* msg)
254 return _MAV_RETURN_uint64_t(msg, 8);
262static inline uint16_t mavlink_msg_vision_position_delta_get_angle_delta(
const mavlink_message_t* msg,
float *angle_delta)
264 return _MAV_RETURN_float_array(msg, angle_delta, 3, 16);
272static inline uint16_t mavlink_msg_vision_position_delta_get_position_delta(
const mavlink_message_t* msg,
float *position_delta)
274 return _MAV_RETURN_float_array(msg, position_delta, 3, 28);
282static inline float mavlink_msg_vision_position_delta_get_confidence(
const mavlink_message_t* msg)
284 return _MAV_RETURN_float(msg, 40);
293static inline void mavlink_msg_vision_position_delta_decode(
const mavlink_message_t* msg, mavlink_vision_position_delta_t* vision_position_delta)
295#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
296 vision_position_delta->time_usec = mavlink_msg_vision_position_delta_get_time_usec(msg);
297 vision_position_delta->time_delta_usec = mavlink_msg_vision_position_delta_get_time_delta_usec(msg);
298 mavlink_msg_vision_position_delta_get_angle_delta(msg, vision_position_delta->angle_delta);
299 mavlink_msg_vision_position_delta_get_position_delta(msg, vision_position_delta->position_delta);
300 vision_position_delta->confidence = mavlink_msg_vision_position_delta_get_confidence(msg);
302 uint8_t len = msg->len < MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN? msg->len : MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN;
303 memset(vision_position_delta, 0, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN);
304 memcpy(vision_position_delta, _MAV_PAYLOAD(msg), len);