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... | |
#define MAVLINK_MESSAGE_INFO_ADSB_VEHICLE |
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 struct __mavlink_adsb_vehicle_t mavlink_adsb_vehicle_t |
|
inlinestatic |
Decode a adsb_vehicle message into a struct.
msg | The message to decode |
adsb_vehicle | C-struct to decode the message contents into |
Definition at line 470 of file mavlink_msg_adsb_vehicle.h.
|
inlinestatic |
Encode a adsb_vehicle struct.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
adsb_vehicle | C-struct to read the message contents from |
Definition at line 191 of file mavlink_msg_adsb_vehicle.h.
|
inlinestatic |
Encode a adsb_vehicle struct on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
adsb_vehicle | C-struct to read the message contents from |
Definition at line 205 of file mavlink_msg_adsb_vehicle.h.
|
inlinestatic |
Get field altitude from adsb_vehicle message.
Definition at line 379 of file mavlink_msg_adsb_vehicle.h.
|
inlinestatic |
Get field altitude_type from adsb_vehicle message.
Definition at line 369 of file mavlink_msg_adsb_vehicle.h.
|
inlinestatic |
Get field callsign from adsb_vehicle message.
Definition at line 419 of file mavlink_msg_adsb_vehicle.h.
|
inlinestatic |
Get field emitter_type from adsb_vehicle message.
Definition at line 429 of file mavlink_msg_adsb_vehicle.h.
|
inlinestatic |
Get field flags from adsb_vehicle message.
Definition at line 449 of file mavlink_msg_adsb_vehicle.h.
|
inlinestatic |
Get field heading from adsb_vehicle message.
Definition at line 389 of file mavlink_msg_adsb_vehicle.h.
|
inlinestatic |
Get field hor_velocity from adsb_vehicle message.
Definition at line 399 of file mavlink_msg_adsb_vehicle.h.
|
inlinestatic |
Send a adsb_vehicle message.
chan | MAVLink channel to send the message |
ICAO_address | ICAO address |
lat | Latitude, expressed as degrees * 1E7 |
lon | Longitude, expressed as degrees * 1E7 |
altitude_type | Type from ADSB_ALTITUDE_TYPE enum |
altitude | Altitude(ASL) in millimeters |
heading | Course over ground in centidegrees |
hor_velocity | The horizontal velocity in centimeters/second |
ver_velocity | The vertical velocity in centimeters/second, positive is up |
callsign | The callsign, 8+null |
emitter_type | Type from ADSB_EMITTER_TYPE enum |
tslc | Time since last communication in seconds |
flags | Flags to indicate various statuses including valid data fields |
squawk | Squawk code Get field ICAO_address from adsb_vehicle message |
Definition at line 339 of file mavlink_msg_adsb_vehicle.h.
|
inlinestatic |
Get field lat from adsb_vehicle message.
Definition at line 349 of file mavlink_msg_adsb_vehicle.h.
|
inlinestatic |
Get field lon from adsb_vehicle message.
Definition at line 359 of file mavlink_msg_adsb_vehicle.h.
|
inlinestatic |
Get field squawk from adsb_vehicle message.
Definition at line 459 of file mavlink_msg_adsb_vehicle.h.
|
inlinestatic |
Get field tslc from adsb_vehicle message.
Definition at line 439 of file mavlink_msg_adsb_vehicle.h.
|
inlinestatic |
Get field ver_velocity from adsb_vehicle message.
Definition at line 409 of file mavlink_msg_adsb_vehicle.h.
|
inlinestatic |
Pack a adsb_vehicle message.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
ICAO_address | ICAO address |
lat | Latitude, expressed as degrees * 1E7 |
lon | Longitude, expressed as degrees * 1E7 |
altitude_type | Type from ADSB_ALTITUDE_TYPE enum |
altitude | Altitude(ASL) in millimeters |
heading | Course over ground in centidegrees |
hor_velocity | The horizontal velocity in centimeters/second |
ver_velocity | The vertical velocity in centimeters/second, positive is up |
callsign | The callsign, 8+null |
emitter_type | Type from ADSB_EMITTER_TYPE enum |
tslc | Time since last communication in seconds |
flags | Flags to indicate various statuses including valid data fields |
squawk | Squawk code |
Definition at line 71 of file mavlink_msg_adsb_vehicle.h.
|
inlinestatic |
Pack a adsb_vehicle message on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
ICAO_address | ICAO address |
lat | Latitude, expressed as degrees * 1E7 |
lon | Longitude, expressed as degrees * 1E7 |
altitude_type | Type from ADSB_ALTITUDE_TYPE enum |
altitude | Altitude(ASL) in millimeters |
heading | Course over ground in centidegrees |
hor_velocity | The horizontal velocity in centimeters/second |
ver_velocity | The vertical velocity in centimeters/second, positive is up |
callsign | The callsign, 8+null |
emitter_type | Type from ADSB_EMITTER_TYPE enum |
tslc | Time since last communication in seconds |
flags | Flags to indicate various statuses including valid data fields |
squawk | Squawk code |
Definition at line 137 of file mavlink_msg_adsb_vehicle.h.