2 // MESSAGE MOUNT_ORIENTATION PACKING
4 #define MAVLINK_MSG_ID_MOUNT_ORIENTATION 265
7 typedef struct __mavlink_mount_orientation_t
{
8 uint32_t time_boot_ms
; /*< [ms] Timestamp (time since system boot).*/
9 float roll
; /*< [deg] Roll in global frame (set to NaN for invalid).*/
10 float pitch
; /*< [deg] Pitch in global frame (set to NaN for invalid).*/
11 float yaw
; /*< [deg] Yaw relative to vehicle (set to NaN for invalid).*/
12 float yaw_absolute
; /*< [deg] Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid).*/
13 } mavlink_mount_orientation_t
;
15 #define MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN 20
16 #define MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN 16
17 #define MAVLINK_MSG_ID_265_LEN 20
18 #define MAVLINK_MSG_ID_265_MIN_LEN 16
20 #define MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC 26
21 #define MAVLINK_MSG_ID_265_CRC 26
25 #if MAVLINK_COMMAND_24BIT
26 #define MAVLINK_MESSAGE_INFO_MOUNT_ORIENTATION { \
28 "MOUNT_ORIENTATION", \
30 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_mount_orientation_t, time_boot_ms) }, \
31 { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mount_orientation_t, roll) }, \
32 { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mount_orientation_t, pitch) }, \
33 { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mount_orientation_t, yaw) }, \
34 { "yaw_absolute", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mount_orientation_t, yaw_absolute) }, \
38 #define MAVLINK_MESSAGE_INFO_MOUNT_ORIENTATION { \
39 "MOUNT_ORIENTATION", \
41 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_mount_orientation_t, time_boot_ms) }, \
42 { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mount_orientation_t, roll) }, \
43 { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mount_orientation_t, pitch) }, \
44 { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mount_orientation_t, yaw) }, \
45 { "yaw_absolute", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mount_orientation_t, yaw_absolute) }, \
51 * @brief Pack a mount_orientation message
52 * @param system_id ID of this system
53 * @param component_id ID of this component (e.g. 200 for IMU)
54 * @param msg The MAVLink message to compress the data into
56 * @param time_boot_ms [ms] Timestamp (time since system boot).
57 * @param roll [deg] Roll in global frame (set to NaN for invalid).
58 * @param pitch [deg] Pitch in global frame (set to NaN for invalid).
59 * @param yaw [deg] Yaw relative to vehicle (set to NaN for invalid).
60 * @param yaw_absolute [deg] Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid).
61 * @return length of the message in bytes (excluding serial stream start sign)
63 static inline uint16_t mavlink_msg_mount_orientation_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
64 uint32_t time_boot_ms
, float roll
, float pitch
, float yaw
, float yaw_absolute
)
66 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
67 char buf
[MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN
];
68 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
69 _mav_put_float(buf
, 4, roll
);
70 _mav_put_float(buf
, 8, pitch
);
71 _mav_put_float(buf
, 12, yaw
);
72 _mav_put_float(buf
, 16, yaw_absolute
);
74 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN
);
76 mavlink_mount_orientation_t packet
;
77 packet
.time_boot_ms
= time_boot_ms
;
81 packet
.yaw_absolute
= yaw_absolute
;
83 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN
);
86 msg
->msgid
= MAVLINK_MSG_ID_MOUNT_ORIENTATION
;
87 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC
);
91 * @brief Pack a mount_orientation message on a channel
92 * @param system_id ID of this system
93 * @param component_id ID of this component (e.g. 200 for IMU)
94 * @param chan The MAVLink channel this message will be sent over
95 * @param msg The MAVLink message to compress the data into
96 * @param time_boot_ms [ms] Timestamp (time since system boot).
97 * @param roll [deg] Roll in global frame (set to NaN for invalid).
98 * @param pitch [deg] Pitch in global frame (set to NaN for invalid).
99 * @param yaw [deg] Yaw relative to vehicle (set to NaN for invalid).
100 * @param yaw_absolute [deg] Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid).
101 * @return length of the message in bytes (excluding serial stream start sign)
103 static inline uint16_t mavlink_msg_mount_orientation_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
104 mavlink_message_t
* msg
,
105 uint32_t time_boot_ms
,float roll
,float pitch
,float yaw
,float yaw_absolute
)
107 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
108 char buf
[MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN
];
109 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
110 _mav_put_float(buf
, 4, roll
);
111 _mav_put_float(buf
, 8, pitch
);
112 _mav_put_float(buf
, 12, yaw
);
113 _mav_put_float(buf
, 16, yaw_absolute
);
115 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN
);
117 mavlink_mount_orientation_t packet
;
118 packet
.time_boot_ms
= time_boot_ms
;
120 packet
.pitch
= pitch
;
122 packet
.yaw_absolute
= yaw_absolute
;
124 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN
);
127 msg
->msgid
= MAVLINK_MSG_ID_MOUNT_ORIENTATION
;
128 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC
);
132 * @brief Encode a mount_orientation struct
134 * @param system_id ID of this system
135 * @param component_id ID of this component (e.g. 200 for IMU)
136 * @param msg The MAVLink message to compress the data into
137 * @param mount_orientation C-struct to read the message contents from
139 static inline uint16_t mavlink_msg_mount_orientation_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
, const mavlink_mount_orientation_t
* mount_orientation
)
141 return mavlink_msg_mount_orientation_pack(system_id
, component_id
, msg
, mount_orientation
->time_boot_ms
, mount_orientation
->roll
, mount_orientation
->pitch
, mount_orientation
->yaw
, mount_orientation
->yaw_absolute
);
145 * @brief Encode a mount_orientation struct on a channel
147 * @param system_id ID of this system
148 * @param component_id ID of this component (e.g. 200 for IMU)
149 * @param chan The MAVLink channel this message will be sent over
150 * @param msg The MAVLink message to compress the data into
151 * @param mount_orientation C-struct to read the message contents from
153 static inline uint16_t mavlink_msg_mount_orientation_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_mount_orientation_t
* mount_orientation
)
155 return mavlink_msg_mount_orientation_pack_chan(system_id
, component_id
, chan
, msg
, mount_orientation
->time_boot_ms
, mount_orientation
->roll
, mount_orientation
->pitch
, mount_orientation
->yaw
, mount_orientation
->yaw_absolute
);
159 * @brief Send a mount_orientation message
160 * @param chan MAVLink channel to send the message
162 * @param time_boot_ms [ms] Timestamp (time since system boot).
163 * @param roll [deg] Roll in global frame (set to NaN for invalid).
164 * @param pitch [deg] Pitch in global frame (set to NaN for invalid).
165 * @param yaw [deg] Yaw relative to vehicle (set to NaN for invalid).
166 * @param yaw_absolute [deg] Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid).
168 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
170 static inline void mavlink_msg_mount_orientation_send(mavlink_channel_t chan
, uint32_t time_boot_ms
, float roll
, float pitch
, float yaw
, float yaw_absolute
)
172 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
173 char buf
[MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN
];
174 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
175 _mav_put_float(buf
, 4, roll
);
176 _mav_put_float(buf
, 8, pitch
);
177 _mav_put_float(buf
, 12, yaw
);
178 _mav_put_float(buf
, 16, yaw_absolute
);
180 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_MOUNT_ORIENTATION
, buf
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC
);
182 mavlink_mount_orientation_t packet
;
183 packet
.time_boot_ms
= time_boot_ms
;
185 packet
.pitch
= pitch
;
187 packet
.yaw_absolute
= yaw_absolute
;
189 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_MOUNT_ORIENTATION
, (const char *)&packet
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC
);
194 * @brief Send a mount_orientation message
195 * @param chan MAVLink channel to send the message
196 * @param struct The MAVLink struct to serialize
198 static inline void mavlink_msg_mount_orientation_send_struct(mavlink_channel_t chan
, const mavlink_mount_orientation_t
* mount_orientation
)
200 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
201 mavlink_msg_mount_orientation_send(chan
, mount_orientation
->time_boot_ms
, mount_orientation
->roll
, mount_orientation
->pitch
, mount_orientation
->yaw
, mount_orientation
->yaw_absolute
);
203 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_MOUNT_ORIENTATION
, (const char *)mount_orientation
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC
);
207 #if MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
209 This varient of _send() can be used to save stack space by re-using
210 memory from the receive buffer. The caller provides a
211 mavlink_message_t which is the size of a full mavlink message. This
212 is usually the receive buffer for the channel, and allows a reply to an
213 incoming message with minimum stack space usage.
215 static inline void mavlink_msg_mount_orientation_send_buf(mavlink_message_t
*msgbuf
, mavlink_channel_t chan
, uint32_t time_boot_ms
, float roll
, float pitch
, float yaw
, float yaw_absolute
)
217 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
218 char *buf
= (char *)msgbuf
;
219 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
220 _mav_put_float(buf
, 4, roll
);
221 _mav_put_float(buf
, 8, pitch
);
222 _mav_put_float(buf
, 12, yaw
);
223 _mav_put_float(buf
, 16, yaw_absolute
);
225 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_MOUNT_ORIENTATION
, buf
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC
);
227 mavlink_mount_orientation_t
*packet
= (mavlink_mount_orientation_t
*)msgbuf
;
228 packet
->time_boot_ms
= time_boot_ms
;
230 packet
->pitch
= pitch
;
232 packet
->yaw_absolute
= yaw_absolute
;
234 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_MOUNT_ORIENTATION
, (const char *)packet
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN
, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC
);
241 // MESSAGE MOUNT_ORIENTATION UNPACKING
245 * @brief Get field time_boot_ms from mount_orientation message
247 * @return [ms] Timestamp (time since system boot).
249 static inline uint32_t mavlink_msg_mount_orientation_get_time_boot_ms(const mavlink_message_t
* msg
)
251 return _MAV_RETURN_uint32_t(msg
, 0);
255 * @brief Get field roll from mount_orientation message
257 * @return [deg] Roll in global frame (set to NaN for invalid).
259 static inline float mavlink_msg_mount_orientation_get_roll(const mavlink_message_t
* msg
)
261 return _MAV_RETURN_float(msg
, 4);
265 * @brief Get field pitch from mount_orientation message
267 * @return [deg] Pitch in global frame (set to NaN for invalid).
269 static inline float mavlink_msg_mount_orientation_get_pitch(const mavlink_message_t
* msg
)
271 return _MAV_RETURN_float(msg
, 8);
275 * @brief Get field yaw from mount_orientation message
277 * @return [deg] Yaw relative to vehicle (set to NaN for invalid).
279 static inline float mavlink_msg_mount_orientation_get_yaw(const mavlink_message_t
* msg
)
281 return _MAV_RETURN_float(msg
, 12);
285 * @brief Get field yaw_absolute from mount_orientation message
287 * @return [deg] Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid).
289 static inline float mavlink_msg_mount_orientation_get_yaw_absolute(const mavlink_message_t
* msg
)
291 return _MAV_RETURN_float(msg
, 16);
295 * @brief Decode a mount_orientation message into a struct
297 * @param msg The message to decode
298 * @param mount_orientation C-struct to decode the message contents into
300 static inline void mavlink_msg_mount_orientation_decode(const mavlink_message_t
* msg
, mavlink_mount_orientation_t
* mount_orientation
)
302 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
303 mount_orientation
->time_boot_ms
= mavlink_msg_mount_orientation_get_time_boot_ms(msg
);
304 mount_orientation
->roll
= mavlink_msg_mount_orientation_get_roll(msg
);
305 mount_orientation
->pitch
= mavlink_msg_mount_orientation_get_pitch(msg
);
306 mount_orientation
->yaw
= mavlink_msg_mount_orientation_get_yaw(msg
);
307 mount_orientation
->yaw_absolute
= mavlink_msg_mount_orientation_get_yaw_absolute(msg
);
309 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN
? msg
->len
: MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN
;
310 memset(mount_orientation
, 0, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN
);
311 memcpy(mount_orientation
, _MAV_PAYLOAD(msg
), len
);