mavlink_msg_altitude.h
Go to the documentation of this file.
00001 // MESSAGE ALTITUDE PACKING
00002 
00003 #define MAVLINK_MSG_ID_ALTITUDE 141
00004 
00005 typedef struct __mavlink_altitude_t
00006 {
00007  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.*/
00008  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.*/
00009  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.*/
00010  float altitude_relative; /*< This is the altitude above the home position. It resets on each change of the current home position.*/
00011  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.*/
00012  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.*/
00013 } mavlink_altitude_t;
00014 
00015 #define MAVLINK_MSG_ID_ALTITUDE_LEN 24
00016 #define MAVLINK_MSG_ID_141_LEN 24
00017 
00018 #define MAVLINK_MSG_ID_ALTITUDE_CRC 148
00019 #define MAVLINK_MSG_ID_141_CRC 148
00020 
00021 
00022 
00023 #define MAVLINK_MESSAGE_INFO_ALTITUDE { \
00024         "ALTITUDE", \
00025         6, \
00026         {  { "altitude_monotonic", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_altitude_t, altitude_monotonic) }, \
00027          { "altitude_amsl", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_altitude_t, altitude_amsl) }, \
00028          { "altitude_local", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_altitude_t, altitude_local) }, \
00029          { "altitude_relative", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_altitude_t, altitude_relative) }, \
00030          { "altitude_terrain", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_altitude_t, altitude_terrain) }, \
00031          { "bottom_clearance", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_altitude_t, bottom_clearance) }, \
00032          } \
00033 }
00034 
00035 
00050 static inline uint16_t mavlink_msg_altitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00051                                                        float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance)
00052 {
00053 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00054         char buf[MAVLINK_MSG_ID_ALTITUDE_LEN];
00055         _mav_put_float(buf, 0, altitude_monotonic);
00056         _mav_put_float(buf, 4, altitude_amsl);
00057         _mav_put_float(buf, 8, altitude_local);
00058         _mav_put_float(buf, 12, altitude_relative);
00059         _mav_put_float(buf, 16, altitude_terrain);
00060         _mav_put_float(buf, 20, bottom_clearance);
00061 
00062         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDE_LEN);
00063 #else
00064         mavlink_altitude_t packet;
00065         packet.altitude_monotonic = altitude_monotonic;
00066         packet.altitude_amsl = altitude_amsl;
00067         packet.altitude_local = altitude_local;
00068         packet.altitude_relative = altitude_relative;
00069         packet.altitude_terrain = altitude_terrain;
00070         packet.bottom_clearance = bottom_clearance;
00071 
00072         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDE_LEN);
00073 #endif
00074 
00075         msg->msgid = MAVLINK_MSG_ID_ALTITUDE;
00076 #if MAVLINK_CRC_EXTRA
00077     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
00078 #else
00079     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ALTITUDE_LEN);
00080 #endif
00081 }
00082 
00097 static inline uint16_t mavlink_msg_altitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00098                                                            mavlink_message_t* msg,
00099                                                            float altitude_monotonic,float altitude_amsl,float altitude_local,float altitude_relative,float altitude_terrain,float bottom_clearance)
00100 {
00101 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00102         char buf[MAVLINK_MSG_ID_ALTITUDE_LEN];
00103         _mav_put_float(buf, 0, altitude_monotonic);
00104         _mav_put_float(buf, 4, altitude_amsl);
00105         _mav_put_float(buf, 8, altitude_local);
00106         _mav_put_float(buf, 12, altitude_relative);
00107         _mav_put_float(buf, 16, altitude_terrain);
00108         _mav_put_float(buf, 20, bottom_clearance);
00109 
00110         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDE_LEN);
00111 #else
00112         mavlink_altitude_t packet;
00113         packet.altitude_monotonic = altitude_monotonic;
00114         packet.altitude_amsl = altitude_amsl;
00115         packet.altitude_local = altitude_local;
00116         packet.altitude_relative = altitude_relative;
00117         packet.altitude_terrain = altitude_terrain;
00118         packet.bottom_clearance = bottom_clearance;
00119 
00120         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDE_LEN);
00121 #endif
00122 
00123         msg->msgid = MAVLINK_MSG_ID_ALTITUDE;
00124 #if MAVLINK_CRC_EXTRA
00125     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
00126 #else
00127     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ALTITUDE_LEN);
00128 #endif
00129 }
00130 
00139 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)
00140 {
00141         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);
00142 }
00143 
00153 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)
00154 {
00155         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);
00156 }
00157 
00169 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00170 
00171 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)
00172 {
00173 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00174         char buf[MAVLINK_MSG_ID_ALTITUDE_LEN];
00175         _mav_put_float(buf, 0, altitude_monotonic);
00176         _mav_put_float(buf, 4, altitude_amsl);
00177         _mav_put_float(buf, 8, altitude_local);
00178         _mav_put_float(buf, 12, altitude_relative);
00179         _mav_put_float(buf, 16, altitude_terrain);
00180         _mav_put_float(buf, 20, bottom_clearance);
00181 
00182 #if MAVLINK_CRC_EXTRA
00183     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
00184 #else
00185     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_LEN);
00186 #endif
00187 #else
00188         mavlink_altitude_t packet;
00189         packet.altitude_monotonic = altitude_monotonic;
00190         packet.altitude_amsl = altitude_amsl;
00191         packet.altitude_local = altitude_local;
00192         packet.altitude_relative = altitude_relative;
00193         packet.altitude_terrain = altitude_terrain;
00194         packet.bottom_clearance = bottom_clearance;
00195 
00196 #if MAVLINK_CRC_EXTRA
00197     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
00198 #else
00199     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ALTITUDE_LEN);
00200 #endif
00201 #endif
00202 }
00203 
00204 #if MAVLINK_MSG_ID_ALTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00205 /*
00206   This varient of _send() can be used to save stack space by re-using
00207   memory from the receive buffer.  The caller provides a
00208   mavlink_message_t which is the size of a full mavlink message. This
00209   is usually the receive buffer for the channel, and allows a reply to an
00210   incoming message with minimum stack space usage.
00211  */
00212 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)
00213 {
00214 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00215         char *buf = (char *)msgbuf;
00216         _mav_put_float(buf, 0, altitude_monotonic);
00217         _mav_put_float(buf, 4, altitude_amsl);
00218         _mav_put_float(buf, 8, altitude_local);
00219         _mav_put_float(buf, 12, altitude_relative);
00220         _mav_put_float(buf, 16, altitude_terrain);
00221         _mav_put_float(buf, 20, bottom_clearance);
00222 
00223 #if MAVLINK_CRC_EXTRA
00224     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
00225 #else
00226     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_LEN);
00227 #endif
00228 #else
00229         mavlink_altitude_t *packet = (mavlink_altitude_t *)msgbuf;
00230         packet->altitude_monotonic = altitude_monotonic;
00231         packet->altitude_amsl = altitude_amsl;
00232         packet->altitude_local = altitude_local;
00233         packet->altitude_relative = altitude_relative;
00234         packet->altitude_terrain = altitude_terrain;
00235         packet->bottom_clearance = bottom_clearance;
00236 
00237 #if MAVLINK_CRC_EXTRA
00238     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)packet, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
00239 #else
00240     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)packet, MAVLINK_MSG_ID_ALTITUDE_LEN);
00241 #endif
00242 #endif
00243 }
00244 #endif
00245 
00246 #endif
00247 
00248 // MESSAGE ALTITUDE UNPACKING
00249 
00250 
00256 static inline float mavlink_msg_altitude_get_altitude_monotonic(const mavlink_message_t* msg)
00257 {
00258         return _MAV_RETURN_float(msg,  0);
00259 }
00260 
00266 static inline float mavlink_msg_altitude_get_altitude_amsl(const mavlink_message_t* msg)
00267 {
00268         return _MAV_RETURN_float(msg,  4);
00269 }
00270 
00276 static inline float mavlink_msg_altitude_get_altitude_local(const mavlink_message_t* msg)
00277 {
00278         return _MAV_RETURN_float(msg,  8);
00279 }
00280 
00286 static inline float mavlink_msg_altitude_get_altitude_relative(const mavlink_message_t* msg)
00287 {
00288         return _MAV_RETURN_float(msg,  12);
00289 }
00290 
00296 static inline float mavlink_msg_altitude_get_altitude_terrain(const mavlink_message_t* msg)
00297 {
00298         return _MAV_RETURN_float(msg,  16);
00299 }
00300 
00306 static inline float mavlink_msg_altitude_get_bottom_clearance(const mavlink_message_t* msg)
00307 {
00308         return _MAV_RETURN_float(msg,  20);
00309 }
00310 
00317 static inline void mavlink_msg_altitude_decode(const mavlink_message_t* msg, mavlink_altitude_t* altitude)
00318 {
00319 #if MAVLINK_NEED_BYTE_SWAP
00320         altitude->altitude_monotonic = mavlink_msg_altitude_get_altitude_monotonic(msg);
00321         altitude->altitude_amsl = mavlink_msg_altitude_get_altitude_amsl(msg);
00322         altitude->altitude_local = mavlink_msg_altitude_get_altitude_local(msg);
00323         altitude->altitude_relative = mavlink_msg_altitude_get_altitude_relative(msg);
00324         altitude->altitude_terrain = mavlink_msg_altitude_get_altitude_terrain(msg);
00325         altitude->bottom_clearance = mavlink_msg_altitude_get_bottom_clearance(msg);
00326 #else
00327         memcpy(altitude, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ALTITUDE_LEN);
00328 #endif
00329 }


dji_sdk_dji2mav
Author(s):
autogenerated on Thu Jun 6 2019 17:55:34