NinjaFlight
 All Data Structures Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
mavlink_msg_altitudes.h
Go to the documentation of this file.
1 // MESSAGE ALTITUDES PACKING
2 
3 #define MAVLINK_MSG_ID_ALTITUDES 181
4 
5 typedef struct __mavlink_altitudes_t
6 {
7  uint32_t time_boot_ms;
8  int32_t alt_gps;
9  int32_t alt_imu;
10  int32_t alt_barometric;
11  int32_t alt_optical_flow;
12  int32_t alt_range_finder;
13  int32_t alt_extra;
15 
16 #define MAVLINK_MSG_ID_ALTITUDES_LEN 28
17 #define MAVLINK_MSG_ID_181_LEN 28
18 
19 #define MAVLINK_MSG_ID_ALTITUDES_CRC 55
20 #define MAVLINK_MSG_ID_181_CRC 55
21 
22 
23 
24 #define MAVLINK_MESSAGE_INFO_ALTITUDES { \
25  "ALTITUDES", \
26  7, \
27  { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_altitudes_t, time_boot_ms) }, \
28  { "alt_gps", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_altitudes_t, alt_gps) }, \
29  { "alt_imu", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_altitudes_t, alt_imu) }, \
30  { "alt_barometric", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_altitudes_t, alt_barometric) }, \
31  { "alt_optical_flow", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_altitudes_t, alt_optical_flow) }, \
32  { "alt_range_finder", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_altitudes_t, alt_range_finder) }, \
33  { "alt_extra", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_altitudes_t, alt_extra) }, \
34  } \
35 }
36 
37 
53 static inline uint16_t mavlink_msg_altitudes_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
54  uint32_t time_boot_ms, int32_t alt_gps, int32_t alt_imu, int32_t alt_barometric, int32_t alt_optical_flow, int32_t alt_range_finder, int32_t alt_extra)
55 {
56 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
58  _mav_put_uint32_t(buf, 0, time_boot_ms);
59  _mav_put_int32_t(buf, 4, alt_gps);
60  _mav_put_int32_t(buf, 8, alt_imu);
61  _mav_put_int32_t(buf, 12, alt_barometric);
62  _mav_put_int32_t(buf, 16, alt_optical_flow);
63  _mav_put_int32_t(buf, 20, alt_range_finder);
64  _mav_put_int32_t(buf, 24, alt_extra);
65 
67 #else
68  mavlink_altitudes_t packet;
69  packet.time_boot_ms = time_boot_ms;
70  packet.alt_gps = alt_gps;
71  packet.alt_imu = alt_imu;
72  packet.alt_barometric = alt_barometric;
73  packet.alt_optical_flow = alt_optical_flow;
74  packet.alt_range_finder = alt_range_finder;
75  packet.alt_extra = alt_extra;
76 
78 #endif
79 
80  msg->msgid = MAVLINK_MSG_ID_ALTITUDES;
81 #if MAVLINK_CRC_EXTRA
83 #else
84  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ALTITUDES_LEN);
85 #endif
86 }
87 
103 static inline uint16_t mavlink_msg_altitudes_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
104  mavlink_message_t* msg,
105  uint32_t time_boot_ms,int32_t alt_gps,int32_t alt_imu,int32_t alt_barometric,int32_t alt_optical_flow,int32_t alt_range_finder,int32_t alt_extra)
106 {
107 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
109  _mav_put_uint32_t(buf, 0, time_boot_ms);
110  _mav_put_int32_t(buf, 4, alt_gps);
111  _mav_put_int32_t(buf, 8, alt_imu);
112  _mav_put_int32_t(buf, 12, alt_barometric);
113  _mav_put_int32_t(buf, 16, alt_optical_flow);
114  _mav_put_int32_t(buf, 20, alt_range_finder);
115  _mav_put_int32_t(buf, 24, alt_extra);
116 
118 #else
119  mavlink_altitudes_t packet;
120  packet.time_boot_ms = time_boot_ms;
121  packet.alt_gps = alt_gps;
122  packet.alt_imu = alt_imu;
123  packet.alt_barometric = alt_barometric;
124  packet.alt_optical_flow = alt_optical_flow;
125  packet.alt_range_finder = alt_range_finder;
126  packet.alt_extra = alt_extra;
127 
129 #endif
130 
131  msg->msgid = MAVLINK_MSG_ID_ALTITUDES;
132 #if MAVLINK_CRC_EXTRA
134 #else
135  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ALTITUDES_LEN);
136 #endif
137 }
138 
147 static inline uint16_t mavlink_msg_altitudes_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_altitudes_t* altitudes)
148 {
149  return mavlink_msg_altitudes_pack(system_id, component_id, msg, altitudes->time_boot_ms, altitudes->alt_gps, altitudes->alt_imu, altitudes->alt_barometric, altitudes->alt_optical_flow, altitudes->alt_range_finder, altitudes->alt_extra);
150 }
151 
161 static inline uint16_t mavlink_msg_altitudes_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_altitudes_t* altitudes)
162 {
163  return mavlink_msg_altitudes_pack_chan(system_id, component_id, chan, msg, altitudes->time_boot_ms, altitudes->alt_gps, altitudes->alt_imu, altitudes->alt_barometric, altitudes->alt_optical_flow, altitudes->alt_range_finder, altitudes->alt_extra);
164 }
165 
178 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
179 
180 static inline void mavlink_msg_altitudes_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t alt_gps, int32_t alt_imu, int32_t alt_barometric, int32_t alt_optical_flow, int32_t alt_range_finder, int32_t alt_extra)
181 {
182 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
184  _mav_put_uint32_t(buf, 0, time_boot_ms);
185  _mav_put_int32_t(buf, 4, alt_gps);
186  _mav_put_int32_t(buf, 8, alt_imu);
187  _mav_put_int32_t(buf, 12, alt_barometric);
188  _mav_put_int32_t(buf, 16, alt_optical_flow);
189  _mav_put_int32_t(buf, 20, alt_range_finder);
190  _mav_put_int32_t(buf, 24, alt_extra);
191 
192 #if MAVLINK_CRC_EXTRA
193  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, buf, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC);
194 #else
195  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, buf, MAVLINK_MSG_ID_ALTITUDES_LEN);
196 #endif
197 #else
198  mavlink_altitudes_t packet;
199  packet.time_boot_ms = time_boot_ms;
200  packet.alt_gps = alt_gps;
201  packet.alt_imu = alt_imu;
202  packet.alt_barometric = alt_barometric;
203  packet.alt_optical_flow = alt_optical_flow;
204  packet.alt_range_finder = alt_range_finder;
205  packet.alt_extra = alt_extra;
206 
207 #if MAVLINK_CRC_EXTRA
208  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, (const char *)&packet, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC);
209 #else
210  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, (const char *)&packet, MAVLINK_MSG_ID_ALTITUDES_LEN);
211 #endif
212 #endif
213 }
214 
215 #if MAVLINK_MSG_ID_ALTITUDES_LEN <= MAVLINK_MAX_PAYLOAD_LEN
216 /*
217  This varient of _send() can be used to save stack space by re-using
218  memory from the receive buffer. The caller provides a
219  mavlink_message_t which is the size of a full mavlink message. This
220  is usually the receive buffer for the channel, and allows a reply to an
221  incoming message with minimum stack space usage.
222  */
223 static inline void mavlink_msg_altitudes_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int32_t alt_gps, int32_t alt_imu, int32_t alt_barometric, int32_t alt_optical_flow, int32_t alt_range_finder, int32_t alt_extra)
224 {
225 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
226  char *buf = (char *)msgbuf;
227  _mav_put_uint32_t(buf, 0, time_boot_ms);
228  _mav_put_int32_t(buf, 4, alt_gps);
229  _mav_put_int32_t(buf, 8, alt_imu);
230  _mav_put_int32_t(buf, 12, alt_barometric);
231  _mav_put_int32_t(buf, 16, alt_optical_flow);
232  _mav_put_int32_t(buf, 20, alt_range_finder);
233  _mav_put_int32_t(buf, 24, alt_extra);
234 
235 #if MAVLINK_CRC_EXTRA
236  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, buf, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC);
237 #else
238  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, buf, MAVLINK_MSG_ID_ALTITUDES_LEN);
239 #endif
240 #else
241  mavlink_altitudes_t *packet = (mavlink_altitudes_t *)msgbuf;
242  packet->time_boot_ms = time_boot_ms;
243  packet->alt_gps = alt_gps;
244  packet->alt_imu = alt_imu;
245  packet->alt_barometric = alt_barometric;
246  packet->alt_optical_flow = alt_optical_flow;
247  packet->alt_range_finder = alt_range_finder;
248  packet->alt_extra = alt_extra;
249 
250 #if MAVLINK_CRC_EXTRA
251  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, (const char *)packet, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC);
252 #else
253  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, (const char *)packet, MAVLINK_MSG_ID_ALTITUDES_LEN);
254 #endif
255 #endif
256 }
257 #endif
258 
259 #endif
260 
261 // MESSAGE ALTITUDES UNPACKING
262 
263 
269 static inline uint32_t mavlink_msg_altitudes_get_time_boot_ms(const mavlink_message_t* msg)
270 {
271  return _MAV_RETURN_uint32_t(msg, 0);
272 }
273 
279 static inline int32_t mavlink_msg_altitudes_get_alt_gps(const mavlink_message_t* msg)
280 {
281  return _MAV_RETURN_int32_t(msg, 4);
282 }
283 
289 static inline int32_t mavlink_msg_altitudes_get_alt_imu(const mavlink_message_t* msg)
290 {
291  return _MAV_RETURN_int32_t(msg, 8);
292 }
293 
299 static inline int32_t mavlink_msg_altitudes_get_alt_barometric(const mavlink_message_t* msg)
300 {
301  return _MAV_RETURN_int32_t(msg, 12);
302 }
303 
309 static inline int32_t mavlink_msg_altitudes_get_alt_optical_flow(const mavlink_message_t* msg)
310 {
311  return _MAV_RETURN_int32_t(msg, 16);
312 }
313 
319 static inline int32_t mavlink_msg_altitudes_get_alt_range_finder(const mavlink_message_t* msg)
320 {
321  return _MAV_RETURN_int32_t(msg, 20);
322 }
323 
329 static inline int32_t mavlink_msg_altitudes_get_alt_extra(const mavlink_message_t* msg)
330 {
331  return _MAV_RETURN_int32_t(msg, 24);
332 }
333 
340 static inline void mavlink_msg_altitudes_decode(const mavlink_message_t* msg, mavlink_altitudes_t* altitudes)
341 {
342 #if MAVLINK_NEED_BYTE_SWAP
343  altitudes->time_boot_ms = mavlink_msg_altitudes_get_time_boot_ms(msg);
344  altitudes->alt_gps = mavlink_msg_altitudes_get_alt_gps(msg);
345  altitudes->alt_imu = mavlink_msg_altitudes_get_alt_imu(msg);
346  altitudes->alt_barometric = mavlink_msg_altitudes_get_alt_barometric(msg);
347  altitudes->alt_optical_flow = mavlink_msg_altitudes_get_alt_optical_flow(msg);
348  altitudes->alt_range_finder = mavlink_msg_altitudes_get_alt_range_finder(msg);
349  altitudes->alt_extra = mavlink_msg_altitudes_get_alt_extra(msg);
350 #else
351  memcpy(altitudes, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ALTITUDES_LEN);
352 #endif
353 }
#define _mav_put_int32_t(buf, wire_offset, b)
Definition: protocol.h:142
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:141