mavlink_msg_attitude_target.h
Go to the documentation of this file.
1 // MESSAGE ATTITUDE_TARGET PACKING
2 
3 #define MAVLINK_MSG_ID_ATTITUDE_TARGET 83
4 
6 {
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*/
15 
16 #define MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN 37
17 #define MAVLINK_MSG_ID_83_LEN 37
18 
19 #define MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC 22
20 #define MAVLINK_MSG_ID_83_CRC 22
21 
22 #define MAVLINK_MSG_ATTITUDE_TARGET_FIELD_Q_LEN 4
23 
24 #define MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET { \
25  "ATTITUDE_TARGET", \
26  7, \
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) }, \
34  } \
35 }
36 
37 
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)
55 {
56 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
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);
66 #else
68  packet.time_boot_ms = time_boot_ms;
72  packet.thrust = thrust;
73  packet.type_mask = type_mask;
74  mav_array_memcpy(packet.q, q, sizeof(float)*4);
76 #endif
77 
78  msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TARGET;
79 #if MAVLINK_CRC_EXTRA
81 #else
82  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
83 #endif
84 }
85 
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)
104 {
105 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
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);
115 #else
117  packet.time_boot_ms = time_boot_ms;
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);
125 #endif
126 
127  msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TARGET;
128 #if MAVLINK_CRC_EXTRA
130 #else
131  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
132 #endif
133 }
134 
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)
144 {
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);
146 }
147 
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)
158 {
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);
160 }
161 
174 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
175 
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)
177 {
178 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
181  _mav_put_float(buf, 20, body_roll_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
189 #else
190  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
191 #endif
192 #else
194  packet.time_boot_ms = time_boot_ms;
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);
203 #else
204  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
205 #endif
206 #endif
207 }
208 
209 #if MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
210 /*
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.
216  */
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)
218 {
219 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
220  char *buf = (char *)msgbuf;
222  _mav_put_float(buf, 20, body_roll_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
230 #else
231  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
232 #endif
233 #else
235  packet->time_boot_ms = time_boot_ms;
236  packet->body_roll_rate = body_roll_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);
244 #else
245  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
246 #endif
247 #endif
248 }
249 #endif
250 
251 #endif
252 
253 // MESSAGE ATTITUDE_TARGET UNPACKING
254 
255 
261 static inline uint32_t mavlink_msg_attitude_target_get_time_boot_ms(const mavlink_message_t* msg)
262 {
263  return _MAV_RETURN_uint32_t(msg, 0);
264 }
265 
271 static inline uint8_t mavlink_msg_attitude_target_get_type_mask(const mavlink_message_t* msg)
272 {
273  return _MAV_RETURN_uint8_t(msg, 36);
274 }
275 
281 static inline uint16_t mavlink_msg_attitude_target_get_q(const mavlink_message_t* msg, float *q)
282 {
283  return _MAV_RETURN_float_array(msg, q, 4, 4);
284 }
285 
291 static inline float mavlink_msg_attitude_target_get_body_roll_rate(const mavlink_message_t* msg)
292 {
293  return _MAV_RETURN_float(msg, 20);
294 }
295 
301 static inline float mavlink_msg_attitude_target_get_body_pitch_rate(const mavlink_message_t* msg)
302 {
303  return _MAV_RETURN_float(msg, 24);
304 }
305 
311 static inline float mavlink_msg_attitude_target_get_body_yaw_rate(const mavlink_message_t* msg)
312 {
313  return _MAV_RETURN_float(msg, 28);
314 }
315 
321 static inline float mavlink_msg_attitude_target_get_thrust(const mavlink_message_t* msg)
322 {
323  return _MAV_RETURN_float(msg, 32);
324 }
325 
332 static inline void mavlink_msg_attitude_target_decode(const mavlink_message_t* msg, mavlink_attitude_target_t* attitude_target)
333 {
334 #if MAVLINK_NEED_BYTE_SWAP
336  mavlink_msg_attitude_target_get_q(msg, attitude_target->q);
340  attitude_target->thrust = mavlink_msg_attitude_target_get_thrust(msg);
342 #else
343  memcpy(attitude_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
344 #endif
345 }
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:151
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:244
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:140
static void mav_array_memcpy(void *dest, const void *src, size_t n)
Definition: protocol.h:176
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:147


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 19:59:24