mavlink_msg_adsb_vehicle.h
Go to the documentation of this file.
1 // MESSAGE ADSB_VEHICLE PACKING
2 
3 #define MAVLINK_MSG_ID_ADSB_VEHICLE 246
4 
6 {
7  uint32_t ICAO_address; /*< ICAO address*/
8  int32_t lat; /*< Latitude, expressed as degrees * 1E7*/
9  int32_t lon; /*< Longitude, expressed as degrees * 1E7*/
10  int32_t altitude; /*< Altitude(ASL) in millimeters*/
11  uint16_t heading; /*< Course over ground in centidegrees*/
12  uint16_t hor_velocity; /*< The horizontal velocity in centimeters/second*/
13  int16_t ver_velocity; /*< The vertical velocity in centimeters/second, positive is up*/
14  uint16_t flags; /*< Flags to indicate various statuses including valid data fields*/
15  uint16_t squawk; /*< Squawk code*/
16  uint8_t altitude_type; /*< Type from ADSB_ALTITUDE_TYPE enum*/
17  char callsign[9]; /*< The callsign, 8+null*/
18  uint8_t emitter_type; /*< Type from ADSB_EMITTER_TYPE enum*/
19  uint8_t tslc; /*< Time since last communication in seconds*/
21 
22 #define MAVLINK_MSG_ID_ADSB_VEHICLE_LEN 38
23 #define MAVLINK_MSG_ID_246_LEN 38
24 
25 #define MAVLINK_MSG_ID_ADSB_VEHICLE_CRC 184
26 #define MAVLINK_MSG_ID_246_CRC 184
27 
28 #define MAVLINK_MSG_ADSB_VEHICLE_FIELD_CALLSIGN_LEN 9
29 
30 #define MAVLINK_MESSAGE_INFO_ADSB_VEHICLE { \
31  "ADSB_VEHICLE", \
32  13, \
33  { { "ICAO_address", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_adsb_vehicle_t, ICAO_address) }, \
34  { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_adsb_vehicle_t, lat) }, \
35  { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_adsb_vehicle_t, lon) }, \
36  { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_adsb_vehicle_t, altitude) }, \
37  { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_adsb_vehicle_t, heading) }, \
38  { "hor_velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_adsb_vehicle_t, hor_velocity) }, \
39  { "ver_velocity", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_adsb_vehicle_t, ver_velocity) }, \
40  { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_adsb_vehicle_t, flags) }, \
41  { "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_adsb_vehicle_t, squawk) }, \
42  { "altitude_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_adsb_vehicle_t, altitude_type) }, \
43  { "callsign", NULL, MAVLINK_TYPE_CHAR, 9, 27, offsetof(mavlink_adsb_vehicle_t, callsign) }, \
44  { "emitter_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_adsb_vehicle_t, emitter_type) }, \
45  { "tslc", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_adsb_vehicle_t, tslc) }, \
46  } \
47 }
48 
49 
71 static inline uint16_t mavlink_msg_adsb_vehicle_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
72  uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk)
73 {
74 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
76  _mav_put_uint32_t(buf, 0, ICAO_address);
77  _mav_put_int32_t(buf, 4, lat);
78  _mav_put_int32_t(buf, 8, lon);
79  _mav_put_int32_t(buf, 12, altitude);
80  _mav_put_uint16_t(buf, 16, heading);
81  _mav_put_uint16_t(buf, 18, hor_velocity);
82  _mav_put_int16_t(buf, 20, ver_velocity);
83  _mav_put_uint16_t(buf, 22, flags);
84  _mav_put_uint16_t(buf, 24, squawk);
85  _mav_put_uint8_t(buf, 26, altitude_type);
86  _mav_put_uint8_t(buf, 36, emitter_type);
87  _mav_put_uint8_t(buf, 37, tslc);
88  _mav_put_char_array(buf, 27, callsign, 9);
90 #else
92  packet.ICAO_address = ICAO_address;
93  packet.lat = lat;
94  packet.lon = lon;
95  packet.altitude = altitude;
96  packet.heading = heading;
97  packet.hor_velocity = hor_velocity;
98  packet.ver_velocity = ver_velocity;
99  packet.flags = flags;
100  packet.squawk = squawk;
101  packet.altitude_type = altitude_type;
102  packet.emitter_type = emitter_type;
103  packet.tslc = tslc;
104  mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9);
106 #endif
107 
108  msg->msgid = MAVLINK_MSG_ID_ADSB_VEHICLE;
109 #if MAVLINK_CRC_EXTRA
111 #else
112  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN);
113 #endif
114 }
115 
137 static inline uint16_t mavlink_msg_adsb_vehicle_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
138  mavlink_message_t* msg,
139  uint32_t ICAO_address,int32_t lat,int32_t lon,uint8_t altitude_type,int32_t altitude,uint16_t heading,uint16_t hor_velocity,int16_t ver_velocity,const char *callsign,uint8_t emitter_type,uint8_t tslc,uint16_t flags,uint16_t squawk)
140 {
141 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
143  _mav_put_uint32_t(buf, 0, ICAO_address);
144  _mav_put_int32_t(buf, 4, lat);
145  _mav_put_int32_t(buf, 8, lon);
146  _mav_put_int32_t(buf, 12, altitude);
147  _mav_put_uint16_t(buf, 16, heading);
148  _mav_put_uint16_t(buf, 18, hor_velocity);
149  _mav_put_int16_t(buf, 20, ver_velocity);
150  _mav_put_uint16_t(buf, 22, flags);
151  _mav_put_uint16_t(buf, 24, squawk);
152  _mav_put_uint8_t(buf, 26, altitude_type);
153  _mav_put_uint8_t(buf, 36, emitter_type);
154  _mav_put_uint8_t(buf, 37, tslc);
155  _mav_put_char_array(buf, 27, callsign, 9);
157 #else
158  mavlink_adsb_vehicle_t packet;
159  packet.ICAO_address = ICAO_address;
160  packet.lat = lat;
161  packet.lon = lon;
162  packet.altitude = altitude;
163  packet.heading = heading;
164  packet.hor_velocity = hor_velocity;
165  packet.ver_velocity = ver_velocity;
166  packet.flags = flags;
167  packet.squawk = squawk;
168  packet.altitude_type = altitude_type;
169  packet.emitter_type = emitter_type;
170  packet.tslc = tslc;
171  mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9);
173 #endif
174 
175  msg->msgid = MAVLINK_MSG_ID_ADSB_VEHICLE;
176 #if MAVLINK_CRC_EXTRA
178 #else
179  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN);
180 #endif
181 }
182 
191 static inline uint16_t mavlink_msg_adsb_vehicle_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_adsb_vehicle_t* adsb_vehicle)
192 {
193  return mavlink_msg_adsb_vehicle_pack(system_id, component_id, msg, adsb_vehicle->ICAO_address, adsb_vehicle->lat, adsb_vehicle->lon, adsb_vehicle->altitude_type, adsb_vehicle->altitude, adsb_vehicle->heading, adsb_vehicle->hor_velocity, adsb_vehicle->ver_velocity, adsb_vehicle->callsign, adsb_vehicle->emitter_type, adsb_vehicle->tslc, adsb_vehicle->flags, adsb_vehicle->squawk);
194 }
195 
205 static inline uint16_t mavlink_msg_adsb_vehicle_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_adsb_vehicle_t* adsb_vehicle)
206 {
207  return mavlink_msg_adsb_vehicle_pack_chan(system_id, component_id, chan, msg, adsb_vehicle->ICAO_address, adsb_vehicle->lat, adsb_vehicle->lon, adsb_vehicle->altitude_type, adsb_vehicle->altitude, adsb_vehicle->heading, adsb_vehicle->hor_velocity, adsb_vehicle->ver_velocity, adsb_vehicle->callsign, adsb_vehicle->emitter_type, adsb_vehicle->tslc, adsb_vehicle->flags, adsb_vehicle->squawk);
208 }
209 
228 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
229 
230 static inline void mavlink_msg_adsb_vehicle_send(mavlink_channel_t chan, uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk)
231 {
232 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
235  _mav_put_int32_t(buf, 4, lat);
236  _mav_put_int32_t(buf, 8, lon);
237  _mav_put_int32_t(buf, 12, altitude);
238  _mav_put_uint16_t(buf, 16, heading);
240  _mav_put_int16_t(buf, 20, ver_velocity);
241  _mav_put_uint16_t(buf, 22, flags);
242  _mav_put_uint16_t(buf, 24, squawk);
244  _mav_put_uint8_t(buf, 36, emitter_type);
245  _mav_put_uint8_t(buf, 37, tslc);
246  _mav_put_char_array(buf, 27, callsign, 9);
247 #if MAVLINK_CRC_EXTRA
249 #else
250  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN);
251 #endif
252 #else
253  mavlink_adsb_vehicle_t packet;
254  packet.ICAO_address = ICAO_address;
255  packet.lat = lat;
256  packet.lon = lon;
257  packet.altitude = altitude;
258  packet.heading = heading;
259  packet.hor_velocity = hor_velocity;
260  packet.ver_velocity = ver_velocity;
261  packet.flags = flags;
262  packet.squawk = squawk;
263  packet.altitude_type = altitude_type;
264  packet.emitter_type = emitter_type;
265  packet.tslc = tslc;
266  mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9);
267 #if MAVLINK_CRC_EXTRA
268  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)&packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC);
269 #else
270  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)&packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN);
271 #endif
272 #endif
273 }
274 
275 #if MAVLINK_MSG_ID_ADSB_VEHICLE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
276 /*
277  This varient of _send() can be used to save stack space by re-using
278  memory from the receive buffer. The caller provides a
279  mavlink_message_t which is the size of a full mavlink message. This
280  is usually the receive buffer for the channel, and allows a reply to an
281  incoming message with minimum stack space usage.
282  */
283 static inline void mavlink_msg_adsb_vehicle_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk)
284 {
285 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
286  char *buf = (char *)msgbuf;
288  _mav_put_int32_t(buf, 4, lat);
289  _mav_put_int32_t(buf, 8, lon);
290  _mav_put_int32_t(buf, 12, altitude);
291  _mav_put_uint16_t(buf, 16, heading);
293  _mav_put_int16_t(buf, 20, ver_velocity);
294  _mav_put_uint16_t(buf, 22, flags);
295  _mav_put_uint16_t(buf, 24, squawk);
297  _mav_put_uint8_t(buf, 36, emitter_type);
298  _mav_put_uint8_t(buf, 37, tslc);
299  _mav_put_char_array(buf, 27, callsign, 9);
300 #if MAVLINK_CRC_EXTRA
302 #else
303  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN);
304 #endif
305 #else
307  packet->ICAO_address = ICAO_address;
308  packet->lat = lat;
309  packet->lon = lon;
310  packet->altitude = altitude;
311  packet->heading = heading;
312  packet->hor_velocity = hor_velocity;
313  packet->ver_velocity = ver_velocity;
314  packet->flags = flags;
315  packet->squawk = squawk;
316  packet->altitude_type = altitude_type;
317  packet->emitter_type = emitter_type;
318  packet->tslc = tslc;
319  mav_array_memcpy(packet->callsign, callsign, sizeof(char)*9);
320 #if MAVLINK_CRC_EXTRA
321  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC);
322 #else
323  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN);
324 #endif
325 #endif
326 }
327 #endif
328 
329 #endif
330 
331 // MESSAGE ADSB_VEHICLE UNPACKING
332 
333 
339 static inline uint32_t mavlink_msg_adsb_vehicle_get_ICAO_address(const mavlink_message_t* msg)
340 {
341  return _MAV_RETURN_uint32_t(msg, 0);
342 }
343 
349 static inline int32_t mavlink_msg_adsb_vehicle_get_lat(const mavlink_message_t* msg)
350 {
351  return _MAV_RETURN_int32_t(msg, 4);
352 }
353 
359 static inline int32_t mavlink_msg_adsb_vehicle_get_lon(const mavlink_message_t* msg)
360 {
361  return _MAV_RETURN_int32_t(msg, 8);
362 }
363 
369 static inline uint8_t mavlink_msg_adsb_vehicle_get_altitude_type(const mavlink_message_t* msg)
370 {
371  return _MAV_RETURN_uint8_t(msg, 26);
372 }
373 
379 static inline int32_t mavlink_msg_adsb_vehicle_get_altitude(const mavlink_message_t* msg)
380 {
381  return _MAV_RETURN_int32_t(msg, 12);
382 }
383 
389 static inline uint16_t mavlink_msg_adsb_vehicle_get_heading(const mavlink_message_t* msg)
390 {
391  return _MAV_RETURN_uint16_t(msg, 16);
392 }
393 
399 static inline uint16_t mavlink_msg_adsb_vehicle_get_hor_velocity(const mavlink_message_t* msg)
400 {
401  return _MAV_RETURN_uint16_t(msg, 18);
402 }
403 
409 static inline int16_t mavlink_msg_adsb_vehicle_get_ver_velocity(const mavlink_message_t* msg)
410 {
411  return _MAV_RETURN_int16_t(msg, 20);
412 }
413 
419 static inline uint16_t mavlink_msg_adsb_vehicle_get_callsign(const mavlink_message_t* msg, char *callsign)
420 {
421  return _MAV_RETURN_char_array(msg, callsign, 9, 27);
422 }
423 
429 static inline uint8_t mavlink_msg_adsb_vehicle_get_emitter_type(const mavlink_message_t* msg)
430 {
431  return _MAV_RETURN_uint8_t(msg, 36);
432 }
433 
439 static inline uint8_t mavlink_msg_adsb_vehicle_get_tslc(const mavlink_message_t* msg)
440 {
441  return _MAV_RETURN_uint8_t(msg, 37);
442 }
443 
449 static inline uint16_t mavlink_msg_adsb_vehicle_get_flags(const mavlink_message_t* msg)
450 {
451  return _MAV_RETURN_uint16_t(msg, 22);
452 }
453 
459 static inline uint16_t mavlink_msg_adsb_vehicle_get_squawk(const mavlink_message_t* msg)
460 {
461  return _MAV_RETURN_uint16_t(msg, 24);
462 }
463 
470 static inline void mavlink_msg_adsb_vehicle_decode(const mavlink_message_t* msg, mavlink_adsb_vehicle_t* adsb_vehicle)
471 {
472 #if MAVLINK_NEED_BYTE_SWAP
474  adsb_vehicle->lat = mavlink_msg_adsb_vehicle_get_lat(msg);
475  adsb_vehicle->lon = mavlink_msg_adsb_vehicle_get_lon(msg);
476  adsb_vehicle->altitude = mavlink_msg_adsb_vehicle_get_altitude(msg);
477  adsb_vehicle->heading = mavlink_msg_adsb_vehicle_get_heading(msg);
480  adsb_vehicle->flags = mavlink_msg_adsb_vehicle_get_flags(msg);
481  adsb_vehicle->squawk = mavlink_msg_adsb_vehicle_get_squawk(msg);
485  adsb_vehicle->tslc = mavlink_msg_adsb_vehicle_get_tslc(msg);
486 #else
487  memcpy(adsb_vehicle, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ADSB_VEHICLE_LEN);
488 #endif
489 }
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:244
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:140
#define _mav_put_int32_t(buf, wire_offset, b)
Definition: protocol.h:148
static void mav_array_memcpy(void *dest, const void *src, size_t n)
Definition: protocol.h:176
static uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value, uint8_t array_length, uint8_t wire_offset)
Definition: protocol.h:288
static void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
Definition: protocol.h:188
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:145
#define _mav_put_int16_t(buf, wire_offset, b)
Definition: protocol.h:146
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:147


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