1 // MESSAGE ATTITUDE_TARGET PACKING
3 #define MAVLINK_MSG_ID_ATTITUDE_TARGET 83
5 typedef struct __mavlink_attitude_target_t
7 uint32_t time_boot_ms
; ///< Timestamp in milliseconds since system boot
8 float q
[4]; ///< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
9 float body_roll_rate
; ///< Body roll rate in radians per second
10 float body_pitch_rate
; ///< Body roll rate in radians per second
11 float body_yaw_rate
; ///< Body roll rate in radians per second
12 float thrust
; ///< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
13 uint8_t type_mask
; ///< Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
14 } mavlink_attitude_target_t
;
16 #define MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN 37
17 #define MAVLINK_MSG_ID_83_LEN 37
19 #define MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC 22
20 #define MAVLINK_MSG_ID_83_CRC 22
22 #define MAVLINK_MSG_ATTITUDE_TARGET_FIELD_Q_LEN 4
24 #define MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET { \
27 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_target_t, time_boot_ms) }, \
28 { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_target_t, q) }, \
29 { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_target_t, body_roll_rate) }, \
30 { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_target_t, body_pitch_rate) }, \
31 { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_target_t, body_yaw_rate) }, \
32 { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_target_t, thrust) }, \
33 { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \
39 * @brief Pack a attitude_target message
40 * @param system_id ID of this system
41 * @param component_id ID of this component (e.g. 200 for IMU)
42 * @param msg The MAVLink message to compress the data into
44 * @param time_boot_ms Timestamp in milliseconds since system boot
45 * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
46 * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
47 * @param body_roll_rate Body roll rate in radians per second
48 * @param body_pitch_rate Body roll rate in radians per second
49 * @param body_yaw_rate Body roll rate in radians per second
50 * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
51 * @return length of the message in bytes (excluding serial stream start sign)
53 static inline uint16_t mavlink_msg_attitude_target_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
54 uint32_t time_boot_ms
, uint8_t type_mask
, const float *q
, float body_roll_rate
, float body_pitch_rate
, float body_yaw_rate
, float thrust
)
56 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
57 char buf
[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN
];
58 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
59 _mav_put_float(buf
, 20, body_roll_rate
);
60 _mav_put_float(buf
, 24, body_pitch_rate
);
61 _mav_put_float(buf
, 28, body_yaw_rate
);
62 _mav_put_float(buf
, 32, thrust
);
63 _mav_put_uint8_t(buf
, 36, type_mask
);
64 _mav_put_float_array(buf
, 4, q
, 4);
65 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN
);
67 mavlink_attitude_target_t packet
;
68 packet
.time_boot_ms
= time_boot_ms
;
69 packet
.body_roll_rate
= body_roll_rate
;
70 packet
.body_pitch_rate
= body_pitch_rate
;
71 packet
.body_yaw_rate
= body_yaw_rate
;
72 packet
.thrust
= thrust
;
73 packet
.type_mask
= type_mask
;
74 mav_array_memcpy(packet
.q
, q
, sizeof(float)*4);
75 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN
);
78 msg
->msgid
= MAVLINK_MSG_ID_ATTITUDE_TARGET
;
80 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN
, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC
);
82 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN
);
87 * @brief Pack a attitude_target message on a channel
88 * @param system_id ID of this system
89 * @param component_id ID of this component (e.g. 200 for IMU)
90 * @param chan The MAVLink channel this message will be sent over
91 * @param msg The MAVLink message to compress the data into
92 * @param time_boot_ms Timestamp in milliseconds since system boot
93 * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
94 * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
95 * @param body_roll_rate Body roll rate in radians per second
96 * @param body_pitch_rate Body roll rate in radians per second
97 * @param body_yaw_rate Body roll rate in radians per second
98 * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
99 * @return length of the message in bytes (excluding serial stream start sign)
101 static inline uint16_t mavlink_msg_attitude_target_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
102 mavlink_message_t
* msg
,
103 uint32_t time_boot_ms
,uint8_t type_mask
,const float *q
,float body_roll_rate
,float body_pitch_rate
,float body_yaw_rate
,float thrust
)
105 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
106 char buf
[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN
];
107 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
108 _mav_put_float(buf
, 20, body_roll_rate
);
109 _mav_put_float(buf
, 24, body_pitch_rate
);
110 _mav_put_float(buf
, 28, body_yaw_rate
);
111 _mav_put_float(buf
, 32, thrust
);
112 _mav_put_uint8_t(buf
, 36, type_mask
);
113 _mav_put_float_array(buf
, 4, q
, 4);
114 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN
);
116 mavlink_attitude_target_t packet
;
117 packet
.time_boot_ms
= time_boot_ms
;
118 packet
.body_roll_rate
= body_roll_rate
;
119 packet
.body_pitch_rate
= body_pitch_rate
;
120 packet
.body_yaw_rate
= body_yaw_rate
;
121 packet
.thrust
= thrust
;
122 packet
.type_mask
= type_mask
;
123 mav_array_memcpy(packet
.q
, q
, sizeof(float)*4);
124 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN
);
127 msg
->msgid
= MAVLINK_MSG_ID_ATTITUDE_TARGET
;
128 #if MAVLINK_CRC_EXTRA
129 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN
, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC
);
131 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN
);
136 * @brief Encode a attitude_target struct
138 * @param system_id ID of this system
139 * @param component_id ID of this component (e.g. 200 for IMU)
140 * @param msg The MAVLink message to compress the data into
141 * @param attitude_target C-struct to read the message contents from
143 static inline uint16_t mavlink_msg_attitude_target_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
, const mavlink_attitude_target_t
* attitude_target
)
145 return mavlink_msg_attitude_target_pack(system_id
, component_id
, msg
, attitude_target
->time_boot_ms
, attitude_target
->type_mask
, attitude_target
->q
, attitude_target
->body_roll_rate
, attitude_target
->body_pitch_rate
, attitude_target
->body_yaw_rate
, attitude_target
->thrust
);
149 * @brief Encode a attitude_target struct on a channel
151 * @param system_id ID of this system
152 * @param component_id ID of this component (e.g. 200 for IMU)
153 * @param chan The MAVLink channel this message will be sent over
154 * @param msg The MAVLink message to compress the data into
155 * @param attitude_target C-struct to read the message contents from
157 static inline uint16_t mavlink_msg_attitude_target_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_attitude_target_t
* attitude_target
)
159 return mavlink_msg_attitude_target_pack_chan(system_id
, component_id
, chan
, msg
, attitude_target
->time_boot_ms
, attitude_target
->type_mask
, attitude_target
->q
, attitude_target
->body_roll_rate
, attitude_target
->body_pitch_rate
, attitude_target
->body_yaw_rate
, attitude_target
->thrust
);
163 * @brief Send a attitude_target message
164 * @param chan MAVLink channel to send the message
166 * @param time_boot_ms Timestamp in milliseconds since system boot
167 * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
168 * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
169 * @param body_roll_rate Body roll rate in radians per second
170 * @param body_pitch_rate Body roll rate in radians per second
171 * @param body_yaw_rate Body roll rate in radians per second
172 * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
174 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
176 static inline void mavlink_msg_attitude_target_send(mavlink_channel_t chan
, uint32_t time_boot_ms
, uint8_t type_mask
, const float *q
, float body_roll_rate
, float body_pitch_rate
, float body_yaw_rate
, float thrust
)
178 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
179 char buf
[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN
];
180 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
181 _mav_put_float(buf
, 20, body_roll_rate
);
182 _mav_put_float(buf
, 24, body_pitch_rate
);
183 _mav_put_float(buf
, 28, body_yaw_rate
);
184 _mav_put_float(buf
, 32, thrust
);
185 _mav_put_uint8_t(buf
, 36, type_mask
);
186 _mav_put_float_array(buf
, 4, q
, 4);
187 #if MAVLINK_CRC_EXTRA
188 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE_TARGET
, buf
, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN
, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC
);
190 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE_TARGET
, buf
, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN
);
193 mavlink_attitude_target_t packet
;
194 packet
.time_boot_ms
= time_boot_ms
;
195 packet
.body_roll_rate
= body_roll_rate
;
196 packet
.body_pitch_rate
= body_pitch_rate
;
197 packet
.body_yaw_rate
= body_yaw_rate
;
198 packet
.thrust
= thrust
;
199 packet
.type_mask
= type_mask
;
200 mav_array_memcpy(packet
.q
, q
, sizeof(float)*4);
201 #if MAVLINK_CRC_EXTRA
202 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE_TARGET
, (const char *)&packet
, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN
, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC
);
204 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE_TARGET
, (const char *)&packet
, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN
);
209 #if MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
211 This varient of _send() can be used to save stack space by re-using
212 memory from the receive buffer. The caller provides a
213 mavlink_message_t which is the size of a full mavlink message. This
214 is usually the receive buffer for the channel, and allows a reply to an
215 incoming message with minimum stack space usage.
217 static inline void mavlink_msg_attitude_target_send_buf(mavlink_message_t
*msgbuf
, mavlink_channel_t chan
, uint32_t time_boot_ms
, uint8_t type_mask
, const float *q
, float body_roll_rate
, float body_pitch_rate
, float body_yaw_rate
, float thrust
)
219 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
220 char *buf
= (char *)msgbuf
;
221 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
222 _mav_put_float(buf
, 20, body_roll_rate
);
223 _mav_put_float(buf
, 24, body_pitch_rate
);
224 _mav_put_float(buf
, 28, body_yaw_rate
);
225 _mav_put_float(buf
, 32, thrust
);
226 _mav_put_uint8_t(buf
, 36, type_mask
);
227 _mav_put_float_array(buf
, 4, q
, 4);
228 #if MAVLINK_CRC_EXTRA
229 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE_TARGET
, buf
, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN
, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC
);
231 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE_TARGET
, buf
, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN
);
234 mavlink_attitude_target_t
*packet
= (mavlink_attitude_target_t
*)msgbuf
;
235 packet
->time_boot_ms
= time_boot_ms
;
236 packet
->body_roll_rate
= body_roll_rate
;
237 packet
->body_pitch_rate
= body_pitch_rate
;
238 packet
->body_yaw_rate
= body_yaw_rate
;
239 packet
->thrust
= thrust
;
240 packet
->type_mask
= type_mask
;
241 mav_array_memcpy(packet
->q
, q
, sizeof(float)*4);
242 #if MAVLINK_CRC_EXTRA
243 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE_TARGET
, (const char *)packet
, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN
, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC
);
245 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE_TARGET
, (const char *)packet
, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN
);
253 // MESSAGE ATTITUDE_TARGET UNPACKING
257 * @brief Get field time_boot_ms from attitude_target message
259 * @return Timestamp in milliseconds since system boot
261 static inline uint32_t mavlink_msg_attitude_target_get_time_boot_ms(const mavlink_message_t
* msg
)
263 return _MAV_RETURN_uint32_t(msg
, 0);
267 * @brief Get field type_mask from attitude_target message
269 * @return Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
271 static inline uint8_t mavlink_msg_attitude_target_get_type_mask(const mavlink_message_t
* msg
)
273 return _MAV_RETURN_uint8_t(msg
, 36);
277 * @brief Get field q from attitude_target message
279 * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
281 static inline uint16_t mavlink_msg_attitude_target_get_q(const mavlink_message_t
* msg
, float *q
)
283 return _MAV_RETURN_float_array(msg
, q
, 4, 4);
287 * @brief Get field body_roll_rate from attitude_target message
289 * @return Body roll rate in radians per second
291 static inline float mavlink_msg_attitude_target_get_body_roll_rate(const mavlink_message_t
* msg
)
293 return _MAV_RETURN_float(msg
, 20);
297 * @brief Get field body_pitch_rate from attitude_target message
299 * @return Body roll rate in radians per second
301 static inline float mavlink_msg_attitude_target_get_body_pitch_rate(const mavlink_message_t
* msg
)
303 return _MAV_RETURN_float(msg
, 24);
307 * @brief Get field body_yaw_rate from attitude_target message
309 * @return Body roll rate in radians per second
311 static inline float mavlink_msg_attitude_target_get_body_yaw_rate(const mavlink_message_t
* msg
)
313 return _MAV_RETURN_float(msg
, 28);
317 * @brief Get field thrust from attitude_target message
319 * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
321 static inline float mavlink_msg_attitude_target_get_thrust(const mavlink_message_t
* msg
)
323 return _MAV_RETURN_float(msg
, 32);
327 * @brief Decode a attitude_target message into a struct
329 * @param msg The message to decode
330 * @param attitude_target C-struct to decode the message contents into
332 static inline void mavlink_msg_attitude_target_decode(const mavlink_message_t
* msg
, mavlink_attitude_target_t
* attitude_target
)
334 #if MAVLINK_NEED_BYTE_SWAP
335 attitude_target
->time_boot_ms
= mavlink_msg_attitude_target_get_time_boot_ms(msg
);
336 mavlink_msg_attitude_target_get_q(msg
, attitude_target
->q
);
337 attitude_target
->body_roll_rate
= mavlink_msg_attitude_target_get_body_roll_rate(msg
);
338 attitude_target
->body_pitch_rate
= mavlink_msg_attitude_target_get_body_pitch_rate(msg
);
339 attitude_target
->body_yaw_rate
= mavlink_msg_attitude_target_get_body_yaw_rate(msg
);
340 attitude_target
->thrust
= mavlink_msg_attitude_target_get_thrust(msg
);
341 attitude_target
->type_mask
= mavlink_msg_attitude_target_get_type_mask(msg
);
343 memcpy(attitude_target
, _MAV_PAYLOAD(msg
), MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN
);