4#define MAVLINK_MSG_ID_ALTITUDES 181
7typedef struct __mavlink_altitudes_t {
11 int32_t alt_barometric;
12 int32_t alt_optical_flow;
13 int32_t alt_range_finder;
15}) mavlink_altitudes_t;
17#define MAVLINK_MSG_ID_ALTITUDES_LEN 28
18#define MAVLINK_MSG_ID_ALTITUDES_MIN_LEN 28
19#define MAVLINK_MSG_ID_181_LEN 28
20#define MAVLINK_MSG_ID_181_MIN_LEN 28
22#define MAVLINK_MSG_ID_ALTITUDES_CRC 55
23#define MAVLINK_MSG_ID_181_CRC 55
27#if MAVLINK_COMMAND_24BIT
28#define MAVLINK_MESSAGE_INFO_ALTITUDES { \
32 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_altitudes_t, time_boot_ms) }, \
33 { "alt_gps", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_altitudes_t, alt_gps) }, \
34 { "alt_imu", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_altitudes_t, alt_imu) }, \
35 { "alt_barometric", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_altitudes_t, alt_barometric) }, \
36 { "alt_optical_flow", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_altitudes_t, alt_optical_flow) }, \
37 { "alt_range_finder", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_altitudes_t, alt_range_finder) }, \
38 { "alt_extra", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_altitudes_t, alt_extra) }, \
42#define MAVLINK_MESSAGE_INFO_ALTITUDES { \
45 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_altitudes_t, time_boot_ms) }, \
46 { "alt_gps", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_altitudes_t, alt_gps) }, \
47 { "alt_imu", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_altitudes_t, alt_imu) }, \
48 { "alt_barometric", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_altitudes_t, alt_barometric) }, \
49 { "alt_optical_flow", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_altitudes_t, alt_optical_flow) }, \
50 { "alt_range_finder", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_altitudes_t, alt_range_finder) }, \
51 { "alt_extra", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_altitudes_t, alt_extra) }, \
71static inline uint16_t mavlink_msg_altitudes_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
72 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)
74#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
75 char buf[MAVLINK_MSG_ID_ALTITUDES_LEN];
76 _mav_put_uint32_t(buf, 0, time_boot_ms);
77 _mav_put_int32_t(buf, 4, alt_gps);
78 _mav_put_int32_t(buf, 8, alt_imu);
79 _mav_put_int32_t(buf, 12, alt_barometric);
80 _mav_put_int32_t(buf, 16, alt_optical_flow);
81 _mav_put_int32_t(buf, 20, alt_range_finder);
82 _mav_put_int32_t(buf, 24, alt_extra);
84 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDES_LEN);
86 mavlink_altitudes_t packet;
87 packet.time_boot_ms = time_boot_ms;
88 packet.alt_gps = alt_gps;
89 packet.alt_imu = alt_imu;
90 packet.alt_barometric = alt_barometric;
91 packet.alt_optical_flow = alt_optical_flow;
92 packet.alt_range_finder = alt_range_finder;
93 packet.alt_extra = alt_extra;
95 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDES_LEN);
98 msg->msgid = MAVLINK_MSG_ID_ALTITUDES;
99 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ALTITUDES_MIN_LEN, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC);
117static inline uint16_t mavlink_msg_altitudes_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
118 mavlink_message_t* msg,
119 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)
121#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
122 char buf[MAVLINK_MSG_ID_ALTITUDES_LEN];
123 _mav_put_uint32_t(buf, 0, time_boot_ms);
124 _mav_put_int32_t(buf, 4, alt_gps);
125 _mav_put_int32_t(buf, 8, alt_imu);
126 _mav_put_int32_t(buf, 12, alt_barometric);
127 _mav_put_int32_t(buf, 16, alt_optical_flow);
128 _mav_put_int32_t(buf, 20, alt_range_finder);
129 _mav_put_int32_t(buf, 24, alt_extra);
131 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDES_LEN);
133 mavlink_altitudes_t packet;
134 packet.time_boot_ms = time_boot_ms;
135 packet.alt_gps = alt_gps;
136 packet.alt_imu = alt_imu;
137 packet.alt_barometric = alt_barometric;
138 packet.alt_optical_flow = alt_optical_flow;
139 packet.alt_range_finder = alt_range_finder;
140 packet.alt_extra = alt_extra;
142 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDES_LEN);
145 msg->msgid = MAVLINK_MSG_ID_ALTITUDES;
146 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ALTITUDES_MIN_LEN, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC);
157static inline uint16_t mavlink_msg_altitudes_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_altitudes_t* altitudes)
159 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);
171static 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)
173 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);
188#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
190static 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)
192#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
193 char buf[MAVLINK_MSG_ID_ALTITUDES_LEN];
194 _mav_put_uint32_t(buf, 0, time_boot_ms);
195 _mav_put_int32_t(buf, 4, alt_gps);
196 _mav_put_int32_t(buf, 8, alt_imu);
197 _mav_put_int32_t(buf, 12, alt_barometric);
198 _mav_put_int32_t(buf, 16, alt_optical_flow);
199 _mav_put_int32_t(buf, 20, alt_range_finder);
200 _mav_put_int32_t(buf, 24, alt_extra);
202 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, buf, MAVLINK_MSG_ID_ALTITUDES_MIN_LEN, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC);
204 mavlink_altitudes_t packet;
205 packet.time_boot_ms = time_boot_ms;
206 packet.alt_gps = alt_gps;
207 packet.alt_imu = alt_imu;
208 packet.alt_barometric = alt_barometric;
209 packet.alt_optical_flow = alt_optical_flow;
210 packet.alt_range_finder = alt_range_finder;
211 packet.alt_extra = alt_extra;
213 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, (
const char *)&packet, MAVLINK_MSG_ID_ALTITUDES_MIN_LEN, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC);
222static inline void mavlink_msg_altitudes_send_struct(mavlink_channel_t chan,
const mavlink_altitudes_t* altitudes)
224#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
225 mavlink_msg_altitudes_send(chan, altitudes->time_boot_ms, altitudes->alt_gps, altitudes->alt_imu, altitudes->alt_barometric, altitudes->alt_optical_flow, altitudes->alt_range_finder, altitudes->alt_extra);
227 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, (
const char *)altitudes, MAVLINK_MSG_ID_ALTITUDES_MIN_LEN, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC);
231#if MAVLINK_MSG_ID_ALTITUDES_LEN <= MAVLINK_MAX_PAYLOAD_LEN
239static 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)
241#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
242 char *buf = (
char *)msgbuf;
243 _mav_put_uint32_t(buf, 0, time_boot_ms);
244 _mav_put_int32_t(buf, 4, alt_gps);
245 _mav_put_int32_t(buf, 8, alt_imu);
246 _mav_put_int32_t(buf, 12, alt_barometric);
247 _mav_put_int32_t(buf, 16, alt_optical_flow);
248 _mav_put_int32_t(buf, 20, alt_range_finder);
249 _mav_put_int32_t(buf, 24, alt_extra);
251 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, buf, MAVLINK_MSG_ID_ALTITUDES_MIN_LEN, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC);
253 mavlink_altitudes_t *packet = (mavlink_altitudes_t *)msgbuf;
254 packet->time_boot_ms = time_boot_ms;
255 packet->alt_gps = alt_gps;
256 packet->alt_imu = alt_imu;
257 packet->alt_barometric = alt_barometric;
258 packet->alt_optical_flow = alt_optical_flow;
259 packet->alt_range_finder = alt_range_finder;
260 packet->alt_extra = alt_extra;
262 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, (
const char *)packet, MAVLINK_MSG_ID_ALTITUDES_MIN_LEN, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC);
277static inline uint32_t mavlink_msg_altitudes_get_time_boot_ms(
const mavlink_message_t* msg)
279 return _MAV_RETURN_uint32_t(msg, 0);
287static inline int32_t mavlink_msg_altitudes_get_alt_gps(
const mavlink_message_t* msg)
289 return _MAV_RETURN_int32_t(msg, 4);
297static inline int32_t mavlink_msg_altitudes_get_alt_imu(
const mavlink_message_t* msg)
299 return _MAV_RETURN_int32_t(msg, 8);
307static inline int32_t mavlink_msg_altitudes_get_alt_barometric(
const mavlink_message_t* msg)
309 return _MAV_RETURN_int32_t(msg, 12);
317static inline int32_t mavlink_msg_altitudes_get_alt_optical_flow(
const mavlink_message_t* msg)
319 return _MAV_RETURN_int32_t(msg, 16);
327static inline int32_t mavlink_msg_altitudes_get_alt_range_finder(
const mavlink_message_t* msg)
329 return _MAV_RETURN_int32_t(msg, 20);
337static inline int32_t mavlink_msg_altitudes_get_alt_extra(
const mavlink_message_t* msg)
339 return _MAV_RETURN_int32_t(msg, 24);
348static inline void mavlink_msg_altitudes_decode(
const mavlink_message_t* msg, mavlink_altitudes_t* altitudes)
350#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
351 altitudes->time_boot_ms = mavlink_msg_altitudes_get_time_boot_ms(msg);
352 altitudes->alt_gps = mavlink_msg_altitudes_get_alt_gps(msg);
353 altitudes->alt_imu = mavlink_msg_altitudes_get_alt_imu(msg);
354 altitudes->alt_barometric = mavlink_msg_altitudes_get_alt_barometric(msg);
355 altitudes->alt_optical_flow = mavlink_msg_altitudes_get_alt_optical_flow(msg);
356 altitudes->alt_range_finder = mavlink_msg_altitudes_get_alt_range_finder(msg);
357 altitudes->alt_extra = mavlink_msg_altitudes_get_alt_extra(msg);
359 uint8_t len = msg->len < MAVLINK_MSG_ID_ALTITUDES_LEN? msg->len : MAVLINK_MSG_ID_ALTITUDES_LEN;
360 memset(altitudes, 0, MAVLINK_MSG_ID_ALTITUDES_LEN);
361 memcpy(altitudes, _MAV_PAYLOAD(msg), len);