NinjaFlight
 All Data Structures Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
mavlink_msg_radio_calibration.h
Go to the documentation of this file.
1 // MESSAGE RADIO_CALIBRATION PACKING
2 
3 #define MAVLINK_MSG_ID_RADIO_CALIBRATION 221
4 
6 {
7  uint16_t aileron[3];
8  uint16_t elevator[3];
9  uint16_t rudder[3];
10  uint16_t gyro[2];
11  uint16_t pitch[5];
12  uint16_t throttle[5];
14 
15 #define MAVLINK_MSG_ID_RADIO_CALIBRATION_LEN 42
16 #define MAVLINK_MSG_ID_221_LEN 42
17 
18 #define MAVLINK_MSG_ID_RADIO_CALIBRATION_CRC 71
19 #define MAVLINK_MSG_ID_221_CRC 71
20 
21 #define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_AILERON_LEN 3
22 #define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_ELEVATOR_LEN 3
23 #define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_RUDDER_LEN 3
24 #define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_GYRO_LEN 2
25 #define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_PITCH_LEN 5
26 #define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_THROTTLE_LEN 5
27 
28 #define MAVLINK_MESSAGE_INFO_RADIO_CALIBRATION { \
29  "RADIO_CALIBRATION", \
30  6, \
31  { { "aileron", NULL, MAVLINK_TYPE_UINT16_T, 3, 0, offsetof(mavlink_radio_calibration_t, aileron) }, \
32  { "elevator", NULL, MAVLINK_TYPE_UINT16_T, 3, 6, offsetof(mavlink_radio_calibration_t, elevator) }, \
33  { "rudder", NULL, MAVLINK_TYPE_UINT16_T, 3, 12, offsetof(mavlink_radio_calibration_t, rudder) }, \
34  { "gyro", NULL, MAVLINK_TYPE_UINT16_T, 2, 18, offsetof(mavlink_radio_calibration_t, gyro) }, \
35  { "pitch", NULL, MAVLINK_TYPE_UINT16_T, 5, 22, offsetof(mavlink_radio_calibration_t, pitch) }, \
36  { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 5, 32, offsetof(mavlink_radio_calibration_t, throttle) }, \
37  } \
38 }
39 
40 
55 static inline uint16_t mavlink_msg_radio_calibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
56  const uint16_t *aileron, const uint16_t *elevator, const uint16_t *rudder, const uint16_t *gyro, const uint16_t *pitch, const uint16_t *throttle)
57 {
58 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
60 
61  _mav_put_uint16_t_array(buf, 0, aileron, 3);
62  _mav_put_uint16_t_array(buf, 6, elevator, 3);
63  _mav_put_uint16_t_array(buf, 12, rudder, 3);
64  _mav_put_uint16_t_array(buf, 18, gyro, 2);
65  _mav_put_uint16_t_array(buf, 22, pitch, 5);
66  _mav_put_uint16_t_array(buf, 32, throttle, 5);
68 #else
70 
71  mav_array_memcpy(packet.aileron, aileron, sizeof(uint16_t)*3);
72  mav_array_memcpy(packet.elevator, elevator, sizeof(uint16_t)*3);
73  mav_array_memcpy(packet.rudder, rudder, sizeof(uint16_t)*3);
74  mav_array_memcpy(packet.gyro, gyro, sizeof(uint16_t)*2);
75  mav_array_memcpy(packet.pitch, pitch, sizeof(uint16_t)*5);
76  mav_array_memcpy(packet.throttle, throttle, sizeof(uint16_t)*5);
78 #endif
79 
81 #if MAVLINK_CRC_EXTRA
83 #else
84  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RADIO_CALIBRATION_LEN);
85 #endif
86 }
87 
102 static inline uint16_t mavlink_msg_radio_calibration_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
103  mavlink_message_t* msg,
104  const uint16_t *aileron,const uint16_t *elevator,const uint16_t *rudder,const uint16_t *gyro,const uint16_t *pitch,const uint16_t *throttle)
105 {
106 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
108 
109  _mav_put_uint16_t_array(buf, 0, aileron, 3);
110  _mav_put_uint16_t_array(buf, 6, elevator, 3);
111  _mav_put_uint16_t_array(buf, 12, rudder, 3);
112  _mav_put_uint16_t_array(buf, 18, gyro, 2);
113  _mav_put_uint16_t_array(buf, 22, pitch, 5);
114  _mav_put_uint16_t_array(buf, 32, throttle, 5);
116 #else
118 
119  mav_array_memcpy(packet.aileron, aileron, sizeof(uint16_t)*3);
120  mav_array_memcpy(packet.elevator, elevator, sizeof(uint16_t)*3);
121  mav_array_memcpy(packet.rudder, rudder, sizeof(uint16_t)*3);
122  mav_array_memcpy(packet.gyro, gyro, sizeof(uint16_t)*2);
123  mav_array_memcpy(packet.pitch, pitch, sizeof(uint16_t)*5);
124  mav_array_memcpy(packet.throttle, throttle, sizeof(uint16_t)*5);
126 #endif
127 
129 #if MAVLINK_CRC_EXTRA
131 #else
132  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RADIO_CALIBRATION_LEN);
133 #endif
134 }
135 
144 static inline uint16_t mavlink_msg_radio_calibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_calibration_t* radio_calibration)
145 {
146  return mavlink_msg_radio_calibration_pack(system_id, component_id, msg, radio_calibration->aileron, radio_calibration->elevator, radio_calibration->rudder, radio_calibration->gyro, radio_calibration->pitch, radio_calibration->throttle);
147 }
148 
158 static inline uint16_t mavlink_msg_radio_calibration_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_radio_calibration_t* radio_calibration)
159 {
160  return mavlink_msg_radio_calibration_pack_chan(system_id, component_id, chan, msg, radio_calibration->aileron, radio_calibration->elevator, radio_calibration->rudder, radio_calibration->gyro, radio_calibration->pitch, radio_calibration->throttle);
161 }
162 
174 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
175 
176 static inline void mavlink_msg_radio_calibration_send(mavlink_channel_t chan, const uint16_t *aileron, const uint16_t *elevator, const uint16_t *rudder, const uint16_t *gyro, const uint16_t *pitch, const uint16_t *throttle)
177 {
178 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
180 
181  _mav_put_uint16_t_array(buf, 0, aileron, 3);
182  _mav_put_uint16_t_array(buf, 6, elevator, 3);
183  _mav_put_uint16_t_array(buf, 12, rudder, 3);
184  _mav_put_uint16_t_array(buf, 18, gyro, 2);
185  _mav_put_uint16_t_array(buf, 22, pitch, 5);
186  _mav_put_uint16_t_array(buf, 32, throttle, 5);
187 #if MAVLINK_CRC_EXTRA
189 #else
190  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_CALIBRATION, buf, MAVLINK_MSG_ID_RADIO_CALIBRATION_LEN);
191 #endif
192 #else
194 
195  mav_array_memcpy(packet.aileron, aileron, sizeof(uint16_t)*3);
196  mav_array_memcpy(packet.elevator, elevator, sizeof(uint16_t)*3);
197  mav_array_memcpy(packet.rudder, rudder, sizeof(uint16_t)*3);
198  mav_array_memcpy(packet.gyro, gyro, sizeof(uint16_t)*2);
199  mav_array_memcpy(packet.pitch, pitch, sizeof(uint16_t)*5);
200  mav_array_memcpy(packet.throttle, throttle, sizeof(uint16_t)*5);
201 #if MAVLINK_CRC_EXTRA
202  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_CALIBRATION, (const char *)&packet, MAVLINK_MSG_ID_RADIO_CALIBRATION_LEN, MAVLINK_MSG_ID_RADIO_CALIBRATION_CRC);
203 #else
204  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_CALIBRATION, (const char *)&packet, MAVLINK_MSG_ID_RADIO_CALIBRATION_LEN);
205 #endif
206 #endif
207 }
208 
209 #if MAVLINK_MSG_ID_RADIO_CALIBRATION_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_radio_calibration_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint16_t *aileron, const uint16_t *elevator, const uint16_t *rudder, const uint16_t *gyro, const uint16_t *pitch, const uint16_t *throttle)
218 {
219 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
220  char *buf = (char *)msgbuf;
221 
222  _mav_put_uint16_t_array(buf, 0, aileron, 3);
223  _mav_put_uint16_t_array(buf, 6, elevator, 3);
224  _mav_put_uint16_t_array(buf, 12, rudder, 3);
225  _mav_put_uint16_t_array(buf, 18, gyro, 2);
226  _mav_put_uint16_t_array(buf, 22, pitch, 5);
227  _mav_put_uint16_t_array(buf, 32, throttle, 5);
228 #if MAVLINK_CRC_EXTRA
230 #else
231  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_CALIBRATION, buf, MAVLINK_MSG_ID_RADIO_CALIBRATION_LEN);
232 #endif
233 #else
235 
236  mav_array_memcpy(packet->aileron, aileron, sizeof(uint16_t)*3);
237  mav_array_memcpy(packet->elevator, elevator, sizeof(uint16_t)*3);
238  mav_array_memcpy(packet->rudder, rudder, sizeof(uint16_t)*3);
239  mav_array_memcpy(packet->gyro, gyro, sizeof(uint16_t)*2);
240  mav_array_memcpy(packet->pitch, pitch, sizeof(uint16_t)*5);
241  mav_array_memcpy(packet->throttle, throttle, sizeof(uint16_t)*5);
242 #if MAVLINK_CRC_EXTRA
243  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_CALIBRATION, (const char *)packet, MAVLINK_MSG_ID_RADIO_CALIBRATION_LEN, MAVLINK_MSG_ID_RADIO_CALIBRATION_CRC);
244 #else
245  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_CALIBRATION, (const char *)packet, MAVLINK_MSG_ID_RADIO_CALIBRATION_LEN);
246 #endif
247 #endif
248 }
249 #endif
250 
251 #endif
252 
253 // MESSAGE RADIO_CALIBRATION UNPACKING
254 
255 
261 static inline uint16_t mavlink_msg_radio_calibration_get_aileron(const mavlink_message_t* msg, uint16_t *aileron)
262 {
263  return _MAV_RETURN_uint16_t_array(msg, aileron, 3, 0);
264 }
265 
271 static inline uint16_t mavlink_msg_radio_calibration_get_elevator(const mavlink_message_t* msg, uint16_t *elevator)
272 {
273  return _MAV_RETURN_uint16_t_array(msg, elevator, 3, 6);
274 }
275 
281 static inline uint16_t mavlink_msg_radio_calibration_get_rudder(const mavlink_message_t* msg, uint16_t *rudder)
282 {
283  return _MAV_RETURN_uint16_t_array(msg, rudder, 3, 12);
284 }
285 
291 static inline uint16_t mavlink_msg_radio_calibration_get_gyro(const mavlink_message_t* msg, uint16_t *gyro)
292 {
293  return _MAV_RETURN_uint16_t_array(msg, gyro, 2, 18);
294 }
295 
301 static inline uint16_t mavlink_msg_radio_calibration_get_pitch(const mavlink_message_t* msg, uint16_t *pitch)
302 {
303  return _MAV_RETURN_uint16_t_array(msg, pitch, 5, 22);
304 }
305 
311 static inline uint16_t mavlink_msg_radio_calibration_get_throttle(const mavlink_message_t* msg, uint16_t *throttle)
312 {
313  return _MAV_RETURN_uint16_t_array(msg, throttle, 5, 32);
314 }
315 
322 static inline void mavlink_msg_radio_calibration_decode(const mavlink_message_t* msg, mavlink_radio_calibration_t* radio_calibration)
323 {
324 #if MAVLINK_NEED_BYTE_SWAP
325  mavlink_msg_radio_calibration_get_aileron(msg, radio_calibration->aileron);
326  mavlink_msg_radio_calibration_get_elevator(msg, radio_calibration->elevator);
327  mavlink_msg_radio_calibration_get_rudder(msg, radio_calibration->rudder);
328  mavlink_msg_radio_calibration_get_gyro(msg, radio_calibration->gyro);
329  mavlink_msg_radio_calibration_get_pitch(msg, radio_calibration->pitch);
330  mavlink_msg_radio_calibration_get_throttle(msg, radio_calibration->throttle);
331 #else
332  memcpy(radio_calibration, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RADIO_CALIBRATION_LEN);
333 #endif
334 }
struct throttle_correction_config throttle
Definition: config.h:98
struct gyro_config gyro
Definition: config.h:93
int16_t pitch
Definition: accelerometer.h:52