1 // MESSAGE VISION_SPEED_ESTIMATE PACKING
3 #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 103
5 typedef struct __mavlink_vision_speed_estimate_t
{
6 uint64_t usec
; ///< Timestamp (milliseconds)
7 float x
; ///< Global X speed
8 float y
; ///< Global Y speed
9 float z
; ///< Global Z speed
10 } mavlink_vision_speed_estimate_t
;
12 #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 20
13 #define MAVLINK_MSG_ID_103_LEN 20
16 #define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE \
18 "VISION_SPEED_ESTIMATE", \
21 { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_speed_estimate_t, usec) }, \
22 { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_speed_estimate_t, x) }, \
23 { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_speed_estimate_t, y) }, \
24 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_speed_estimate_t, z) }, \
30 * @brief Pack a vision_speed_estimate message
31 * @param system_id ID of this system
32 * @param component_id ID of this component (e.g. 200 for IMU)
33 * @param msg The MAVLink message to compress the data into
35 * @param usec Timestamp (milliseconds)
36 * @param x Global X speed
37 * @param y Global Y speed
38 * @param z Global Z speed
39 * @return length of the message in bytes (excluding serial stream start sign)
41 static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
*msg
,
42 uint64_t usec
, float x
, float y
, float z
)
44 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
46 _mav_put_uint64_t(buf
, 0, usec
);
47 _mav_put_float(buf
, 8, x
);
48 _mav_put_float(buf
, 12, y
);
49 _mav_put_float(buf
, 16, z
);
51 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 20);
53 mavlink_vision_speed_estimate_t packet
;
59 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 20);
62 msg
->msgid
= MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE
;
63 return mavlink_finalize_message(msg
, system_id
, component_id
, 20, 208);
67 * @brief Pack a vision_speed_estimate message on a channel
68 * @param system_id ID of this system
69 * @param component_id ID of this component (e.g. 200 for IMU)
70 * @param chan The MAVLink channel this message was sent over
71 * @param msg The MAVLink message to compress the data into
72 * @param usec Timestamp (milliseconds)
73 * @param x Global X speed
74 * @param y Global Y speed
75 * @param z Global Z speed
76 * @return length of the message in bytes (excluding serial stream start sign)
78 static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
79 mavlink_message_t
*msg
,
80 uint64_t usec
, float x
, float y
, float z
)
82 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
84 _mav_put_uint64_t(buf
, 0, usec
);
85 _mav_put_float(buf
, 8, x
);
86 _mav_put_float(buf
, 12, y
);
87 _mav_put_float(buf
, 16, z
);
89 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 20);
91 mavlink_vision_speed_estimate_t packet
;
97 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 20);
100 msg
->msgid
= MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE
;
101 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, 20, 208);
105 * @brief Encode a vision_speed_estimate struct into a message
107 * @param system_id ID of this system
108 * @param component_id ID of this component (e.g. 200 for IMU)
109 * @param msg The MAVLink message to compress the data into
110 * @param vision_speed_estimate C-struct to read the message contents from
112 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
)
114 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
);
118 * @brief Send a vision_speed_estimate message
119 * @param chan MAVLink channel to send the message
121 * @param usec Timestamp (milliseconds)
122 * @param x Global X speed
123 * @param y Global Y speed
124 * @param z Global Z speed
126 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
128 static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan
, uint64_t usec
, float x
, float y
, float z
)
130 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
132 _mav_put_uint64_t(buf
, 0, usec
);
133 _mav_put_float(buf
, 8, x
);
134 _mav_put_float(buf
, 12, y
);
135 _mav_put_float(buf
, 16, z
);
137 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE
, buf
, 20, 208);
139 mavlink_vision_speed_estimate_t packet
;
145 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE
, (const char *)&packet
, 20, 208);
149 #endif // ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
151 // MESSAGE VISION_SPEED_ESTIMATE UNPACKING
155 * @brief Get field usec from vision_speed_estimate message
157 * @return Timestamp (milliseconds)
159 static inline uint64_t mavlink_msg_vision_speed_estimate_get_usec(const mavlink_message_t
*msg
)
161 return _MAV_RETURN_uint64_t(msg
, 0);
165 * @brief Get field x from vision_speed_estimate message
167 * @return Global X speed
169 static inline float mavlink_msg_vision_speed_estimate_get_x(const mavlink_message_t
*msg
)
171 return _MAV_RETURN_float(msg
, 8);
175 * @brief Get field y from vision_speed_estimate message
177 * @return Global Y speed
179 static inline float mavlink_msg_vision_speed_estimate_get_y(const mavlink_message_t
*msg
)
181 return _MAV_RETURN_float(msg
, 12);
185 * @brief Get field z from vision_speed_estimate message
187 * @return Global Z speed
189 static inline float mavlink_msg_vision_speed_estimate_get_z(const mavlink_message_t
*msg
)
191 return _MAV_RETURN_float(msg
, 16);
195 * @brief Decode a vision_speed_estimate message into a struct
197 * @param msg The message to decode
198 * @param vision_speed_estimate C-struct to decode the message contents into
200 static inline void mavlink_msg_vision_speed_estimate_decode(const mavlink_message_t
*msg
, mavlink_vision_speed_estimate_t
*vision_speed_estimate
)
202 #if MAVLINK_NEED_BYTE_SWAP
203 vision_speed_estimate
->usec
= mavlink_msg_vision_speed_estimate_get_usec(msg
);
204 vision_speed_estimate
->x
= mavlink_msg_vision_speed_estimate_get_x(msg
);
205 vision_speed_estimate
->y
= mavlink_msg_vision_speed_estimate_get_y(msg
);
206 vision_speed_estimate
->z
= mavlink_msg_vision_speed_estimate_get_z(msg
);
208 memcpy(vision_speed_estimate
, _MAV_PAYLOAD(msg
), 20);