mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-24 00:35:34 +03:00
[MAVLINK] Update mavlink library to latest v1.0 release
This commit is contained in:
parent
81f2e0c0c0
commit
d8ac874087
149 changed files with 10247 additions and 5961 deletions
|
@ -3,22 +3,22 @@
|
|||
|
||||
#define MAVLINK_MSG_ID_COMMAND_INT 75
|
||||
|
||||
MAVPACKED(
|
||||
|
||||
typedef struct __mavlink_command_int_t {
|
||||
float param1; /*< PARAM1, see MAV_CMD enum*/
|
||||
float param2; /*< PARAM2, see MAV_CMD enum*/
|
||||
float param3; /*< PARAM3, see MAV_CMD enum*/
|
||||
float param4; /*< PARAM4, see MAV_CMD enum*/
|
||||
int32_t x; /*< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7*/
|
||||
int32_t y; /*< PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7*/
|
||||
float z; /*< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.*/
|
||||
uint16_t command; /*< The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs*/
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
uint8_t frame; /*< The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h*/
|
||||
uint8_t current; /*< false:0, true:1*/
|
||||
uint8_t autocontinue; /*< autocontinue to next wp*/
|
||||
}) mavlink_command_int_t;
|
||||
float param1; /*< PARAM1, see MAV_CMD enum*/
|
||||
float param2; /*< PARAM2, see MAV_CMD enum*/
|
||||
float param3; /*< PARAM3, see MAV_CMD enum*/
|
||||
float param4; /*< PARAM4, see MAV_CMD enum*/
|
||||
int32_t x; /*< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7*/
|
||||
int32_t y; /*< PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7*/
|
||||
float z; /*< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame).*/
|
||||
uint16_t command; /*< The scheduled action for the mission item.*/
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
uint8_t frame; /*< The coordinate system of the COMMAND.*/
|
||||
uint8_t current; /*< false:0, true:1*/
|
||||
uint8_t autocontinue; /*< autocontinue to next wp*/
|
||||
} mavlink_command_int_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_COMMAND_INT_LEN 35
|
||||
#define MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN 35
|
||||
|
@ -35,38 +35,38 @@ typedef struct __mavlink_command_int_t {
|
|||
75, \
|
||||
"COMMAND_INT", \
|
||||
13, \
|
||||
{ { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \
|
||||
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \
|
||||
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \
|
||||
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \
|
||||
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \
|
||||
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \
|
||||
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \
|
||||
{ "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \
|
||||
{ "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_int_t, param2) }, \
|
||||
{ "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_int_t, param3) }, \
|
||||
{ "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_int_t, param4) }, \
|
||||
{ "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_command_int_t, x) }, \
|
||||
{ "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_command_int_t, y) }, \
|
||||
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_int_t, z) }, \
|
||||
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \
|
||||
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \
|
||||
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \
|
||||
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \
|
||||
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \
|
||||
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \
|
||||
} \
|
||||
}
|
||||
#else
|
||||
#define MAVLINK_MESSAGE_INFO_COMMAND_INT { \
|
||||
"COMMAND_INT", \
|
||||
13, \
|
||||
{ { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \
|
||||
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \
|
||||
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \
|
||||
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \
|
||||
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \
|
||||
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \
|
||||
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \
|
||||
{ "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \
|
||||
{ "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_int_t, param2) }, \
|
||||
{ "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_int_t, param3) }, \
|
||||
{ "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_int_t, param4) }, \
|
||||
{ "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_command_int_t, x) }, \
|
||||
{ "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_command_int_t, y) }, \
|
||||
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_int_t, z) }, \
|
||||
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \
|
||||
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \
|
||||
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \
|
||||
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \
|
||||
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \
|
||||
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \
|
||||
} \
|
||||
}
|
||||
#endif
|
||||
|
@ -77,19 +77,19 @@ typedef struct __mavlink_command_int_t {
|
|||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
*
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
* @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h
|
||||
* @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs
|
||||
* @param current false:0, true:1
|
||||
* @param autocontinue autocontinue to next wp
|
||||
* @param param1 PARAM1, see MAV_CMD enum
|
||||
* @param param2 PARAM2, see MAV_CMD enum
|
||||
* @param param3 PARAM3, see MAV_CMD enum
|
||||
* @param param4 PARAM4, see MAV_CMD enum
|
||||
* @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
|
||||
* @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
|
||||
* @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
* @param frame The coordinate system of the COMMAND.
|
||||
* @param command The scheduled action for the mission item.
|
||||
* @param current false:0, true:1
|
||||
* @param autocontinue autocontinue to next wp
|
||||
* @param param1 PARAM1, see MAV_CMD enum
|
||||
* @param param2 PARAM2, see MAV_CMD enum
|
||||
* @param param3 PARAM3, see MAV_CMD enum
|
||||
* @param param4 PARAM4, see MAV_CMD enum
|
||||
* @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
|
||||
* @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
|
||||
* @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame).
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_command_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
|
@ -141,19 +141,19 @@ static inline uint16_t mavlink_msg_command_int_pack(uint8_t system_id, uint8_t c
|
|||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
* @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h
|
||||
* @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs
|
||||
* @param current false:0, true:1
|
||||
* @param autocontinue autocontinue to next wp
|
||||
* @param param1 PARAM1, see MAV_CMD enum
|
||||
* @param param2 PARAM2, see MAV_CMD enum
|
||||
* @param param3 PARAM3, see MAV_CMD enum
|
||||
* @param param4 PARAM4, see MAV_CMD enum
|
||||
* @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
|
||||
* @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
|
||||
* @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
* @param frame The coordinate system of the COMMAND.
|
||||
* @param command The scheduled action for the mission item.
|
||||
* @param current false:0, true:1
|
||||
* @param autocontinue autocontinue to next wp
|
||||
* @param param1 PARAM1, see MAV_CMD enum
|
||||
* @param param2 PARAM2, see MAV_CMD enum
|
||||
* @param param3 PARAM3, see MAV_CMD enum
|
||||
* @param param4 PARAM4, see MAV_CMD enum
|
||||
* @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
|
||||
* @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
|
||||
* @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame).
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_command_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
|
@ -231,19 +231,19 @@ static inline uint16_t mavlink_msg_command_int_encode_chan(uint8_t system_id, ui
|
|||
* @brief Send a command_int message
|
||||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
* @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h
|
||||
* @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs
|
||||
* @param current false:0, true:1
|
||||
* @param autocontinue autocontinue to next wp
|
||||
* @param param1 PARAM1, see MAV_CMD enum
|
||||
* @param param2 PARAM2, see MAV_CMD enum
|
||||
* @param param3 PARAM3, see MAV_CMD enum
|
||||
* @param param4 PARAM4, see MAV_CMD enum
|
||||
* @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
|
||||
* @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
|
||||
* @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
* @param frame The coordinate system of the COMMAND.
|
||||
* @param command The scheduled action for the mission item.
|
||||
* @param current false:0, true:1
|
||||
* @param autocontinue autocontinue to next wp
|
||||
* @param param1 PARAM1, see MAV_CMD enum
|
||||
* @param param2 PARAM2, see MAV_CMD enum
|
||||
* @param param3 PARAM3, see MAV_CMD enum
|
||||
* @param param4 PARAM4, see MAV_CMD enum
|
||||
* @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
|
||||
* @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
|
||||
* @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame).
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
|
@ -356,7 +356,7 @@ static inline void mavlink_msg_command_int_send_buf(mavlink_message_t *msgbuf, m
|
|||
/**
|
||||
* @brief Get field target_system from command_int message
|
||||
*
|
||||
* @return System ID
|
||||
* @return System ID
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_command_int_get_target_system(const mavlink_message_t* msg)
|
||||
{
|
||||
|
@ -366,7 +366,7 @@ static inline uint8_t mavlink_msg_command_int_get_target_system(const mavlink_me
|
|||
/**
|
||||
* @brief Get field target_component from command_int message
|
||||
*
|
||||
* @return Component ID
|
||||
* @return Component ID
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_command_int_get_target_component(const mavlink_message_t* msg)
|
||||
{
|
||||
|
@ -376,7 +376,7 @@ static inline uint8_t mavlink_msg_command_int_get_target_component(const mavlink
|
|||
/**
|
||||
* @brief Get field frame from command_int message
|
||||
*
|
||||
* @return The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h
|
||||
* @return The coordinate system of the COMMAND.
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_command_int_get_frame(const mavlink_message_t* msg)
|
||||
{
|
||||
|
@ -386,7 +386,7 @@ static inline uint8_t mavlink_msg_command_int_get_frame(const mavlink_message_t*
|
|||
/**
|
||||
* @brief Get field command from command_int message
|
||||
*
|
||||
* @return The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs
|
||||
* @return The scheduled action for the mission item.
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_command_int_get_command(const mavlink_message_t* msg)
|
||||
{
|
||||
|
@ -396,7 +396,7 @@ static inline uint16_t mavlink_msg_command_int_get_command(const mavlink_message
|
|||
/**
|
||||
* @brief Get field current from command_int message
|
||||
*
|
||||
* @return false:0, true:1
|
||||
* @return false:0, true:1
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_command_int_get_current(const mavlink_message_t* msg)
|
||||
{
|
||||
|
@ -406,7 +406,7 @@ static inline uint8_t mavlink_msg_command_int_get_current(const mavlink_message_
|
|||
/**
|
||||
* @brief Get field autocontinue from command_int message
|
||||
*
|
||||
* @return autocontinue to next wp
|
||||
* @return autocontinue to next wp
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_command_int_get_autocontinue(const mavlink_message_t* msg)
|
||||
{
|
||||
|
@ -416,7 +416,7 @@ static inline uint8_t mavlink_msg_command_int_get_autocontinue(const mavlink_mes
|
|||
/**
|
||||
* @brief Get field param1 from command_int message
|
||||
*
|
||||
* @return PARAM1, see MAV_CMD enum
|
||||
* @return PARAM1, see MAV_CMD enum
|
||||
*/
|
||||
static inline float mavlink_msg_command_int_get_param1(const mavlink_message_t* msg)
|
||||
{
|
||||
|
@ -426,7 +426,7 @@ static inline float mavlink_msg_command_int_get_param1(const mavlink_message_t*
|
|||
/**
|
||||
* @brief Get field param2 from command_int message
|
||||
*
|
||||
* @return PARAM2, see MAV_CMD enum
|
||||
* @return PARAM2, see MAV_CMD enum
|
||||
*/
|
||||
static inline float mavlink_msg_command_int_get_param2(const mavlink_message_t* msg)
|
||||
{
|
||||
|
@ -436,7 +436,7 @@ static inline float mavlink_msg_command_int_get_param2(const mavlink_message_t*
|
|||
/**
|
||||
* @brief Get field param3 from command_int message
|
||||
*
|
||||
* @return PARAM3, see MAV_CMD enum
|
||||
* @return PARAM3, see MAV_CMD enum
|
||||
*/
|
||||
static inline float mavlink_msg_command_int_get_param3(const mavlink_message_t* msg)
|
||||
{
|
||||
|
@ -446,7 +446,7 @@ static inline float mavlink_msg_command_int_get_param3(const mavlink_message_t*
|
|||
/**
|
||||
* @brief Get field param4 from command_int message
|
||||
*
|
||||
* @return PARAM4, see MAV_CMD enum
|
||||
* @return PARAM4, see MAV_CMD enum
|
||||
*/
|
||||
static inline float mavlink_msg_command_int_get_param4(const mavlink_message_t* msg)
|
||||
{
|
||||
|
@ -456,7 +456,7 @@ static inline float mavlink_msg_command_int_get_param4(const mavlink_message_t*
|
|||
/**
|
||||
* @brief Get field x from command_int message
|
||||
*
|
||||
* @return PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
|
||||
* @return PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
|
||||
*/
|
||||
static inline int32_t mavlink_msg_command_int_get_x(const mavlink_message_t* msg)
|
||||
{
|
||||
|
@ -466,7 +466,7 @@ static inline int32_t mavlink_msg_command_int_get_x(const mavlink_message_t* msg
|
|||
/**
|
||||
* @brief Get field y from command_int message
|
||||
*
|
||||
* @return PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
|
||||
* @return PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
|
||||
*/
|
||||
static inline int32_t mavlink_msg_command_int_get_y(const mavlink_message_t* msg)
|
||||
{
|
||||
|
@ -476,7 +476,7 @@ static inline int32_t mavlink_msg_command_int_get_y(const mavlink_message_t* msg
|
|||
/**
|
||||
* @brief Get field z from command_int message
|
||||
*
|
||||
* @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
|
||||
* @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame).
|
||||
*/
|
||||
static inline float mavlink_msg_command_int_get_z(const mavlink_message_t* msg)
|
||||
{
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue