2 // MESSAGE VISION_SPEED_ESTIMATE PACKING
4 #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 103
7 typedef struct __mavlink_vision_speed_estimate_t
{
8 uint64_t usec
; /*< [us] Timestamp (UNIX time or time since system boot)*/
9 float x
; /*< [m/s] Global X speed*/
10 float y
; /*< [m/s] Global Y speed*/
11 float z
; /*< [m/s] Global Z speed*/
12 float covariance
[9]; /*< Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array.*/
13 uint8_t reset_counter
; /*< Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.*/
14 } mavlink_vision_speed_estimate_t
;
16 #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 57
17 #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN 20
18 #define MAVLINK_MSG_ID_103_LEN 57
19 #define MAVLINK_MSG_ID_103_MIN_LEN 20
21 #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC 208
22 #define MAVLINK_MSG_ID_103_CRC 208
24 #define MAVLINK_MSG_VISION_SPEED_ESTIMATE_FIELD_COVARIANCE_LEN 9
26 #if MAVLINK_COMMAND_24BIT
27 #define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE { \
29 "VISION_SPEED_ESTIMATE", \
31 { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_speed_estimate_t, usec) }, \
32 { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_speed_estimate_t, x) }, \
33 { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_speed_estimate_t, y) }, \
34 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_speed_estimate_t, z) }, \
35 { "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 20, offsetof(mavlink_vision_speed_estimate_t, covariance) }, \
36 { "reset_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 56, offsetof(mavlink_vision_speed_estimate_t, reset_counter) }, \
40 #define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE { \
41 "VISION_SPEED_ESTIMATE", \
43 { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_speed_estimate_t, usec) }, \
44 { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_speed_estimate_t, x) }, \
45 { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_speed_estimate_t, y) }, \
46 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_speed_estimate_t, z) }, \
47 { "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 20, offsetof(mavlink_vision_speed_estimate_t, covariance) }, \
48 { "reset_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 56, offsetof(mavlink_vision_speed_estimate_t, reset_counter) }, \
54 * @brief Pack a vision_speed_estimate message
55 * @param system_id ID of this system
56 * @param component_id ID of this component (e.g. 200 for IMU)
57 * @param msg The MAVLink message to compress the data into
59 * @param usec [us] Timestamp (UNIX time or time since system boot)
60 * @param x [m/s] Global X speed
61 * @param y [m/s] Global Y speed
62 * @param z [m/s] Global Z speed
63 * @param covariance Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array.
64 * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
65 * @return length of the message in bytes (excluding serial stream start sign)
67 static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
68 uint64_t usec
, float x
, float y
, float z
, const float *covariance
, uint8_t reset_counter
)
70 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
71 char buf
[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN
];
72 _mav_put_uint64_t(buf
, 0, usec
);
73 _mav_put_float(buf
, 8, x
);
74 _mav_put_float(buf
, 12, y
);
75 _mav_put_float(buf
, 16, z
);
76 _mav_put_uint8_t(buf
, 56, reset_counter
);
77 _mav_put_float_array(buf
, 20, covariance
, 9);
78 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN
);
80 mavlink_vision_speed_estimate_t packet
;
85 packet
.reset_counter
= reset_counter
;
86 mav_array_memcpy(packet
.covariance
, covariance
, sizeof(float)*9);
87 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN
);
90 msg
->msgid
= MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE
;
91 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC
);
95 * @brief Pack a vision_speed_estimate message on a channel
96 * @param system_id ID of this system
97 * @param component_id ID of this component (e.g. 200 for IMU)
98 * @param chan The MAVLink channel this message will be sent over
99 * @param msg The MAVLink message to compress the data into
100 * @param usec [us] Timestamp (UNIX time or time since system boot)
101 * @param x [m/s] Global X speed
102 * @param y [m/s] Global Y speed
103 * @param z [m/s] Global Z speed
104 * @param covariance Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array.
105 * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
106 * @return length of the message in bytes (excluding serial stream start sign)
108 static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
109 mavlink_message_t
* msg
,
110 uint64_t usec
,float x
,float y
,float z
,const float *covariance
,uint8_t reset_counter
)
112 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
113 char buf
[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN
];
114 _mav_put_uint64_t(buf
, 0, usec
);
115 _mav_put_float(buf
, 8, x
);
116 _mav_put_float(buf
, 12, y
);
117 _mav_put_float(buf
, 16, z
);
118 _mav_put_uint8_t(buf
, 56, reset_counter
);
119 _mav_put_float_array(buf
, 20, covariance
, 9);
120 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN
);
122 mavlink_vision_speed_estimate_t packet
;
127 packet
.reset_counter
= reset_counter
;
128 mav_array_memcpy(packet
.covariance
, covariance
, sizeof(float)*9);
129 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN
);
132 msg
->msgid
= MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE
;
133 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC
);
137 * @brief Encode a vision_speed_estimate struct
139 * @param system_id ID of this system
140 * @param component_id ID of this component (e.g. 200 for IMU)
141 * @param msg The MAVLink message to compress the data into
142 * @param vision_speed_estimate C-struct to read the message contents from
144 static inline uint16_t mavlink_msg_vision_speed_estimate_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
, const mavlink_vision_speed_estimate_t
* vision_speed_estimate
)
146 return mavlink_msg_vision_speed_estimate_pack(system_id
, component_id
, msg
, vision_speed_estimate
->usec
, vision_speed_estimate
->x
, vision_speed_estimate
->y
, vision_speed_estimate
->z
, vision_speed_estimate
->covariance
, vision_speed_estimate
->reset_counter
);
150 * @brief Encode a vision_speed_estimate struct on a channel
152 * @param system_id ID of this system
153 * @param component_id ID of this component (e.g. 200 for IMU)
154 * @param chan The MAVLink channel this message will be sent over
155 * @param msg The MAVLink message to compress the data into
156 * @param vision_speed_estimate C-struct to read the message contents from
158 static inline uint16_t mavlink_msg_vision_speed_estimate_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_vision_speed_estimate_t
* vision_speed_estimate
)
160 return mavlink_msg_vision_speed_estimate_pack_chan(system_id
, component_id
, chan
, msg
, vision_speed_estimate
->usec
, vision_speed_estimate
->x
, vision_speed_estimate
->y
, vision_speed_estimate
->z
, vision_speed_estimate
->covariance
, vision_speed_estimate
->reset_counter
);
164 * @brief Send a vision_speed_estimate message
165 * @param chan MAVLink channel to send the message
167 * @param usec [us] Timestamp (UNIX time or time since system boot)
168 * @param x [m/s] Global X speed
169 * @param y [m/s] Global Y speed
170 * @param z [m/s] Global Z speed
171 * @param covariance Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array.
172 * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
174 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
176 static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan
, uint64_t usec
, float x
, float y
, float z
, const float *covariance
, uint8_t reset_counter
)
178 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
179 char buf
[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN
];
180 _mav_put_uint64_t(buf
, 0, usec
);
181 _mav_put_float(buf
, 8, x
);
182 _mav_put_float(buf
, 12, y
);
183 _mav_put_float(buf
, 16, z
);
184 _mav_put_uint8_t(buf
, 56, reset_counter
);
185 _mav_put_float_array(buf
, 20, covariance
, 9);
186 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE
, buf
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC
);
188 mavlink_vision_speed_estimate_t packet
;
193 packet
.reset_counter
= reset_counter
;
194 mav_array_memcpy(packet
.covariance
, covariance
, sizeof(float)*9);
195 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE
, (const char *)&packet
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC
);
200 * @brief Send a vision_speed_estimate message
201 * @param chan MAVLink channel to send the message
202 * @param struct The MAVLink struct to serialize
204 static inline void mavlink_msg_vision_speed_estimate_send_struct(mavlink_channel_t chan
, const mavlink_vision_speed_estimate_t
* vision_speed_estimate
)
206 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
207 mavlink_msg_vision_speed_estimate_send(chan
, vision_speed_estimate
->usec
, vision_speed_estimate
->x
, vision_speed_estimate
->y
, vision_speed_estimate
->z
, vision_speed_estimate
->covariance
, vision_speed_estimate
->reset_counter
);
209 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE
, (const char *)vision_speed_estimate
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC
);
213 #if MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
215 This varient of _send() can be used to save stack space by re-using
216 memory from the receive buffer. The caller provides a
217 mavlink_message_t which is the size of a full mavlink message. This
218 is usually the receive buffer for the channel, and allows a reply to an
219 incoming message with minimum stack space usage.
221 static inline void mavlink_msg_vision_speed_estimate_send_buf(mavlink_message_t
*msgbuf
, mavlink_channel_t chan
, uint64_t usec
, float x
, float y
, float z
, const float *covariance
, uint8_t reset_counter
)
223 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
224 char *buf
= (char *)msgbuf
;
225 _mav_put_uint64_t(buf
, 0, usec
);
226 _mav_put_float(buf
, 8, x
);
227 _mav_put_float(buf
, 12, y
);
228 _mav_put_float(buf
, 16, z
);
229 _mav_put_uint8_t(buf
, 56, reset_counter
);
230 _mav_put_float_array(buf
, 20, covariance
, 9);
231 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE
, buf
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC
);
233 mavlink_vision_speed_estimate_t
*packet
= (mavlink_vision_speed_estimate_t
*)msgbuf
;
238 packet
->reset_counter
= reset_counter
;
239 mav_array_memcpy(packet
->covariance
, covariance
, sizeof(float)*9);
240 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE
, (const char *)packet
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC
);
247 // MESSAGE VISION_SPEED_ESTIMATE UNPACKING
251 * @brief Get field usec from vision_speed_estimate message
253 * @return [us] Timestamp (UNIX time or time since system boot)
255 static inline uint64_t mavlink_msg_vision_speed_estimate_get_usec(const mavlink_message_t
* msg
)
257 return _MAV_RETURN_uint64_t(msg
, 0);
261 * @brief Get field x from vision_speed_estimate message
263 * @return [m/s] Global X speed
265 static inline float mavlink_msg_vision_speed_estimate_get_x(const mavlink_message_t
* msg
)
267 return _MAV_RETURN_float(msg
, 8);
271 * @brief Get field y from vision_speed_estimate message
273 * @return [m/s] Global Y speed
275 static inline float mavlink_msg_vision_speed_estimate_get_y(const mavlink_message_t
* msg
)
277 return _MAV_RETURN_float(msg
, 12);
281 * @brief Get field z from vision_speed_estimate message
283 * @return [m/s] Global Z speed
285 static inline float mavlink_msg_vision_speed_estimate_get_z(const mavlink_message_t
* msg
)
287 return _MAV_RETURN_float(msg
, 16);
291 * @brief Get field covariance from vision_speed_estimate message
293 * @return Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array.
295 static inline uint16_t mavlink_msg_vision_speed_estimate_get_covariance(const mavlink_message_t
* msg
, float *covariance
)
297 return _MAV_RETURN_float_array(msg
, covariance
, 9, 20);
301 * @brief Get field reset_counter from vision_speed_estimate message
303 * @return Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
305 static inline uint8_t mavlink_msg_vision_speed_estimate_get_reset_counter(const mavlink_message_t
* msg
)
307 return _MAV_RETURN_uint8_t(msg
, 56);
311 * @brief Decode a vision_speed_estimate message into a struct
313 * @param msg The message to decode
314 * @param vision_speed_estimate C-struct to decode the message contents into
316 static inline void mavlink_msg_vision_speed_estimate_decode(const mavlink_message_t
* msg
, mavlink_vision_speed_estimate_t
* vision_speed_estimate
)
318 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
319 vision_speed_estimate
->usec
= mavlink_msg_vision_speed_estimate_get_usec(msg
);
320 vision_speed_estimate
->x
= mavlink_msg_vision_speed_estimate_get_x(msg
);
321 vision_speed_estimate
->y
= mavlink_msg_vision_speed_estimate_get_y(msg
);
322 vision_speed_estimate
->z
= mavlink_msg_vision_speed_estimate_get_z(msg
);
323 mavlink_msg_vision_speed_estimate_get_covariance(msg
, vision_speed_estimate
->covariance
);
324 vision_speed_estimate
->reset_counter
= mavlink_msg_vision_speed_estimate_get_reset_counter(msg
);
326 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN
? msg
->len
: MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN
;
327 memset(vision_speed_estimate
, 0, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN
);
328 memcpy(vision_speed_estimate
, _MAV_PAYLOAD(msg
), len
);