Classes | Macros | Typedefs | Functions
mavlink_msg_adsb_vehicle.h File Reference
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  __mavlink_adsb_vehicle_t
 

Macros

#define MAVLINK_MESSAGE_INFO_ADSB_VEHICLE
 
#define MAVLINK_MSG_ADSB_VEHICLE_FIELD_CALLSIGN_LEN   9
 
#define MAVLINK_MSG_ID_246_CRC   184
 
#define MAVLINK_MSG_ID_246_LEN   38
 
#define MAVLINK_MSG_ID_ADSB_VEHICLE   246
 
#define MAVLINK_MSG_ID_ADSB_VEHICLE_CRC   184
 
#define MAVLINK_MSG_ID_ADSB_VEHICLE_LEN   38
 

Typedefs

typedef struct __mavlink_adsb_vehicle_t mavlink_adsb_vehicle_t
 

Functions

static void mavlink_msg_adsb_vehicle_decode (const mavlink_message_t *msg, mavlink_adsb_vehicle_t *adsb_vehicle)
 Decode a adsb_vehicle message into a struct. More...
 
static 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)
 Encode a adsb_vehicle struct. More...
 
static 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)
 Encode a adsb_vehicle struct on a channel. More...
 
static int32_t mavlink_msg_adsb_vehicle_get_altitude (const mavlink_message_t *msg)
 Get field altitude from adsb_vehicle message. More...
 
static uint8_t mavlink_msg_adsb_vehicle_get_altitude_type (const mavlink_message_t *msg)
 Get field altitude_type from adsb_vehicle message. More...
 
static uint16_t mavlink_msg_adsb_vehicle_get_callsign (const mavlink_message_t *msg, char *callsign)
 Get field callsign from adsb_vehicle message. More...
 
static uint8_t mavlink_msg_adsb_vehicle_get_emitter_type (const mavlink_message_t *msg)
 Get field emitter_type from adsb_vehicle message. More...
 
static uint16_t mavlink_msg_adsb_vehicle_get_flags (const mavlink_message_t *msg)
 Get field flags from adsb_vehicle message. More...
 
static uint16_t mavlink_msg_adsb_vehicle_get_heading (const mavlink_message_t *msg)
 Get field heading from adsb_vehicle message. More...
 
static uint16_t mavlink_msg_adsb_vehicle_get_hor_velocity (const mavlink_message_t *msg)
 Get field hor_velocity from adsb_vehicle message. More...
 
static uint32_t mavlink_msg_adsb_vehicle_get_ICAO_address (const mavlink_message_t *msg)
 Send a adsb_vehicle message. More...
 
static int32_t mavlink_msg_adsb_vehicle_get_lat (const mavlink_message_t *msg)
 Get field lat from adsb_vehicle message. More...
 
static int32_t mavlink_msg_adsb_vehicle_get_lon (const mavlink_message_t *msg)
 Get field lon from adsb_vehicle message. More...
 
static uint16_t mavlink_msg_adsb_vehicle_get_squawk (const mavlink_message_t *msg)
 Get field squawk from adsb_vehicle message. More...
 
static uint8_t mavlink_msg_adsb_vehicle_get_tslc (const mavlink_message_t *msg)
 Get field tslc from adsb_vehicle message. More...
 
static int16_t mavlink_msg_adsb_vehicle_get_ver_velocity (const mavlink_message_t *msg)
 Get field ver_velocity from adsb_vehicle message. More...
 
static uint16_t mavlink_msg_adsb_vehicle_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, 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)
 Pack a adsb_vehicle message. More...
 
static uint16_t mavlink_msg_adsb_vehicle_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, 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)
 Pack a adsb_vehicle message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_ADSB_VEHICLE
Value:
{ \
"ADSB_VEHICLE", \
13, \
{ { "ICAO_address", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_adsb_vehicle_t, ICAO_address) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_adsb_vehicle_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_adsb_vehicle_t, lon) }, \
{ "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_adsb_vehicle_t, altitude) }, \
{ "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_adsb_vehicle_t, heading) }, \
{ "hor_velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_adsb_vehicle_t, hor_velocity) }, \
{ "ver_velocity", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_adsb_vehicle_t, ver_velocity) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_adsb_vehicle_t, flags) }, \
{ "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_adsb_vehicle_t, squawk) }, \
{ "altitude_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_adsb_vehicle_t, altitude_type) }, \
{ "callsign", NULL, MAVLINK_TYPE_CHAR, 9, 27, offsetof(mavlink_adsb_vehicle_t, callsign) }, \
{ "emitter_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_adsb_vehicle_t, emitter_type) }, \
{ "tslc", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_adsb_vehicle_t, tslc) }, \
} \
}
float altitude
Definition: ms4525.c:41
#define NULL
Definition: usbd_def.h:50

Definition at line 30 of file mavlink_msg_adsb_vehicle.h.

#define MAVLINK_MSG_ADSB_VEHICLE_FIELD_CALLSIGN_LEN   9

Definition at line 28 of file mavlink_msg_adsb_vehicle.h.

#define MAVLINK_MSG_ID_246_CRC   184

Definition at line 26 of file mavlink_msg_adsb_vehicle.h.

#define MAVLINK_MSG_ID_246_LEN   38

Definition at line 23 of file mavlink_msg_adsb_vehicle.h.

#define MAVLINK_MSG_ID_ADSB_VEHICLE   246

Definition at line 3 of file mavlink_msg_adsb_vehicle.h.

#define MAVLINK_MSG_ID_ADSB_VEHICLE_CRC   184

Definition at line 25 of file mavlink_msg_adsb_vehicle.h.

#define MAVLINK_MSG_ID_ADSB_VEHICLE_LEN   38

Definition at line 22 of file mavlink_msg_adsb_vehicle.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_adsb_vehicle_decode ( const mavlink_message_t *  msg,
mavlink_adsb_vehicle_t adsb_vehicle 
)
inlinestatic

Decode a adsb_vehicle message into a struct.

Parameters
msgThe message to decode
adsb_vehicleC-struct to decode the message contents into

Definition at line 470 of file mavlink_msg_adsb_vehicle.h.

static 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 
)
inlinestatic

Encode a adsb_vehicle struct.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
adsb_vehicleC-struct to read the message contents from

Definition at line 191 of file mavlink_msg_adsb_vehicle.h.

static 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 
)
inlinestatic

Encode a adsb_vehicle struct on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
adsb_vehicleC-struct to read the message contents from

Definition at line 205 of file mavlink_msg_adsb_vehicle.h.

static int32_t mavlink_msg_adsb_vehicle_get_altitude ( const mavlink_message_t *  msg)
inlinestatic

Get field altitude from adsb_vehicle message.

Returns
Altitude(ASL) in millimeters

Definition at line 379 of file mavlink_msg_adsb_vehicle.h.

static uint8_t mavlink_msg_adsb_vehicle_get_altitude_type ( const mavlink_message_t *  msg)
inlinestatic

Get field altitude_type from adsb_vehicle message.

Returns
Type from ADSB_ALTITUDE_TYPE enum

Definition at line 369 of file mavlink_msg_adsb_vehicle.h.

static uint16_t mavlink_msg_adsb_vehicle_get_callsign ( const mavlink_message_t *  msg,
char *  callsign 
)
inlinestatic

Get field callsign from adsb_vehicle message.

Returns
The callsign, 8+null

Definition at line 419 of file mavlink_msg_adsb_vehicle.h.

static uint8_t mavlink_msg_adsb_vehicle_get_emitter_type ( const mavlink_message_t *  msg)
inlinestatic

Get field emitter_type from adsb_vehicle message.

Returns
Type from ADSB_EMITTER_TYPE enum

Definition at line 429 of file mavlink_msg_adsb_vehicle.h.

static uint16_t mavlink_msg_adsb_vehicle_get_flags ( const mavlink_message_t *  msg)
inlinestatic

Get field flags from adsb_vehicle message.

Returns
Flags to indicate various statuses including valid data fields

Definition at line 449 of file mavlink_msg_adsb_vehicle.h.

static uint16_t mavlink_msg_adsb_vehicle_get_heading ( const mavlink_message_t *  msg)
inlinestatic

Get field heading from adsb_vehicle message.

Returns
Course over ground in centidegrees

Definition at line 389 of file mavlink_msg_adsb_vehicle.h.

static uint16_t mavlink_msg_adsb_vehicle_get_hor_velocity ( const mavlink_message_t *  msg)
inlinestatic

Get field hor_velocity from adsb_vehicle message.

Returns
The horizontal velocity in centimeters/second

Definition at line 399 of file mavlink_msg_adsb_vehicle.h.

static uint32_t mavlink_msg_adsb_vehicle_get_ICAO_address ( const mavlink_message_t *  msg)
inlinestatic

Send a adsb_vehicle message.

Parameters
chanMAVLink channel to send the message
ICAO_addressICAO address
latLatitude, expressed as degrees * 1E7
lonLongitude, expressed as degrees * 1E7
altitude_typeType from ADSB_ALTITUDE_TYPE enum
altitudeAltitude(ASL) in millimeters
headingCourse over ground in centidegrees
hor_velocityThe horizontal velocity in centimeters/second
ver_velocityThe vertical velocity in centimeters/second, positive is up
callsignThe callsign, 8+null
emitter_typeType from ADSB_EMITTER_TYPE enum
tslcTime since last communication in seconds
flagsFlags to indicate various statuses including valid data fields
squawkSquawk code Get field ICAO_address from adsb_vehicle message
Returns
ICAO address

Definition at line 339 of file mavlink_msg_adsb_vehicle.h.

static int32_t mavlink_msg_adsb_vehicle_get_lat ( const mavlink_message_t *  msg)
inlinestatic

Get field lat from adsb_vehicle message.

Returns
Latitude, expressed as degrees * 1E7

Definition at line 349 of file mavlink_msg_adsb_vehicle.h.

static int32_t mavlink_msg_adsb_vehicle_get_lon ( const mavlink_message_t *  msg)
inlinestatic

Get field lon from adsb_vehicle message.

Returns
Longitude, expressed as degrees * 1E7

Definition at line 359 of file mavlink_msg_adsb_vehicle.h.

static uint16_t mavlink_msg_adsb_vehicle_get_squawk ( const mavlink_message_t *  msg)
inlinestatic

Get field squawk from adsb_vehicle message.

Returns
Squawk code

Definition at line 459 of file mavlink_msg_adsb_vehicle.h.

static uint8_t mavlink_msg_adsb_vehicle_get_tslc ( const mavlink_message_t *  msg)
inlinestatic

Get field tslc from adsb_vehicle message.

Returns
Time since last communication in seconds

Definition at line 439 of file mavlink_msg_adsb_vehicle.h.

static int16_t mavlink_msg_adsb_vehicle_get_ver_velocity ( const mavlink_message_t *  msg)
inlinestatic

Get field ver_velocity from adsb_vehicle message.

Returns
The vertical velocity in centimeters/second, positive is up

Definition at line 409 of file mavlink_msg_adsb_vehicle.h.

static uint16_t mavlink_msg_adsb_vehicle_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
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 
)
inlinestatic

Pack a adsb_vehicle message.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
ICAO_addressICAO address
latLatitude, expressed as degrees * 1E7
lonLongitude, expressed as degrees * 1E7
altitude_typeType from ADSB_ALTITUDE_TYPE enum
altitudeAltitude(ASL) in millimeters
headingCourse over ground in centidegrees
hor_velocityThe horizontal velocity in centimeters/second
ver_velocityThe vertical velocity in centimeters/second, positive is up
callsignThe callsign, 8+null
emitter_typeType from ADSB_EMITTER_TYPE enum
tslcTime since last communication in seconds
flagsFlags to indicate various statuses including valid data fields
squawkSquawk code
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 71 of file mavlink_msg_adsb_vehicle.h.

static uint16_t mavlink_msg_adsb_vehicle_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
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 
)
inlinestatic

Pack a adsb_vehicle message on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
ICAO_addressICAO address
latLatitude, expressed as degrees * 1E7
lonLongitude, expressed as degrees * 1E7
altitude_typeType from ADSB_ALTITUDE_TYPE enum
altitudeAltitude(ASL) in millimeters
headingCourse over ground in centidegrees
hor_velocityThe horizontal velocity in centimeters/second
ver_velocityThe vertical velocity in centimeters/second, positive is up
callsignThe callsign, 8+null
emitter_typeType from ADSB_EMITTER_TYPE enum
tslcTime since last communication in seconds
flagsFlags to indicate various statuses including valid data fields
squawkSquawk code
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 137 of file mavlink_msg_adsb_vehicle.h.



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