1 // MESSAGE MANUAL_CONTROL PACKING
3 #define MAVLINK_MSG_ID_MANUAL_CONTROL 69
5 typedef struct __mavlink_manual_control_t
{
7 float pitch
; ///< pitch
9 float thrust
; ///< thrust
10 uint8_t target
; ///< The system to be controlled
11 uint8_t roll_manual
; ///< roll control enabled auto:0, manual:1
12 uint8_t pitch_manual
; ///< pitch auto:0, manual:1
13 uint8_t yaw_manual
; ///< yaw auto:0, manual:1
14 uint8_t thrust_manual
; ///< thrust auto:0, manual:1
15 } mavlink_manual_control_t
;
17 #define MAVLINK_MSG_ID_MANUAL_CONTROL_LEN 21
18 #define MAVLINK_MSG_ID_69_LEN 21
21 #define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL \
26 { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_manual_control_t, roll) }, \
27 { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_manual_control_t, pitch) }, \
28 { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_manual_control_t, yaw) }, \
29 { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_manual_control_t, thrust) }, \
30 { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_manual_control_t, target) }, \
31 { "roll_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_manual_control_t, roll_manual) }, \
32 { "pitch_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_manual_control_t, pitch_manual) }, \
33 { "yaw_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_manual_control_t, yaw_manual) }, \
34 { "thrust_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_control_t, thrust_manual) }, \
40 * @brief Pack a manual_control message
41 * @param system_id ID of this system
42 * @param component_id ID of this component (e.g. 200 for IMU)
43 * @param msg The MAVLink message to compress the data into
45 * @param target The system to be controlled
49 * @param thrust thrust
50 * @param roll_manual roll control enabled auto:0, manual:1
51 * @param pitch_manual pitch auto:0, manual:1
52 * @param yaw_manual yaw auto:0, manual:1
53 * @param thrust_manual thrust auto:0, manual:1
54 * @return length of the message in bytes (excluding serial stream start sign)
56 static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
*msg
,
57 uint8_t target
, float roll
, float pitch
, float yaw
, float thrust
, uint8_t roll_manual
, uint8_t pitch_manual
, uint8_t yaw_manual
, uint8_t thrust_manual
)
59 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
61 _mav_put_float(buf
, 0, roll
);
62 _mav_put_float(buf
, 4, pitch
);
63 _mav_put_float(buf
, 8, yaw
);
64 _mav_put_float(buf
, 12, thrust
);
65 _mav_put_uint8_t(buf
, 16, target
);
66 _mav_put_uint8_t(buf
, 17, roll_manual
);
67 _mav_put_uint8_t(buf
, 18, pitch_manual
);
68 _mav_put_uint8_t(buf
, 19, yaw_manual
);
69 _mav_put_uint8_t(buf
, 20, thrust_manual
);
71 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 21);
73 mavlink_manual_control_t packet
;
77 packet
.thrust
= thrust
;
78 packet
.target
= target
;
79 packet
.roll_manual
= roll_manual
;
80 packet
.pitch_manual
= pitch_manual
;
81 packet
.yaw_manual
= yaw_manual
;
82 packet
.thrust_manual
= thrust_manual
;
84 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 21);
85 #endif // if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
87 msg
->msgid
= MAVLINK_MSG_ID_MANUAL_CONTROL
;
88 return mavlink_finalize_message(msg
, system_id
, component_id
, 21, 52);
92 * @brief Pack a manual_control message on a channel
93 * @param system_id ID of this system
94 * @param component_id ID of this component (e.g. 200 for IMU)
95 * @param chan The MAVLink channel this message was sent over
96 * @param msg The MAVLink message to compress the data into
97 * @param target The system to be controlled
101 * @param thrust thrust
102 * @param roll_manual roll control enabled auto:0, manual:1
103 * @param pitch_manual pitch auto:0, manual:1
104 * @param yaw_manual yaw auto:0, manual:1
105 * @param thrust_manual thrust auto:0, manual:1
106 * @return length of the message in bytes (excluding serial stream start sign)
108 static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
109 mavlink_message_t
*msg
,
110 uint8_t target
, float roll
, float pitch
, float yaw
, float thrust
, uint8_t roll_manual
, uint8_t pitch_manual
, uint8_t yaw_manual
, uint8_t thrust_manual
)
112 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
114 _mav_put_float(buf
, 0, roll
);
115 _mav_put_float(buf
, 4, pitch
);
116 _mav_put_float(buf
, 8, yaw
);
117 _mav_put_float(buf
, 12, thrust
);
118 _mav_put_uint8_t(buf
, 16, target
);
119 _mav_put_uint8_t(buf
, 17, roll_manual
);
120 _mav_put_uint8_t(buf
, 18, pitch_manual
);
121 _mav_put_uint8_t(buf
, 19, yaw_manual
);
122 _mav_put_uint8_t(buf
, 20, thrust_manual
);
124 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 21);
126 mavlink_manual_control_t packet
;
128 packet
.pitch
= pitch
;
130 packet
.thrust
= thrust
;
131 packet
.target
= target
;
132 packet
.roll_manual
= roll_manual
;
133 packet
.pitch_manual
= pitch_manual
;
134 packet
.yaw_manual
= yaw_manual
;
135 packet
.thrust_manual
= thrust_manual
;
137 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 21);
138 #endif // if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
140 msg
->msgid
= MAVLINK_MSG_ID_MANUAL_CONTROL
;
141 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, 21, 52);
145 * @brief Encode a manual_control struct into a message
147 * @param system_id ID of this system
148 * @param component_id ID of this component (e.g. 200 for IMU)
149 * @param msg The MAVLink message to compress the data into
150 * @param manual_control C-struct to read the message contents from
152 static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
*msg
, const mavlink_manual_control_t
*manual_control
)
154 return mavlink_msg_manual_control_pack(system_id
, component_id
, msg
, manual_control
->target
, manual_control
->roll
, manual_control
->pitch
, manual_control
->yaw
, manual_control
->thrust
, manual_control
->roll_manual
, manual_control
->pitch_manual
, manual_control
->yaw_manual
, manual_control
->thrust_manual
);
158 * @brief Send a manual_control message
159 * @param chan MAVLink channel to send the message
161 * @param target The system to be controlled
165 * @param thrust thrust
166 * @param roll_manual roll control enabled auto:0, manual:1
167 * @param pitch_manual pitch auto:0, manual:1
168 * @param yaw_manual yaw auto:0, manual:1
169 * @param thrust_manual thrust auto:0, manual:1
171 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
173 static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan
, uint8_t target
, float roll
, float pitch
, float yaw
, float thrust
, uint8_t roll_manual
, uint8_t pitch_manual
, uint8_t yaw_manual
, uint8_t thrust_manual
)
175 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
177 _mav_put_float(buf
, 0, roll
);
178 _mav_put_float(buf
, 4, pitch
);
179 _mav_put_float(buf
, 8, yaw
);
180 _mav_put_float(buf
, 12, thrust
);
181 _mav_put_uint8_t(buf
, 16, target
);
182 _mav_put_uint8_t(buf
, 17, roll_manual
);
183 _mav_put_uint8_t(buf
, 18, pitch_manual
);
184 _mav_put_uint8_t(buf
, 19, yaw_manual
);
185 _mav_put_uint8_t(buf
, 20, thrust_manual
);
187 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_MANUAL_CONTROL
, buf
, 21, 52);
189 mavlink_manual_control_t packet
;
191 packet
.pitch
= pitch
;
193 packet
.thrust
= thrust
;
194 packet
.target
= target
;
195 packet
.roll_manual
= roll_manual
;
196 packet
.pitch_manual
= pitch_manual
;
197 packet
.yaw_manual
= yaw_manual
;
198 packet
.thrust_manual
= thrust_manual
;
200 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_MANUAL_CONTROL
, (const char *)&packet
, 21, 52);
201 #endif // if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
204 #endif // ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
206 // MESSAGE MANUAL_CONTROL UNPACKING
210 * @brief Get field target from manual_control message
212 * @return The system to be controlled
214 static inline uint8_t mavlink_msg_manual_control_get_target(const mavlink_message_t
*msg
)
216 return _MAV_RETURN_uint8_t(msg
, 16);
220 * @brief Get field roll from manual_control message
224 static inline float mavlink_msg_manual_control_get_roll(const mavlink_message_t
*msg
)
226 return _MAV_RETURN_float(msg
, 0);
230 * @brief Get field pitch from manual_control message
234 static inline float mavlink_msg_manual_control_get_pitch(const mavlink_message_t
*msg
)
236 return _MAV_RETURN_float(msg
, 4);
240 * @brief Get field yaw from manual_control message
244 static inline float mavlink_msg_manual_control_get_yaw(const mavlink_message_t
*msg
)
246 return _MAV_RETURN_float(msg
, 8);
250 * @brief Get field thrust from manual_control message
254 static inline float mavlink_msg_manual_control_get_thrust(const mavlink_message_t
*msg
)
256 return _MAV_RETURN_float(msg
, 12);
260 * @brief Get field roll_manual from manual_control message
262 * @return roll control enabled auto:0, manual:1
264 static inline uint8_t mavlink_msg_manual_control_get_roll_manual(const mavlink_message_t
*msg
)
266 return _MAV_RETURN_uint8_t(msg
, 17);
270 * @brief Get field pitch_manual from manual_control message
272 * @return pitch auto:0, manual:1
274 static inline uint8_t mavlink_msg_manual_control_get_pitch_manual(const mavlink_message_t
*msg
)
276 return _MAV_RETURN_uint8_t(msg
, 18);
280 * @brief Get field yaw_manual from manual_control message
282 * @return yaw auto:0, manual:1
284 static inline uint8_t mavlink_msg_manual_control_get_yaw_manual(const mavlink_message_t
*msg
)
286 return _MAV_RETURN_uint8_t(msg
, 19);
290 * @brief Get field thrust_manual from manual_control message
292 * @return thrust auto:0, manual:1
294 static inline uint8_t mavlink_msg_manual_control_get_thrust_manual(const mavlink_message_t
*msg
)
296 return _MAV_RETURN_uint8_t(msg
, 20);
300 * @brief Decode a manual_control message into a struct
302 * @param msg The message to decode
303 * @param manual_control C-struct to decode the message contents into
305 static inline void mavlink_msg_manual_control_decode(const mavlink_message_t
*msg
, mavlink_manual_control_t
*manual_control
)
307 #if MAVLINK_NEED_BYTE_SWAP
308 manual_control
->roll
= mavlink_msg_manual_control_get_roll(msg
);
309 manual_control
->pitch
= mavlink_msg_manual_control_get_pitch(msg
);
310 manual_control
->yaw
= mavlink_msg_manual_control_get_yaw(msg
);
311 manual_control
->thrust
= mavlink_msg_manual_control_get_thrust(msg
);
312 manual_control
->target
= mavlink_msg_manual_control_get_target(msg
);
313 manual_control
->roll_manual
= mavlink_msg_manual_control_get_roll_manual(msg
);
314 manual_control
->pitch_manual
= mavlink_msg_manual_control_get_pitch_manual(msg
);
315 manual_control
->yaw_manual
= mavlink_msg_manual_control_get_yaw_manual(msg
);
316 manual_control
->thrust_manual
= mavlink_msg_manual_control_get_thrust_manual(msg
);
318 memcpy(manual_control
, _MAV_PAYLOAD(msg
), 21);