2 // MESSAGE GIMBAL_DEVICE_SET_ATTITUDE PACKING
4 #define MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE 284
7 typedef struct __mavlink_gimbal_device_set_attitude_t
{
8 float q
[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, set all fields to NaN if only angular velocity should be used)*/
9 float angular_velocity_x
; /*< [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.*/
10 float angular_velocity_y
; /*< [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.*/
11 float angular_velocity_z
; /*< [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.*/
12 uint16_t flags
; /*< Low level gimbal flags.*/
13 uint8_t target_system
; /*< System ID*/
14 uint8_t target_component
; /*< Component ID*/
15 } mavlink_gimbal_device_set_attitude_t
;
17 #define MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN 32
18 #define MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN 32
19 #define MAVLINK_MSG_ID_284_LEN 32
20 #define MAVLINK_MSG_ID_284_MIN_LEN 32
22 #define MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC 99
23 #define MAVLINK_MSG_ID_284_CRC 99
25 #define MAVLINK_MSG_GIMBAL_DEVICE_SET_ATTITUDE_FIELD_Q_LEN 4
27 #if MAVLINK_COMMAND_24BIT
28 #define MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_SET_ATTITUDE { \
30 "GIMBAL_DEVICE_SET_ATTITUDE", \
32 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gimbal_device_set_attitude_t, target_system) }, \
33 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gimbal_device_set_attitude_t, target_component) }, \
34 { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gimbal_device_set_attitude_t, flags) }, \
35 { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 0, offsetof(mavlink_gimbal_device_set_attitude_t, q) }, \
36 { "angular_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_device_set_attitude_t, angular_velocity_x) }, \
37 { "angular_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_device_set_attitude_t, angular_velocity_y) }, \
38 { "angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_device_set_attitude_t, angular_velocity_z) }, \
42 #define MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_SET_ATTITUDE { \
43 "GIMBAL_DEVICE_SET_ATTITUDE", \
45 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gimbal_device_set_attitude_t, target_system) }, \
46 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gimbal_device_set_attitude_t, target_component) }, \
47 { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gimbal_device_set_attitude_t, flags) }, \
48 { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 0, offsetof(mavlink_gimbal_device_set_attitude_t, q) }, \
49 { "angular_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_device_set_attitude_t, angular_velocity_x) }, \
50 { "angular_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_device_set_attitude_t, angular_velocity_y) }, \
51 { "angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_device_set_attitude_t, angular_velocity_z) }, \
57 * @brief Pack a gimbal_device_set_attitude message
58 * @param system_id ID of this system
59 * @param component_id ID of this component (e.g. 200 for IMU)
60 * @param msg The MAVLink message to compress the data into
62 * @param target_system System ID
63 * @param target_component Component ID
64 * @param flags Low level gimbal flags.
65 * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, set all fields to NaN if only angular velocity should be used)
66 * @param angular_velocity_x [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.
67 * @param angular_velocity_y [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.
68 * @param angular_velocity_z [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.
69 * @return length of the message in bytes (excluding serial stream start sign)
71 static inline uint16_t mavlink_msg_gimbal_device_set_attitude_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
72 uint8_t target_system
, uint8_t target_component
, uint16_t flags
, const float *q
, float angular_velocity_x
, float angular_velocity_y
, float angular_velocity_z
)
74 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
75 char buf
[MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN
];
76 _mav_put_float(buf
, 16, angular_velocity_x
);
77 _mav_put_float(buf
, 20, angular_velocity_y
);
78 _mav_put_float(buf
, 24, angular_velocity_z
);
79 _mav_put_uint16_t(buf
, 28, flags
);
80 _mav_put_uint8_t(buf
, 30, target_system
);
81 _mav_put_uint8_t(buf
, 31, target_component
);
82 _mav_put_float_array(buf
, 0, q
, 4);
83 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN
);
85 mavlink_gimbal_device_set_attitude_t packet
;
86 packet
.angular_velocity_x
= angular_velocity_x
;
87 packet
.angular_velocity_y
= angular_velocity_y
;
88 packet
.angular_velocity_z
= angular_velocity_z
;
90 packet
.target_system
= target_system
;
91 packet
.target_component
= target_component
;
92 mav_array_memcpy(packet
.q
, q
, sizeof(float)*4);
93 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN
);
96 msg
->msgid
= MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE
;
97 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC
);
101 * @brief Pack a gimbal_device_set_attitude message on a channel
102 * @param system_id ID of this system
103 * @param component_id ID of this component (e.g. 200 for IMU)
104 * @param chan The MAVLink channel this message will be sent over
105 * @param msg The MAVLink message to compress the data into
106 * @param target_system System ID
107 * @param target_component Component ID
108 * @param flags Low level gimbal flags.
109 * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, set all fields to NaN if only angular velocity should be used)
110 * @param angular_velocity_x [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.
111 * @param angular_velocity_y [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.
112 * @param angular_velocity_z [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.
113 * @return length of the message in bytes (excluding serial stream start sign)
115 static inline uint16_t mavlink_msg_gimbal_device_set_attitude_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
116 mavlink_message_t
* msg
,
117 uint8_t target_system
,uint8_t target_component
,uint16_t flags
,const float *q
,float angular_velocity_x
,float angular_velocity_y
,float angular_velocity_z
)
119 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
120 char buf
[MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN
];
121 _mav_put_float(buf
, 16, angular_velocity_x
);
122 _mav_put_float(buf
, 20, angular_velocity_y
);
123 _mav_put_float(buf
, 24, angular_velocity_z
);
124 _mav_put_uint16_t(buf
, 28, flags
);
125 _mav_put_uint8_t(buf
, 30, target_system
);
126 _mav_put_uint8_t(buf
, 31, target_component
);
127 _mav_put_float_array(buf
, 0, q
, 4);
128 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN
);
130 mavlink_gimbal_device_set_attitude_t packet
;
131 packet
.angular_velocity_x
= angular_velocity_x
;
132 packet
.angular_velocity_y
= angular_velocity_y
;
133 packet
.angular_velocity_z
= angular_velocity_z
;
134 packet
.flags
= flags
;
135 packet
.target_system
= target_system
;
136 packet
.target_component
= target_component
;
137 mav_array_memcpy(packet
.q
, q
, sizeof(float)*4);
138 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN
);
141 msg
->msgid
= MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE
;
142 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC
);
146 * @brief Encode a gimbal_device_set_attitude struct
148 * @param system_id ID of this system
149 * @param component_id ID of this component (e.g. 200 for IMU)
150 * @param msg The MAVLink message to compress the data into
151 * @param gimbal_device_set_attitude C-struct to read the message contents from
153 static inline uint16_t mavlink_msg_gimbal_device_set_attitude_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
, const mavlink_gimbal_device_set_attitude_t
* gimbal_device_set_attitude
)
155 return mavlink_msg_gimbal_device_set_attitude_pack(system_id
, component_id
, msg
, gimbal_device_set_attitude
->target_system
, gimbal_device_set_attitude
->target_component
, gimbal_device_set_attitude
->flags
, gimbal_device_set_attitude
->q
, gimbal_device_set_attitude
->angular_velocity_x
, gimbal_device_set_attitude
->angular_velocity_y
, gimbal_device_set_attitude
->angular_velocity_z
);
159 * @brief Encode a gimbal_device_set_attitude struct on a channel
161 * @param system_id ID of this system
162 * @param component_id ID of this component (e.g. 200 for IMU)
163 * @param chan The MAVLink channel this message will be sent over
164 * @param msg The MAVLink message to compress the data into
165 * @param gimbal_device_set_attitude C-struct to read the message contents from
167 static inline uint16_t mavlink_msg_gimbal_device_set_attitude_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_gimbal_device_set_attitude_t
* gimbal_device_set_attitude
)
169 return mavlink_msg_gimbal_device_set_attitude_pack_chan(system_id
, component_id
, chan
, msg
, gimbal_device_set_attitude
->target_system
, gimbal_device_set_attitude
->target_component
, gimbal_device_set_attitude
->flags
, gimbal_device_set_attitude
->q
, gimbal_device_set_attitude
->angular_velocity_x
, gimbal_device_set_attitude
->angular_velocity_y
, gimbal_device_set_attitude
->angular_velocity_z
);
173 * @brief Send a gimbal_device_set_attitude message
174 * @param chan MAVLink channel to send the message
176 * @param target_system System ID
177 * @param target_component Component ID
178 * @param flags Low level gimbal flags.
179 * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, set all fields to NaN if only angular velocity should be used)
180 * @param angular_velocity_x [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.
181 * @param angular_velocity_y [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.
182 * @param angular_velocity_z [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.
184 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
186 static inline void mavlink_msg_gimbal_device_set_attitude_send(mavlink_channel_t chan
, uint8_t target_system
, uint8_t target_component
, uint16_t flags
, const float *q
, float angular_velocity_x
, float angular_velocity_y
, float angular_velocity_z
)
188 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
189 char buf
[MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN
];
190 _mav_put_float(buf
, 16, angular_velocity_x
);
191 _mav_put_float(buf
, 20, angular_velocity_y
);
192 _mav_put_float(buf
, 24, angular_velocity_z
);
193 _mav_put_uint16_t(buf
, 28, flags
);
194 _mav_put_uint8_t(buf
, 30, target_system
);
195 _mav_put_uint8_t(buf
, 31, target_component
);
196 _mav_put_float_array(buf
, 0, q
, 4);
197 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE
, buf
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC
);
199 mavlink_gimbal_device_set_attitude_t packet
;
200 packet
.angular_velocity_x
= angular_velocity_x
;
201 packet
.angular_velocity_y
= angular_velocity_y
;
202 packet
.angular_velocity_z
= angular_velocity_z
;
203 packet
.flags
= flags
;
204 packet
.target_system
= target_system
;
205 packet
.target_component
= target_component
;
206 mav_array_memcpy(packet
.q
, q
, sizeof(float)*4);
207 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE
, (const char *)&packet
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC
);
212 * @brief Send a gimbal_device_set_attitude message
213 * @param chan MAVLink channel to send the message
214 * @param struct The MAVLink struct to serialize
216 static inline void mavlink_msg_gimbal_device_set_attitude_send_struct(mavlink_channel_t chan
, const mavlink_gimbal_device_set_attitude_t
* gimbal_device_set_attitude
)
218 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
219 mavlink_msg_gimbal_device_set_attitude_send(chan
, gimbal_device_set_attitude
->target_system
, gimbal_device_set_attitude
->target_component
, gimbal_device_set_attitude
->flags
, gimbal_device_set_attitude
->q
, gimbal_device_set_attitude
->angular_velocity_x
, gimbal_device_set_attitude
->angular_velocity_y
, gimbal_device_set_attitude
->angular_velocity_z
);
221 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE
, (const char *)gimbal_device_set_attitude
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC
);
225 #if MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
227 This varient of _send() can be used to save stack space by re-using
228 memory from the receive buffer. The caller provides a
229 mavlink_message_t which is the size of a full mavlink message. This
230 is usually the receive buffer for the channel, and allows a reply to an
231 incoming message with minimum stack space usage.
233 static inline void mavlink_msg_gimbal_device_set_attitude_send_buf(mavlink_message_t
*msgbuf
, mavlink_channel_t chan
, uint8_t target_system
, uint8_t target_component
, uint16_t flags
, const float *q
, float angular_velocity_x
, float angular_velocity_y
, float angular_velocity_z
)
235 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
236 char *buf
= (char *)msgbuf
;
237 _mav_put_float(buf
, 16, angular_velocity_x
);
238 _mav_put_float(buf
, 20, angular_velocity_y
);
239 _mav_put_float(buf
, 24, angular_velocity_z
);
240 _mav_put_uint16_t(buf
, 28, flags
);
241 _mav_put_uint8_t(buf
, 30, target_system
);
242 _mav_put_uint8_t(buf
, 31, target_component
);
243 _mav_put_float_array(buf
, 0, q
, 4);
244 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE
, buf
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC
);
246 mavlink_gimbal_device_set_attitude_t
*packet
= (mavlink_gimbal_device_set_attitude_t
*)msgbuf
;
247 packet
->angular_velocity_x
= angular_velocity_x
;
248 packet
->angular_velocity_y
= angular_velocity_y
;
249 packet
->angular_velocity_z
= angular_velocity_z
;
250 packet
->flags
= flags
;
251 packet
->target_system
= target_system
;
252 packet
->target_component
= target_component
;
253 mav_array_memcpy(packet
->q
, q
, sizeof(float)*4);
254 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE
, (const char *)packet
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN
, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC
);
261 // MESSAGE GIMBAL_DEVICE_SET_ATTITUDE UNPACKING
265 * @brief Get field target_system from gimbal_device_set_attitude message
269 static inline uint8_t mavlink_msg_gimbal_device_set_attitude_get_target_system(const mavlink_message_t
* msg
)
271 return _MAV_RETURN_uint8_t(msg
, 30);
275 * @brief Get field target_component from gimbal_device_set_attitude message
277 * @return Component ID
279 static inline uint8_t mavlink_msg_gimbal_device_set_attitude_get_target_component(const mavlink_message_t
* msg
)
281 return _MAV_RETURN_uint8_t(msg
, 31);
285 * @brief Get field flags from gimbal_device_set_attitude message
287 * @return Low level gimbal flags.
289 static inline uint16_t mavlink_msg_gimbal_device_set_attitude_get_flags(const mavlink_message_t
* msg
)
291 return _MAV_RETURN_uint16_t(msg
, 28);
295 * @brief Get field q from gimbal_device_set_attitude message
297 * @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, set all fields to NaN if only angular velocity should be used)
299 static inline uint16_t mavlink_msg_gimbal_device_set_attitude_get_q(const mavlink_message_t
* msg
, float *q
)
301 return _MAV_RETURN_float_array(msg
, q
, 4, 0);
305 * @brief Get field angular_velocity_x from gimbal_device_set_attitude message
307 * @return [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.
309 static inline float mavlink_msg_gimbal_device_set_attitude_get_angular_velocity_x(const mavlink_message_t
* msg
)
311 return _MAV_RETURN_float(msg
, 16);
315 * @brief Get field angular_velocity_y from gimbal_device_set_attitude message
317 * @return [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.
319 static inline float mavlink_msg_gimbal_device_set_attitude_get_angular_velocity_y(const mavlink_message_t
* msg
)
321 return _MAV_RETURN_float(msg
, 20);
325 * @brief Get field angular_velocity_z from gimbal_device_set_attitude message
327 * @return [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.
329 static inline float mavlink_msg_gimbal_device_set_attitude_get_angular_velocity_z(const mavlink_message_t
* msg
)
331 return _MAV_RETURN_float(msg
, 24);
335 * @brief Decode a gimbal_device_set_attitude message into a struct
337 * @param msg The message to decode
338 * @param gimbal_device_set_attitude C-struct to decode the message contents into
340 static inline void mavlink_msg_gimbal_device_set_attitude_decode(const mavlink_message_t
* msg
, mavlink_gimbal_device_set_attitude_t
* gimbal_device_set_attitude
)
342 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
343 mavlink_msg_gimbal_device_set_attitude_get_q(msg
, gimbal_device_set_attitude
->q
);
344 gimbal_device_set_attitude
->angular_velocity_x
= mavlink_msg_gimbal_device_set_attitude_get_angular_velocity_x(msg
);
345 gimbal_device_set_attitude
->angular_velocity_y
= mavlink_msg_gimbal_device_set_attitude_get_angular_velocity_y(msg
);
346 gimbal_device_set_attitude
->angular_velocity_z
= mavlink_msg_gimbal_device_set_attitude_get_angular_velocity_z(msg
);
347 gimbal_device_set_attitude
->flags
= mavlink_msg_gimbal_device_set_attitude_get_flags(msg
);
348 gimbal_device_set_attitude
->target_system
= mavlink_msg_gimbal_device_set_attitude_get_target_system(msg
);
349 gimbal_device_set_attitude
->target_component
= mavlink_msg_gimbal_device_set_attitude_get_target_component(msg
);
351 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN
? msg
->len
: MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN
;
352 memset(gimbal_device_set_attitude
, 0, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN
);
353 memcpy(gimbal_device_set_attitude
, _MAV_PAYLOAD(msg
), len
);