Go to the source code of this file.
Classes | |
struct | __mavlink_autopilot_version_t |
Macros | |
#define | MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION |
#define | MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_FLIGHT_CUSTOM_VERSION_LEN 8 |
#define | MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_MIDDLEWARE_CUSTOM_VERSION_LEN 8 |
#define | MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_OS_CUSTOM_VERSION_LEN 8 |
#define | MAVLINK_MSG_ID_148_CRC 178 |
#define | MAVLINK_MSG_ID_148_LEN 60 |
#define | MAVLINK_MSG_ID_AUTOPILOT_VERSION 148 |
#define | MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC 178 |
#define | MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN 60 |
Typedefs | |
typedef struct __mavlink_autopilot_version_t | mavlink_autopilot_version_t |
Functions | |
static void | mavlink_msg_autopilot_version_decode (const mavlink_message_t *msg, mavlink_autopilot_version_t *autopilot_version) |
Decode a autopilot_version message into a struct. More... | |
static uint16_t | mavlink_msg_autopilot_version_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_autopilot_version_t *autopilot_version) |
Encode a autopilot_version struct. More... | |
static uint16_t | mavlink_msg_autopilot_version_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_autopilot_version_t *autopilot_version) |
Encode a autopilot_version struct on a channel. More... | |
static uint32_t | mavlink_msg_autopilot_version_get_board_version (const mavlink_message_t *msg) |
Get field board_version from autopilot_version message. More... | |
static uint64_t | mavlink_msg_autopilot_version_get_capabilities (const mavlink_message_t *msg) |
Send a autopilot_version message. More... | |
static uint16_t | mavlink_msg_autopilot_version_get_flight_custom_version (const mavlink_message_t *msg, uint8_t *flight_custom_version) |
Get field flight_custom_version from autopilot_version message. More... | |
static uint32_t | mavlink_msg_autopilot_version_get_flight_sw_version (const mavlink_message_t *msg) |
Get field flight_sw_version from autopilot_version message. More... | |
static uint16_t | mavlink_msg_autopilot_version_get_middleware_custom_version (const mavlink_message_t *msg, uint8_t *middleware_custom_version) |
Get field middleware_custom_version from autopilot_version message. More... | |
static uint32_t | mavlink_msg_autopilot_version_get_middleware_sw_version (const mavlink_message_t *msg) |
Get field middleware_sw_version from autopilot_version message. More... | |
static uint16_t | mavlink_msg_autopilot_version_get_os_custom_version (const mavlink_message_t *msg, uint8_t *os_custom_version) |
Get field os_custom_version from autopilot_version message. More... | |
static uint32_t | mavlink_msg_autopilot_version_get_os_sw_version (const mavlink_message_t *msg) |
Get field os_sw_version from autopilot_version message. More... | |
static uint16_t | mavlink_msg_autopilot_version_get_product_id (const mavlink_message_t *msg) |
Get field product_id from autopilot_version message. More... | |
static uint64_t | mavlink_msg_autopilot_version_get_uid (const mavlink_message_t *msg) |
Get field uid from autopilot_version message. More... | |
static uint16_t | mavlink_msg_autopilot_version_get_vendor_id (const mavlink_message_t *msg) |
Get field vendor_id from autopilot_version message. More... | |
static uint16_t | mavlink_msg_autopilot_version_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid) |
Pack a autopilot_version message. More... | |
static uint16_t | mavlink_msg_autopilot_version_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid) |
Pack a autopilot_version message on a channel. More... | |
#define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION |
Definition at line 30 of file mavlink_msg_autopilot_version.h.
#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_FLIGHT_CUSTOM_VERSION_LEN 8 |
Definition at line 26 of file mavlink_msg_autopilot_version.h.
#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_MIDDLEWARE_CUSTOM_VERSION_LEN 8 |
Definition at line 27 of file mavlink_msg_autopilot_version.h.
#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_OS_CUSTOM_VERSION_LEN 8 |
Definition at line 28 of file mavlink_msg_autopilot_version.h.
#define MAVLINK_MSG_ID_148_CRC 178 |
Definition at line 24 of file mavlink_msg_autopilot_version.h.
#define MAVLINK_MSG_ID_148_LEN 60 |
Definition at line 21 of file mavlink_msg_autopilot_version.h.
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION 148 |
Definition at line 3 of file mavlink_msg_autopilot_version.h.
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC 178 |
Definition at line 23 of file mavlink_msg_autopilot_version.h.
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN 60 |
Definition at line 20 of file mavlink_msg_autopilot_version.h.
typedef struct __mavlink_autopilot_version_t mavlink_autopilot_version_t |
|
inlinestatic |
Decode a autopilot_version message into a struct.
msg | The message to decode |
autopilot_version | C-struct to decode the message contents into |
Definition at line 426 of file mavlink_msg_autopilot_version.h.
|
inlinestatic |
Encode a autopilot_version 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 |
autopilot_version | C-struct to read the message contents from |
Definition at line 177 of file mavlink_msg_autopilot_version.h.
|
inlinestatic |
Encode a autopilot_version 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 |
autopilot_version | C-struct to read the message contents from |
Definition at line 191 of file mavlink_msg_autopilot_version.h.
|
inlinestatic |
Get field board_version from autopilot_version message.
Definition at line 355 of file mavlink_msg_autopilot_version.h.
|
inlinestatic |
Send a autopilot_version message.
chan | MAVLink channel to send the message |
capabilities | bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) |
flight_sw_version | Firmware version number |
middleware_sw_version | Middleware version number |
os_sw_version | Operating system version number |
board_version | HW / board version (last 8 bytes should be silicon ID, if any) |
flight_custom_version | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. |
middleware_custom_version | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. |
os_custom_version | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. |
vendor_id | ID of the board vendor |
product_id | ID of the product |
uid | UID if provided by hardware Get field capabilities from autopilot_version message |
Definition at line 315 of file mavlink_msg_autopilot_version.h.
|
inlinestatic |
Get field flight_custom_version from autopilot_version message.
Definition at line 365 of file mavlink_msg_autopilot_version.h.
|
inlinestatic |
Get field flight_sw_version from autopilot_version message.
Definition at line 325 of file mavlink_msg_autopilot_version.h.
|
inlinestatic |
Get field middleware_custom_version from autopilot_version message.
Definition at line 375 of file mavlink_msg_autopilot_version.h.
|
inlinestatic |
Get field middleware_sw_version from autopilot_version message.
Definition at line 335 of file mavlink_msg_autopilot_version.h.
|
inlinestatic |
Get field os_custom_version from autopilot_version message.
Definition at line 385 of file mavlink_msg_autopilot_version.h.
|
inlinestatic |
Get field os_sw_version from autopilot_version message.
Definition at line 345 of file mavlink_msg_autopilot_version.h.
|
inlinestatic |
Get field product_id from autopilot_version message.
Definition at line 405 of file mavlink_msg_autopilot_version.h.
|
inlinestatic |
Get field uid from autopilot_version message.
Definition at line 415 of file mavlink_msg_autopilot_version.h.
|
inlinestatic |
Get field vendor_id from autopilot_version message.
Definition at line 395 of file mavlink_msg_autopilot_version.h.
|
inlinestatic |
Pack a autopilot_version 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 |
capabilities | bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) |
flight_sw_version | Firmware version number |
middleware_sw_version | Middleware version number |
os_sw_version | Operating system version number |
board_version | HW / board version (last 8 bytes should be silicon ID, if any) |
flight_custom_version | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. |
middleware_custom_version | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. |
os_custom_version | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. |
vendor_id | ID of the board vendor |
product_id | ID of the product |
uid | UID if provided by hardware |
Definition at line 67 of file mavlink_msg_autopilot_version.h.
|
inlinestatic |
Pack a autopilot_version 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 |
capabilities | bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) |
flight_sw_version | Firmware version number |
middleware_sw_version | Middleware version number |
os_sw_version | Operating system version number |
board_version | HW / board version (last 8 bytes should be silicon ID, if any) |
flight_custom_version | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. |
middleware_custom_version | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. |
os_custom_version | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. |
vendor_id | ID of the board vendor |
product_id | ID of the product |
uid | UID if provided by hardware |
Definition at line 127 of file mavlink_msg_autopilot_version.h.