Dependents:   AIT_UWB_Range

Committer:
bhepp
Date:
Mon Apr 04 11:18:57 2016 +0000
Revision:
10:bd4a08d39e94
Parent:
0:28183cc7963f
nop

Who changed what in which revision?

UserRevisionLine numberNew contents of line
bhepp 0:28183cc7963f 1 // MESSAGE ALTITUDE PACKING
bhepp 0:28183cc7963f 2
bhepp 0:28183cc7963f 3 #define MAVLINK_MSG_ID_ALTITUDE 141
bhepp 0:28183cc7963f 4
bhepp 0:28183cc7963f 5 typedef struct __mavlink_altitude_t
bhepp 0:28183cc7963f 6 {
bhepp 0:28183cc7963f 7 float altitude_monotonic; /*< This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.*/
bhepp 0:28183cc7963f 8 float altitude_amsl; /*< This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude.*/
bhepp 0:28183cc7963f 9 float altitude_local; /*< This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.*/
bhepp 0:28183cc7963f 10 float altitude_relative; /*< This is the altitude above the home position. It resets on each change of the current home position.*/
bhepp 0:28183cc7963f 11 float altitude_terrain; /*< This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.*/
bhepp 0:28183cc7963f 12 float bottom_clearance; /*< This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.*/
bhepp 0:28183cc7963f 13 } mavlink_altitude_t;
bhepp 0:28183cc7963f 14
bhepp 0:28183cc7963f 15 #define MAVLINK_MSG_ID_ALTITUDE_LEN 24
bhepp 0:28183cc7963f 16 #define MAVLINK_MSG_ID_141_LEN 24
bhepp 0:28183cc7963f 17
bhepp 0:28183cc7963f 18 #define MAVLINK_MSG_ID_ALTITUDE_CRC 148
bhepp 0:28183cc7963f 19 #define MAVLINK_MSG_ID_141_CRC 148
bhepp 0:28183cc7963f 20
bhepp 0:28183cc7963f 21
bhepp 0:28183cc7963f 22
bhepp 0:28183cc7963f 23 #define MAVLINK_MESSAGE_INFO_ALTITUDE { \
bhepp 0:28183cc7963f 24 "ALTITUDE", \
bhepp 0:28183cc7963f 25 6, \
bhepp 0:28183cc7963f 26 { { "altitude_monotonic", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_altitude_t, altitude_monotonic) }, \
bhepp 0:28183cc7963f 27 { "altitude_amsl", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_altitude_t, altitude_amsl) }, \
bhepp 0:28183cc7963f 28 { "altitude_local", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_altitude_t, altitude_local) }, \
bhepp 0:28183cc7963f 29 { "altitude_relative", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_altitude_t, altitude_relative) }, \
bhepp 0:28183cc7963f 30 { "altitude_terrain", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_altitude_t, altitude_terrain) }, \
bhepp 0:28183cc7963f 31 { "bottom_clearance", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_altitude_t, bottom_clearance) }, \
bhepp 0:28183cc7963f 32 } \
bhepp 0:28183cc7963f 33 }
bhepp 0:28183cc7963f 34
bhepp 0:28183cc7963f 35
bhepp 0:28183cc7963f 36 /**
bhepp 0:28183cc7963f 37 * @brief Pack a altitude message
bhepp 0:28183cc7963f 38 * @param system_id ID of this system
bhepp 0:28183cc7963f 39 * @param component_id ID of this component (e.g. 200 for IMU)
bhepp 0:28183cc7963f 40 * @param msg The MAVLink message to compress the data into
bhepp 0:28183cc7963f 41 *
bhepp 0:28183cc7963f 42 * @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
bhepp 0:28183cc7963f 43 * @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude.
bhepp 0:28183cc7963f 44 * @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
bhepp 0:28183cc7963f 45 * @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position.
bhepp 0:28183cc7963f 46 * @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
bhepp 0:28183cc7963f 47 * @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.
bhepp 0:28183cc7963f 48 * @return length of the message in bytes (excluding serial stream start sign)
bhepp 0:28183cc7963f 49 */
bhepp 0:28183cc7963f 50 static inline uint16_t mavlink_msg_altitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
bhepp 0:28183cc7963f 51 float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance)
bhepp 0:28183cc7963f 52 {
bhepp 0:28183cc7963f 53 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
bhepp 0:28183cc7963f 54 char buf[MAVLINK_MSG_ID_ALTITUDE_LEN];
bhepp 0:28183cc7963f 55 _mav_put_float(buf, 0, altitude_monotonic);
bhepp 0:28183cc7963f 56 _mav_put_float(buf, 4, altitude_amsl);
bhepp 0:28183cc7963f 57 _mav_put_float(buf, 8, altitude_local);
bhepp 0:28183cc7963f 58 _mav_put_float(buf, 12, altitude_relative);
bhepp 0:28183cc7963f 59 _mav_put_float(buf, 16, altitude_terrain);
bhepp 0:28183cc7963f 60 _mav_put_float(buf, 20, bottom_clearance);
bhepp 0:28183cc7963f 61
bhepp 0:28183cc7963f 62 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDE_LEN);
bhepp 0:28183cc7963f 63 #else
bhepp 0:28183cc7963f 64 mavlink_altitude_t packet;
bhepp 0:28183cc7963f 65 packet.altitude_monotonic = altitude_monotonic;
bhepp 0:28183cc7963f 66 packet.altitude_amsl = altitude_amsl;
bhepp 0:28183cc7963f 67 packet.altitude_local = altitude_local;
bhepp 0:28183cc7963f 68 packet.altitude_relative = altitude_relative;
bhepp 0:28183cc7963f 69 packet.altitude_terrain = altitude_terrain;
bhepp 0:28183cc7963f 70 packet.bottom_clearance = bottom_clearance;
bhepp 0:28183cc7963f 71
bhepp 0:28183cc7963f 72 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDE_LEN);
bhepp 0:28183cc7963f 73 #endif
bhepp 0:28183cc7963f 74
bhepp 0:28183cc7963f 75 msg->msgid = MAVLINK_MSG_ID_ALTITUDE;
bhepp 0:28183cc7963f 76 #if MAVLINK_CRC_EXTRA
bhepp 0:28183cc7963f 77 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
bhepp 0:28183cc7963f 78 #else
bhepp 0:28183cc7963f 79 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ALTITUDE_LEN);
bhepp 0:28183cc7963f 80 #endif
bhepp 0:28183cc7963f 81 }
bhepp 0:28183cc7963f 82
bhepp 0:28183cc7963f 83 /**
bhepp 0:28183cc7963f 84 * @brief Pack a altitude message on a channel
bhepp 0:28183cc7963f 85 * @param system_id ID of this system
bhepp 0:28183cc7963f 86 * @param component_id ID of this component (e.g. 200 for IMU)
bhepp 0:28183cc7963f 87 * @param chan The MAVLink channel this message will be sent over
bhepp 0:28183cc7963f 88 * @param msg The MAVLink message to compress the data into
bhepp 0:28183cc7963f 89 * @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
bhepp 0:28183cc7963f 90 * @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude.
bhepp 0:28183cc7963f 91 * @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
bhepp 0:28183cc7963f 92 * @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position.
bhepp 0:28183cc7963f 93 * @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
bhepp 0:28183cc7963f 94 * @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.
bhepp 0:28183cc7963f 95 * @return length of the message in bytes (excluding serial stream start sign)
bhepp 0:28183cc7963f 96 */
bhepp 0:28183cc7963f 97 static inline uint16_t mavlink_msg_altitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
bhepp 0:28183cc7963f 98 mavlink_message_t* msg,
bhepp 0:28183cc7963f 99 float altitude_monotonic,float altitude_amsl,float altitude_local,float altitude_relative,float altitude_terrain,float bottom_clearance)
bhepp 0:28183cc7963f 100 {
bhepp 0:28183cc7963f 101 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
bhepp 0:28183cc7963f 102 char buf[MAVLINK_MSG_ID_ALTITUDE_LEN];
bhepp 0:28183cc7963f 103 _mav_put_float(buf, 0, altitude_monotonic);
bhepp 0:28183cc7963f 104 _mav_put_float(buf, 4, altitude_amsl);
bhepp 0:28183cc7963f 105 _mav_put_float(buf, 8, altitude_local);
bhepp 0:28183cc7963f 106 _mav_put_float(buf, 12, altitude_relative);
bhepp 0:28183cc7963f 107 _mav_put_float(buf, 16, altitude_terrain);
bhepp 0:28183cc7963f 108 _mav_put_float(buf, 20, bottom_clearance);
bhepp 0:28183cc7963f 109
bhepp 0:28183cc7963f 110 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDE_LEN);
bhepp 0:28183cc7963f 111 #else
bhepp 0:28183cc7963f 112 mavlink_altitude_t packet;
bhepp 0:28183cc7963f 113 packet.altitude_monotonic = altitude_monotonic;
bhepp 0:28183cc7963f 114 packet.altitude_amsl = altitude_amsl;
bhepp 0:28183cc7963f 115 packet.altitude_local = altitude_local;
bhepp 0:28183cc7963f 116 packet.altitude_relative = altitude_relative;
bhepp 0:28183cc7963f 117 packet.altitude_terrain = altitude_terrain;
bhepp 0:28183cc7963f 118 packet.bottom_clearance = bottom_clearance;
bhepp 0:28183cc7963f 119
bhepp 0:28183cc7963f 120 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDE_LEN);
bhepp 0:28183cc7963f 121 #endif
bhepp 0:28183cc7963f 122
bhepp 0:28183cc7963f 123 msg->msgid = MAVLINK_MSG_ID_ALTITUDE;
bhepp 0:28183cc7963f 124 #if MAVLINK_CRC_EXTRA
bhepp 0:28183cc7963f 125 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
bhepp 0:28183cc7963f 126 #else
bhepp 0:28183cc7963f 127 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ALTITUDE_LEN);
bhepp 0:28183cc7963f 128 #endif
bhepp 0:28183cc7963f 129 }
bhepp 0:28183cc7963f 130
bhepp 0:28183cc7963f 131 /**
bhepp 0:28183cc7963f 132 * @brief Encode a altitude struct
bhepp 0:28183cc7963f 133 *
bhepp 0:28183cc7963f 134 * @param system_id ID of this system
bhepp 0:28183cc7963f 135 * @param component_id ID of this component (e.g. 200 for IMU)
bhepp 0:28183cc7963f 136 * @param msg The MAVLink message to compress the data into
bhepp 0:28183cc7963f 137 * @param altitude C-struct to read the message contents from
bhepp 0:28183cc7963f 138 */
bhepp 0:28183cc7963f 139 static inline uint16_t mavlink_msg_altitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_altitude_t* altitude)
bhepp 0:28183cc7963f 140 {
bhepp 0:28183cc7963f 141 return mavlink_msg_altitude_pack(system_id, component_id, msg, altitude->altitude_monotonic, altitude->altitude_amsl, altitude->altitude_local, altitude->altitude_relative, altitude->altitude_terrain, altitude->bottom_clearance);
bhepp 0:28183cc7963f 142 }
bhepp 0:28183cc7963f 143
bhepp 0:28183cc7963f 144 /**
bhepp 0:28183cc7963f 145 * @brief Encode a altitude struct on a channel
bhepp 0:28183cc7963f 146 *
bhepp 0:28183cc7963f 147 * @param system_id ID of this system
bhepp 0:28183cc7963f 148 * @param component_id ID of this component (e.g. 200 for IMU)
bhepp 0:28183cc7963f 149 * @param chan The MAVLink channel this message will be sent over
bhepp 0:28183cc7963f 150 * @param msg The MAVLink message to compress the data into
bhepp 0:28183cc7963f 151 * @param altitude C-struct to read the message contents from
bhepp 0:28183cc7963f 152 */
bhepp 0:28183cc7963f 153 static inline uint16_t mavlink_msg_altitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_altitude_t* altitude)
bhepp 0:28183cc7963f 154 {
bhepp 0:28183cc7963f 155 return mavlink_msg_altitude_pack_chan(system_id, component_id, chan, msg, altitude->altitude_monotonic, altitude->altitude_amsl, altitude->altitude_local, altitude->altitude_relative, altitude->altitude_terrain, altitude->bottom_clearance);
bhepp 0:28183cc7963f 156 }
bhepp 0:28183cc7963f 157
bhepp 0:28183cc7963f 158 /**
bhepp 0:28183cc7963f 159 * @brief Send a altitude message
bhepp 0:28183cc7963f 160 * @param chan MAVLink channel to send the message
bhepp 0:28183cc7963f 161 *
bhepp 0:28183cc7963f 162 * @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
bhepp 0:28183cc7963f 163 * @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude.
bhepp 0:28183cc7963f 164 * @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
bhepp 0:28183cc7963f 165 * @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position.
bhepp 0:28183cc7963f 166 * @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
bhepp 0:28183cc7963f 167 * @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.
bhepp 0:28183cc7963f 168 */
bhepp 0:28183cc7963f 169 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
bhepp 0:28183cc7963f 170
bhepp 0:28183cc7963f 171 static inline void mavlink_msg_altitude_send(mavlink_channel_t chan, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance)
bhepp 0:28183cc7963f 172 {
bhepp 0:28183cc7963f 173 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
bhepp 0:28183cc7963f 174 char buf[MAVLINK_MSG_ID_ALTITUDE_LEN];
bhepp 0:28183cc7963f 175 _mav_put_float(buf, 0, altitude_monotonic);
bhepp 0:28183cc7963f 176 _mav_put_float(buf, 4, altitude_amsl);
bhepp 0:28183cc7963f 177 _mav_put_float(buf, 8, altitude_local);
bhepp 0:28183cc7963f 178 _mav_put_float(buf, 12, altitude_relative);
bhepp 0:28183cc7963f 179 _mav_put_float(buf, 16, altitude_terrain);
bhepp 0:28183cc7963f 180 _mav_put_float(buf, 20, bottom_clearance);
bhepp 0:28183cc7963f 181
bhepp 0:28183cc7963f 182 #if MAVLINK_CRC_EXTRA
bhepp 0:28183cc7963f 183 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
bhepp 0:28183cc7963f 184 #else
bhepp 0:28183cc7963f 185 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_LEN);
bhepp 0:28183cc7963f 186 #endif
bhepp 0:28183cc7963f 187 #else
bhepp 0:28183cc7963f 188 mavlink_altitude_t packet;
bhepp 0:28183cc7963f 189 packet.altitude_monotonic = altitude_monotonic;
bhepp 0:28183cc7963f 190 packet.altitude_amsl = altitude_amsl;
bhepp 0:28183cc7963f 191 packet.altitude_local = altitude_local;
bhepp 0:28183cc7963f 192 packet.altitude_relative = altitude_relative;
bhepp 0:28183cc7963f 193 packet.altitude_terrain = altitude_terrain;
bhepp 0:28183cc7963f 194 packet.bottom_clearance = bottom_clearance;
bhepp 0:28183cc7963f 195
bhepp 0:28183cc7963f 196 #if MAVLINK_CRC_EXTRA
bhepp 0:28183cc7963f 197 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
bhepp 0:28183cc7963f 198 #else
bhepp 0:28183cc7963f 199 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ALTITUDE_LEN);
bhepp 0:28183cc7963f 200 #endif
bhepp 0:28183cc7963f 201 #endif
bhepp 0:28183cc7963f 202 }
bhepp 0:28183cc7963f 203
bhepp 0:28183cc7963f 204 #if MAVLINK_MSG_ID_ALTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
bhepp 0:28183cc7963f 205 /*
bhepp 0:28183cc7963f 206 This varient of _send() can be used to save stack space by re-using
bhepp 0:28183cc7963f 207 memory from the receive buffer. The caller provides a
bhepp 0:28183cc7963f 208 mavlink_message_t which is the size of a full mavlink message. This
bhepp 0:28183cc7963f 209 is usually the receive buffer for the channel, and allows a reply to an
bhepp 0:28183cc7963f 210 incoming message with minimum stack space usage.
bhepp 0:28183cc7963f 211 */
bhepp 0:28183cc7963f 212 static inline void mavlink_msg_altitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance)
bhepp 0:28183cc7963f 213 {
bhepp 0:28183cc7963f 214 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
bhepp 0:28183cc7963f 215 char *buf = (char *)msgbuf;
bhepp 0:28183cc7963f 216 _mav_put_float(buf, 0, altitude_monotonic);
bhepp 0:28183cc7963f 217 _mav_put_float(buf, 4, altitude_amsl);
bhepp 0:28183cc7963f 218 _mav_put_float(buf, 8, altitude_local);
bhepp 0:28183cc7963f 219 _mav_put_float(buf, 12, altitude_relative);
bhepp 0:28183cc7963f 220 _mav_put_float(buf, 16, altitude_terrain);
bhepp 0:28183cc7963f 221 _mav_put_float(buf, 20, bottom_clearance);
bhepp 0:28183cc7963f 222
bhepp 0:28183cc7963f 223 #if MAVLINK_CRC_EXTRA
bhepp 0:28183cc7963f 224 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
bhepp 0:28183cc7963f 225 #else
bhepp 0:28183cc7963f 226 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_LEN);
bhepp 0:28183cc7963f 227 #endif
bhepp 0:28183cc7963f 228 #else
bhepp 0:28183cc7963f 229 mavlink_altitude_t *packet = (mavlink_altitude_t *)msgbuf;
bhepp 0:28183cc7963f 230 packet->altitude_monotonic = altitude_monotonic;
bhepp 0:28183cc7963f 231 packet->altitude_amsl = altitude_amsl;
bhepp 0:28183cc7963f 232 packet->altitude_local = altitude_local;
bhepp 0:28183cc7963f 233 packet->altitude_relative = altitude_relative;
bhepp 0:28183cc7963f 234 packet->altitude_terrain = altitude_terrain;
bhepp 0:28183cc7963f 235 packet->bottom_clearance = bottom_clearance;
bhepp 0:28183cc7963f 236
bhepp 0:28183cc7963f 237 #if MAVLINK_CRC_EXTRA
bhepp 0:28183cc7963f 238 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)packet, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
bhepp 0:28183cc7963f 239 #else
bhepp 0:28183cc7963f 240 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)packet, MAVLINK_MSG_ID_ALTITUDE_LEN);
bhepp 0:28183cc7963f 241 #endif
bhepp 0:28183cc7963f 242 #endif
bhepp 0:28183cc7963f 243 }
bhepp 0:28183cc7963f 244 #endif
bhepp 0:28183cc7963f 245
bhepp 0:28183cc7963f 246 #endif
bhepp 0:28183cc7963f 247
bhepp 0:28183cc7963f 248 // MESSAGE ALTITUDE UNPACKING
bhepp 0:28183cc7963f 249
bhepp 0:28183cc7963f 250
bhepp 0:28183cc7963f 251 /**
bhepp 0:28183cc7963f 252 * @brief Get field altitude_monotonic from altitude message
bhepp 0:28183cc7963f 253 *
bhepp 0:28183cc7963f 254 * @return This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
bhepp 0:28183cc7963f 255 */
bhepp 0:28183cc7963f 256 static inline float mavlink_msg_altitude_get_altitude_monotonic(const mavlink_message_t* msg)
bhepp 0:28183cc7963f 257 {
bhepp 0:28183cc7963f 258 return _MAV_RETURN_float(msg, 0);
bhepp 0:28183cc7963f 259 }
bhepp 0:28183cc7963f 260
bhepp 0:28183cc7963f 261 /**
bhepp 0:28183cc7963f 262 * @brief Get field altitude_amsl from altitude message
bhepp 0:28183cc7963f 263 *
bhepp 0:28183cc7963f 264 * @return This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude.
bhepp 0:28183cc7963f 265 */
bhepp 0:28183cc7963f 266 static inline float mavlink_msg_altitude_get_altitude_amsl(const mavlink_message_t* msg)
bhepp 0:28183cc7963f 267 {
bhepp 0:28183cc7963f 268 return _MAV_RETURN_float(msg, 4);
bhepp 0:28183cc7963f 269 }
bhepp 0:28183cc7963f 270
bhepp 0:28183cc7963f 271 /**
bhepp 0:28183cc7963f 272 * @brief Get field altitude_local from altitude message
bhepp 0:28183cc7963f 273 *
bhepp 0:28183cc7963f 274 * @return This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
bhepp 0:28183cc7963f 275 */
bhepp 0:28183cc7963f 276 static inline float mavlink_msg_altitude_get_altitude_local(const mavlink_message_t* msg)
bhepp 0:28183cc7963f 277 {
bhepp 0:28183cc7963f 278 return _MAV_RETURN_float(msg, 8);
bhepp 0:28183cc7963f 279 }
bhepp 0:28183cc7963f 280
bhepp 0:28183cc7963f 281 /**
bhepp 0:28183cc7963f 282 * @brief Get field altitude_relative from altitude message
bhepp 0:28183cc7963f 283 *
bhepp 0:28183cc7963f 284 * @return This is the altitude above the home position. It resets on each change of the current home position.
bhepp 0:28183cc7963f 285 */
bhepp 0:28183cc7963f 286 static inline float mavlink_msg_altitude_get_altitude_relative(const mavlink_message_t* msg)
bhepp 0:28183cc7963f 287 {
bhepp 0:28183cc7963f 288 return _MAV_RETURN_float(msg, 12);
bhepp 0:28183cc7963f 289 }
bhepp 0:28183cc7963f 290
bhepp 0:28183cc7963f 291 /**
bhepp 0:28183cc7963f 292 * @brief Get field altitude_terrain from altitude message
bhepp 0:28183cc7963f 293 *
bhepp 0:28183cc7963f 294 * @return This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
bhepp 0:28183cc7963f 295 */
bhepp 0:28183cc7963f 296 static inline float mavlink_msg_altitude_get_altitude_terrain(const mavlink_message_t* msg)
bhepp 0:28183cc7963f 297 {
bhepp 0:28183cc7963f 298 return _MAV_RETURN_float(msg, 16);
bhepp 0:28183cc7963f 299 }
bhepp 0:28183cc7963f 300
bhepp 0:28183cc7963f 301 /**
bhepp 0:28183cc7963f 302 * @brief Get field bottom_clearance from altitude message
bhepp 0:28183cc7963f 303 *
bhepp 0:28183cc7963f 304 * @return This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.
bhepp 0:28183cc7963f 305 */
bhepp 0:28183cc7963f 306 static inline float mavlink_msg_altitude_get_bottom_clearance(const mavlink_message_t* msg)
bhepp 0:28183cc7963f 307 {
bhepp 0:28183cc7963f 308 return _MAV_RETURN_float(msg, 20);
bhepp 0:28183cc7963f 309 }
bhepp 0:28183cc7963f 310
bhepp 0:28183cc7963f 311 /**
bhepp 0:28183cc7963f 312 * @brief Decode a altitude message into a struct
bhepp 0:28183cc7963f 313 *
bhepp 0:28183cc7963f 314 * @param msg The message to decode
bhepp 0:28183cc7963f 315 * @param altitude C-struct to decode the message contents into
bhepp 0:28183cc7963f 316 */
bhepp 0:28183cc7963f 317 static inline void mavlink_msg_altitude_decode(const mavlink_message_t* msg, mavlink_altitude_t* altitude)
bhepp 0:28183cc7963f 318 {
bhepp 0:28183cc7963f 319 #if MAVLINK_NEED_BYTE_SWAP
bhepp 0:28183cc7963f 320 altitude->altitude_monotonic = mavlink_msg_altitude_get_altitude_monotonic(msg);
bhepp 0:28183cc7963f 321 altitude->altitude_amsl = mavlink_msg_altitude_get_altitude_amsl(msg);
bhepp 0:28183cc7963f 322 altitude->altitude_local = mavlink_msg_altitude_get_altitude_local(msg);
bhepp 0:28183cc7963f 323 altitude->altitude_relative = mavlink_msg_altitude_get_altitude_relative(msg);
bhepp 0:28183cc7963f 324 altitude->altitude_terrain = mavlink_msg_altitude_get_altitude_terrain(msg);
bhepp 0:28183cc7963f 325 altitude->bottom_clearance = mavlink_msg_altitude_get_bottom_clearance(msg);
bhepp 0:28183cc7963f 326 #else
bhepp 0:28183cc7963f 327 memcpy(altitude, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ALTITUDE_LEN);
bhepp 0:28183cc7963f 328 #endif
bhepp 0:28183cc7963f 329 }