mavlink_msg_altitude.h
Go to the documentation of this file.
1 // MESSAGE ALTITUDE PACKING
2 
3 #define MAVLINK_MSG_ID_ALTITUDE 141
4 
5 typedef struct __mavlink_altitude_t
6 {
7  uint64_t time_usec; /*< Timestamp (milliseconds since system boot)*/
8  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.*/
9  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.*/
10  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.*/
11  float altitude_relative; /*< This is the altitude above the home position. It resets on each change of the current home position.*/
12  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.*/
13  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.*/
15 
16 #define MAVLINK_MSG_ID_ALTITUDE_LEN 32
17 #define MAVLINK_MSG_ID_141_LEN 32
18 
19 #define MAVLINK_MSG_ID_ALTITUDE_CRC 47
20 #define MAVLINK_MSG_ID_141_CRC 47
21 
22 
23 
24 #define MAVLINK_MESSAGE_INFO_ALTITUDE { \
25  "ALTITUDE", \
26  7, \
27  { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_altitude_t, time_usec) }, \
28  { "altitude_monotonic", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_altitude_t, altitude_monotonic) }, \
29  { "altitude_amsl", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_altitude_t, altitude_amsl) }, \
30  { "altitude_local", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_altitude_t, altitude_local) }, \
31  { "altitude_relative", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_altitude_t, altitude_relative) }, \
32  { "altitude_terrain", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_altitude_t, altitude_terrain) }, \
33  { "bottom_clearance", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_altitude_t, bottom_clearance) }, \
34  } \
35 }
36 
37 
53 static inline uint16_t mavlink_msg_altitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
55 {
56 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
58  _mav_put_uint64_t(buf, 0, time_usec);
59  _mav_put_float(buf, 8, altitude_monotonic);
60  _mav_put_float(buf, 12, altitude_amsl);
61  _mav_put_float(buf, 16, altitude_local);
62  _mav_put_float(buf, 20, altitude_relative);
63  _mav_put_float(buf, 24, altitude_terrain);
64  _mav_put_float(buf, 28, bottom_clearance);
65 
67 #else
68  mavlink_altitude_t packet;
69  packet.time_usec = time_usec;
76 
78 #endif
79 
80  msg->msgid = MAVLINK_MSG_ID_ALTITUDE;
81 #if MAVLINK_CRC_EXTRA
83 #else
84  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ALTITUDE_LEN);
85 #endif
86 }
87 
103 static inline uint16_t mavlink_msg_altitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
104  mavlink_message_t* msg,
106 {
107 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
108  char buf[MAVLINK_MSG_ID_ALTITUDE_LEN];
109  _mav_put_uint64_t(buf, 0, time_usec);
110  _mav_put_float(buf, 8, altitude_monotonic);
111  _mav_put_float(buf, 12, altitude_amsl);
112  _mav_put_float(buf, 16, altitude_local);
113  _mav_put_float(buf, 20, altitude_relative);
114  _mav_put_float(buf, 24, altitude_terrain);
115  _mav_put_float(buf, 28, bottom_clearance);
116 
118 #else
119  mavlink_altitude_t packet;
120  packet.time_usec = time_usec;
122  packet.altitude_amsl = altitude_amsl;
127 
129 #endif
130 
131  msg->msgid = MAVLINK_MSG_ID_ALTITUDE;
132 #if MAVLINK_CRC_EXTRA
134 #else
135  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ALTITUDE_LEN);
136 #endif
137 }
138 
147 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)
148 {
149  return mavlink_msg_altitude_pack(system_id, component_id, msg, altitude->time_usec, altitude->altitude_monotonic, altitude->altitude_amsl, altitude->altitude_local, altitude->altitude_relative, altitude->altitude_terrain, altitude->bottom_clearance);
150 }
151 
161 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)
162 {
163  return mavlink_msg_altitude_pack_chan(system_id, component_id, chan, msg, altitude->time_usec, altitude->altitude_monotonic, altitude->altitude_amsl, altitude->altitude_local, altitude->altitude_relative, altitude->altitude_terrain, altitude->bottom_clearance);
164 }
165 
178 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
179 
180 static inline void mavlink_msg_altitude_send(mavlink_channel_t chan, uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance)
181 {
182 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
183  char buf[MAVLINK_MSG_ID_ALTITUDE_LEN];
184  _mav_put_uint64_t(buf, 0, time_usec);
186  _mav_put_float(buf, 12, altitude_amsl);
187  _mav_put_float(buf, 16, altitude_local);
190  _mav_put_float(buf, 28, bottom_clearance);
191 
192 #if MAVLINK_CRC_EXTRA
193  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
194 #else
195  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_LEN);
196 #endif
197 #else
198  mavlink_altitude_t packet;
199  packet.time_usec = time_usec;
201  packet.altitude_amsl = altitude_amsl;
206 
207 #if MAVLINK_CRC_EXTRA
208  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
209 #else
210  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ALTITUDE_LEN);
211 #endif
212 #endif
213 }
214 
215 #if MAVLINK_MSG_ID_ALTITUDE_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_altitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance)
224 {
225 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
226  char *buf = (char *)msgbuf;
227  _mav_put_uint64_t(buf, 0, time_usec);
229  _mav_put_float(buf, 12, altitude_amsl);
230  _mav_put_float(buf, 16, altitude_local);
233  _mav_put_float(buf, 28, bottom_clearance);
234 
235 #if MAVLINK_CRC_EXTRA
236  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
237 #else
238  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_LEN);
239 #endif
240 #else
241  mavlink_altitude_t *packet = (mavlink_altitude_t *)msgbuf;
242  packet->time_usec = time_usec;
244  packet->altitude_amsl = altitude_amsl;
245  packet->altitude_local = altitude_local;
249 
250 #if MAVLINK_CRC_EXTRA
251  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)packet, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
252 #else
253  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)packet, MAVLINK_MSG_ID_ALTITUDE_LEN);
254 #endif
255 #endif
256 }
257 #endif
258 
259 #endif
260 
261 // MESSAGE ALTITUDE UNPACKING
262 
263 
269 static inline uint64_t mavlink_msg_altitude_get_time_usec(const mavlink_message_t* msg)
270 {
271  return _MAV_RETURN_uint64_t(msg, 0);
272 }
273 
279 static inline float mavlink_msg_altitude_get_altitude_monotonic(const mavlink_message_t* msg)
280 {
281  return _MAV_RETURN_float(msg, 8);
282 }
283 
289 static inline float mavlink_msg_altitude_get_altitude_amsl(const mavlink_message_t* msg)
290 {
291  return _MAV_RETURN_float(msg, 12);
292 }
293 
299 static inline float mavlink_msg_altitude_get_altitude_local(const mavlink_message_t* msg)
300 {
301  return _MAV_RETURN_float(msg, 16);
302 }
303 
309 static inline float mavlink_msg_altitude_get_altitude_relative(const mavlink_message_t* msg)
310 {
311  return _MAV_RETURN_float(msg, 20);
312 }
313 
319 static inline float mavlink_msg_altitude_get_altitude_terrain(const mavlink_message_t* msg)
320 {
321  return _MAV_RETURN_float(msg, 24);
322 }
323 
329 static inline float mavlink_msg_altitude_get_bottom_clearance(const mavlink_message_t* msg)
330 {
331  return _MAV_RETURN_float(msg, 28);
332 }
333 
340 static inline void mavlink_msg_altitude_decode(const mavlink_message_t* msg, mavlink_altitude_t* altitude)
341 {
342 #if MAVLINK_NEED_BYTE_SWAP
350 #else
351  memcpy(altitude, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ALTITUDE_LEN);
352 #endif
353 }
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:151
float altitude
Definition: ms4525.c:41
#define _mav_put_uint64_t(buf, wire_offset, b)
Definition: protocol.h:149


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:46