3 #define MAVLINK_MSG_ID_ALTITUDES 181
16 #define MAVLINK_MSG_ID_ALTITUDES_LEN 28
17 #define MAVLINK_MSG_ID_181_LEN 28
19 #define MAVLINK_MSG_ID_ALTITUDES_CRC 55
20 #define MAVLINK_MSG_ID_181_CRC 55
24 #define MAVLINK_MESSAGE_INFO_ALTITUDES { \
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) }, \
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)
56 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
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)
107 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
132 #if MAVLINK_CRC_EXTRA
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)
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)
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);
178 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
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)
182 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
192 #if MAVLINK_CRC_EXTRA
207 #if MAVLINK_CRC_EXTRA
215 #if MAVLINK_MSG_ID_ALTITUDES_LEN <= MAVLINK_MAX_PAYLOAD_LEN
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)
225 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
226 char *buf = (
char *)msgbuf;
235 #if MAVLINK_CRC_EXTRA
250 #if MAVLINK_CRC_EXTRA
269 static inline uint32_t mavlink_msg_altitudes_get_time_boot_ms(
const mavlink_message_t* msg)
271 return _MAV_RETURN_uint32_t(msg, 0);
279 static inline int32_t mavlink_msg_altitudes_get_alt_gps(
const mavlink_message_t* msg)
281 return _MAV_RETURN_int32_t(msg, 4);
289 static inline int32_t mavlink_msg_altitudes_get_alt_imu(
const mavlink_message_t* msg)
291 return _MAV_RETURN_int32_t(msg, 8);
299 static inline int32_t mavlink_msg_altitudes_get_alt_barometric(
const mavlink_message_t* msg)
301 return _MAV_RETURN_int32_t(msg, 12);
309 static inline int32_t mavlink_msg_altitudes_get_alt_optical_flow(
const mavlink_message_t* msg)
311 return _MAV_RETURN_int32_t(msg, 16);
319 static inline int32_t mavlink_msg_altitudes_get_alt_range_finder(
const mavlink_message_t* msg)
321 return _MAV_RETURN_int32_t(msg, 20);
329 static inline int32_t mavlink_msg_altitudes_get_alt_extra(
const mavlink_message_t* msg)
331 return _MAV_RETURN_int32_t(msg, 24);
340 static inline void mavlink_msg_altitudes_decode(
const mavlink_message_t* msg,
mavlink_altitudes_t* altitudes)
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);
#define MAVLINK_MSG_ID_ALTITUDES
Definition: mavlink_msg_altitudes.h:3
int32_t alt_optical_flow
Optical flow altitude above ground in meters, expressed as * 1000 (millimeters)
Definition: mavlink_msg_altitudes.h:11
int32_t alt_range_finder
Rangefinder Altitude above ground in meters, expressed as * 1000 (millimeters)
Definition: mavlink_msg_altitudes.h:12
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
Definition: mavlink_helpers.h:105
Definition: mavlink_msg_altitudes.h:5
#define _mav_put_int32_t(buf, wire_offset, b)
Definition: protocol.h:142
int32_t alt_barometric
barometeric altitude above ground in meters, expressed as * 1000 (millimeters)
Definition: mavlink_msg_altitudes.h:10
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
int32_t alt_gps
GPS altitude in meters, expressed as * 1000 (millimeters), above MSL.
Definition: mavlink_msg_altitudes.h:8
int32_t alt_extra
Extra altitude above ground in meters, expressed as * 1000 (millimeters)
Definition: mavlink_msg_altitudes.h:13
mavlink_channel_t
Definition: mavlink_types.h:178
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
int32_t alt_imu
IMU altitude above ground in meters, expressed as * 1000 (millimeters)
Definition: mavlink_msg_altitudes.h:9
#define MAVLINK_MSG_ID_ALTITUDES_LEN
Definition: mavlink_msg_altitudes.h:16
struct __mavlink_altitudes_t mavlink_altitudes_t
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
Definition: mavlink_helpers.h:71
#define MAVLINK_MSG_ID_ALTITUDES_CRC
Definition: mavlink_msg_altitudes.h:19
uint32_t time_boot_ms
Timestamp (milliseconds since system boot)
Definition: mavlink_msg_altitudes.h:7
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:141