MAVLink: updated to latest upstream mavlink

this includes no significant changes
This commit is contained in:
Andrew Tridgell 2012-05-25 17:57:34 +10:00
parent 45c3c101fe
commit 2c3bfd896a
18 changed files with 711 additions and 297 deletions

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Apr 30 11:40:11 2012"
#define MAVLINK_BUILD_DATE "Fri May 25 17:56:06 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Apr 30 11:40:11 2012"
#define MAVLINK_BUILD_DATE "Fri May 25 17:56:06 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101

File diff suppressed because one or more lines are too long

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Apr 30 11:40:12 2012"
#define MAVLINK_BUILD_DATE "Fri May 25 17:56:06 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101

File diff suppressed because one or more lines are too long

View File

@ -4,10 +4,10 @@
typedef struct __mavlink_param_request_read_t
{
int16_t param_index; ///< Parameter index. Send -1 to use the param ID field as identifier
int16_t param_index; ///< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
char param_id[16]; ///< Onboard parameter id
char param_id[16]; ///< Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
} mavlink_param_request_read_t;
#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20
@ -34,8 +34,8 @@ typedef struct __mavlink_param_request_read_t
*
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_index Parameter index. Send -1 to use the param ID field as identifier
* @param param_id Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -69,8 +69,8 @@ static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, ui
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_index Parameter index. Send -1 to use the param ID field as identifier
* @param param_id Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -116,8 +116,8 @@ static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id,
*
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_index Parameter index. Send -1 to use the param ID field as identifier
* @param param_id Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -168,7 +168,7 @@ static inline uint8_t mavlink_msg_param_request_read_get_target_component(const
/**
* @brief Get field param_id from param_request_read message
*
* @return Onboard parameter id
* @return Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
*/
static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t* msg, char *param_id)
{
@ -178,7 +178,7 @@ static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink
/**
* @brief Get field param_index from param_request_read message
*
* @return Parameter index. Send -1 to use the param ID field as identifier
* @return Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
*/
static inline int16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t* msg)
{

View File

@ -7,8 +7,8 @@ typedef struct __mavlink_param_set_t
float param_value; ///< Onboard parameter value
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
char param_id[16]; ///< Onboard parameter id
uint8_t param_type; ///< Onboard parameter type: see MAV_VAR enum
char param_id[16]; ///< Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
uint8_t param_type; ///< Onboard parameter type: see MAVLINK_TYPE enum in mavlink/mavlink_types.h
} mavlink_param_set_t;
#define MAVLINK_MSG_ID_PARAM_SET_LEN 23
@ -36,9 +36,9 @@ typedef struct __mavlink_param_set_t
*
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_id Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see MAV_VAR enum
* @param param_type Onboard parameter type: see MAVLINK_TYPE enum in mavlink/mavlink_types.h
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@ -74,9 +74,9 @@ static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t com
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_id Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see MAV_VAR enum
* @param param_type Onboard parameter type: see MAVLINK_TYPE enum in mavlink/mavlink_types.h
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@ -124,9 +124,9 @@ static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t c
*
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_id Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see MAV_VAR enum
* @param param_type Onboard parameter type: see MAVLINK_TYPE enum in mavlink/mavlink_types.h
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -179,7 +179,7 @@ static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_m
/**
* @brief Get field param_id from param_set message
*
* @return Onboard parameter id
* @return Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
*/
static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t* msg, char *param_id)
{
@ -199,7 +199,7 @@ static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_
/**
* @brief Get field param_type from param_set message
*
* @return Onboard parameter type: see MAV_VAR enum
* @return Onboard parameter type: see MAVLINK_TYPE enum in mavlink/mavlink_types.h
*/
static inline uint8_t mavlink_msg_param_set_get_param_type(const mavlink_message_t* msg)
{

View File

@ -7,8 +7,8 @@ typedef struct __mavlink_param_value_t
float param_value; ///< Onboard parameter value
uint16_t param_count; ///< Total number of onboard parameters
uint16_t param_index; ///< Index of this onboard parameter
char param_id[16]; ///< Onboard parameter id
uint8_t param_type; ///< Onboard parameter type: see MAV_VAR enum
char param_id[16]; ///< Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
uint8_t param_type; ///< Onboard parameter type: see MAVLINK_TYPE enum in mavlink/mavlink_types.h
} mavlink_param_value_t;
#define MAVLINK_MSG_ID_PARAM_VALUE_LEN 25
@ -34,9 +34,9 @@ typedef struct __mavlink_param_value_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param param_id Onboard parameter id
* @param param_id Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see MAV_VAR enum
* @param param_type Onboard parameter type: see MAVLINK_TYPE enum in mavlink/mavlink_types.h
* @param param_count Total number of onboard parameters
* @param param_index Index of this onboard parameter
* @return length of the message in bytes (excluding serial stream start sign)
@ -72,9 +72,9 @@ static inline uint16_t mavlink_msg_param_value_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 was sent over
* @param msg The MAVLink message to compress the data into
* @param param_id Onboard parameter id
* @param param_id Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see MAV_VAR enum
* @param param_type Onboard parameter type: see MAVLINK_TYPE enum in mavlink/mavlink_types.h
* @param param_count Total number of onboard parameters
* @param param_index Index of this onboard parameter
* @return length of the message in bytes (excluding serial stream start sign)
@ -122,9 +122,9 @@ static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t
* @brief Send a param_value message
* @param chan MAVLink channel to send the message
*
* @param param_id Onboard parameter id
* @param param_id Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see MAV_VAR enum
* @param param_type Onboard parameter type: see MAVLINK_TYPE enum in mavlink/mavlink_types.h
* @param param_count Total number of onboard parameters
* @param param_index Index of this onboard parameter
*/
@ -159,7 +159,7 @@ static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const ch
/**
* @brief Get field param_id from param_value message
*
* @return Onboard parameter id
* @return Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
*/
static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, char *param_id)
{
@ -179,7 +179,7 @@ static inline float mavlink_msg_param_value_get_param_value(const mavlink_messag
/**
* @brief Get field param_type from param_value message
*
* @return Onboard parameter type: see MAV_VAR enum
* @return Onboard parameter type: see MAVLINK_TYPE enum in mavlink/mavlink_types.h
*/
static inline uint8_t mavlink_msg_param_value_get_param_type(const mavlink_message_t* msg)
{

View File

@ -0,0 +1,320 @@
// MESSAGE SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST PACKING
#define MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST 63
typedef struct __mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t
{
int16_t roll[4]; ///< Desired roll angle in radians +-PI (+-32767)
int16_t pitch[4]; ///< Desired pitch angle in radians +-PI (+-32767)
int16_t yaw[4]; ///< Desired yaw angle in radians, scaled to int16 +-PI (+-32767)
uint16_t thrust[4]; ///< Collective thrust, scaled to uint16 (0..65535)
uint8_t group; ///< ID of the quadrotor group (0 - 255, up to 256 groups supported)
uint8_t mode; ///< ID of the flight mode (0 - 255, up to 256 modes supported)
uint8_t led_red[4]; ///< RGB red channel (0-255)
uint8_t led_blue[4]; ///< RGB green channel (0-255)
uint8_t led_green[4]; ///< RGB blue channel (0-255)
} mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t;
#define MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN 46
#define MAVLINK_MSG_ID_63_LEN 46
#define MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_ROLL_LEN 4
#define MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_PITCH_LEN 4
#define MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_YAW_LEN 4
#define MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_THRUST_LEN 4
#define MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_LED_RED_LEN 4
#define MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_LED_BLUE_LEN 4
#define MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_LED_GREEN_LEN 4
#define MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST { \
"SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST", \
9, \
{ { "roll", NULL, MAVLINK_TYPE_INT16_T, 4, 0, offsetof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_INT16_T, 4, 8, offsetof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_INT16_T, 4, 16, offsetof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t, yaw) }, \
{ "thrust", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t, thrust) }, \
{ "group", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t, group) }, \
{ "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t, mode) }, \
{ "led_red", NULL, MAVLINK_TYPE_UINT8_T, 4, 34, offsetof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t, led_red) }, \
{ "led_blue", NULL, MAVLINK_TYPE_UINT8_T, 4, 38, offsetof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t, led_blue) }, \
{ "led_green", NULL, MAVLINK_TYPE_UINT8_T, 4, 42, offsetof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t, led_green) }, \
} \
}
/**
* @brief Pack a set_quad_swarm_led_roll_pitch_yaw_thrust message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param group ID of the quadrotor group (0 - 255, up to 256 groups supported)
* @param mode ID of the flight mode (0 - 255, up to 256 modes supported)
* @param led_red RGB red channel (0-255)
* @param led_blue RGB green channel (0-255)
* @param led_green RGB blue channel (0-255)
* @param roll Desired roll angle in radians +-PI (+-32767)
* @param pitch Desired pitch angle in radians +-PI (+-32767)
* @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-32767)
* @param thrust Collective thrust, scaled to uint16 (0..65535)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t group, uint8_t mode, const uint8_t *led_red, const uint8_t *led_blue, const uint8_t *led_green, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[46];
_mav_put_uint8_t(buf, 32, group);
_mav_put_uint8_t(buf, 33, mode);
_mav_put_int16_t_array(buf, 0, roll, 4);
_mav_put_int16_t_array(buf, 8, pitch, 4);
_mav_put_int16_t_array(buf, 16, yaw, 4);
_mav_put_uint16_t_array(buf, 24, thrust, 4);
_mav_put_uint8_t_array(buf, 34, led_red, 4);
_mav_put_uint8_t_array(buf, 38, led_blue, 4);
_mav_put_uint8_t_array(buf, 42, led_green, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 46);
#else
mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t packet;
packet.group = group;
packet.mode = mode;
mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*4);
mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*4);
mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*4);
mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*4);
mav_array_memcpy(packet.led_red, led_red, sizeof(uint8_t)*4);
mav_array_memcpy(packet.led_blue, led_blue, sizeof(uint8_t)*4);
mav_array_memcpy(packet.led_green, led_green, sizeof(uint8_t)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 46);
#endif
msg->msgid = MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST;
return mavlink_finalize_message(msg, system_id, component_id, 46, 130);
}
/**
* @brief Pack a set_quad_swarm_led_roll_pitch_yaw_thrust message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param group ID of the quadrotor group (0 - 255, up to 256 groups supported)
* @param mode ID of the flight mode (0 - 255, up to 256 modes supported)
* @param led_red RGB red channel (0-255)
* @param led_blue RGB green channel (0-255)
* @param led_green RGB blue channel (0-255)
* @param roll Desired roll angle in radians +-PI (+-32767)
* @param pitch Desired pitch angle in radians +-PI (+-32767)
* @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-32767)
* @param thrust Collective thrust, scaled to uint16 (0..65535)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t group,uint8_t mode,const uint8_t *led_red,const uint8_t *led_blue,const uint8_t *led_green,const int16_t *roll,const int16_t *pitch,const int16_t *yaw,const uint16_t *thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[46];
_mav_put_uint8_t(buf, 32, group);
_mav_put_uint8_t(buf, 33, mode);
_mav_put_int16_t_array(buf, 0, roll, 4);
_mav_put_int16_t_array(buf, 8, pitch, 4);
_mav_put_int16_t_array(buf, 16, yaw, 4);
_mav_put_uint16_t_array(buf, 24, thrust, 4);
_mav_put_uint8_t_array(buf, 34, led_red, 4);
_mav_put_uint8_t_array(buf, 38, led_blue, 4);
_mav_put_uint8_t_array(buf, 42, led_green, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 46);
#else
mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t packet;
packet.group = group;
packet.mode = mode;
mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*4);
mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*4);
mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*4);
mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*4);
mav_array_memcpy(packet.led_red, led_red, sizeof(uint8_t)*4);
mav_array_memcpy(packet.led_blue, led_blue, sizeof(uint8_t)*4);
mav_array_memcpy(packet.led_green, led_green, sizeof(uint8_t)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 46);
#endif
msg->msgid = MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 46, 130);
}
/**
* @brief Encode a set_quad_swarm_led_roll_pitch_yaw_thrust struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param set_quad_swarm_led_roll_pitch_yaw_thrust C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t* set_quad_swarm_led_roll_pitch_yaw_thrust)
{
return mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack(system_id, component_id, msg, set_quad_swarm_led_roll_pitch_yaw_thrust->group, set_quad_swarm_led_roll_pitch_yaw_thrust->mode, set_quad_swarm_led_roll_pitch_yaw_thrust->led_red, set_quad_swarm_led_roll_pitch_yaw_thrust->led_blue, set_quad_swarm_led_roll_pitch_yaw_thrust->led_green, set_quad_swarm_led_roll_pitch_yaw_thrust->roll, set_quad_swarm_led_roll_pitch_yaw_thrust->pitch, set_quad_swarm_led_roll_pitch_yaw_thrust->yaw, set_quad_swarm_led_roll_pitch_yaw_thrust->thrust);
}
/**
* @brief Send a set_quad_swarm_led_roll_pitch_yaw_thrust message
* @param chan MAVLink channel to send the message
*
* @param group ID of the quadrotor group (0 - 255, up to 256 groups supported)
* @param mode ID of the flight mode (0 - 255, up to 256 modes supported)
* @param led_red RGB red channel (0-255)
* @param led_blue RGB green channel (0-255)
* @param led_green RGB blue channel (0-255)
* @param roll Desired roll angle in radians +-PI (+-32767)
* @param pitch Desired pitch angle in radians +-PI (+-32767)
* @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-32767)
* @param thrust Collective thrust, scaled to uint16 (0..65535)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_send(mavlink_channel_t chan, uint8_t group, uint8_t mode, const uint8_t *led_red, const uint8_t *led_blue, const uint8_t *led_green, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[46];
_mav_put_uint8_t(buf, 32, group);
_mav_put_uint8_t(buf, 33, mode);
_mav_put_int16_t_array(buf, 0, roll, 4);
_mav_put_int16_t_array(buf, 8, pitch, 4);
_mav_put_int16_t_array(buf, 16, yaw, 4);
_mav_put_uint16_t_array(buf, 24, thrust, 4);
_mav_put_uint8_t_array(buf, 34, led_red, 4);
_mav_put_uint8_t_array(buf, 38, led_blue, 4);
_mav_put_uint8_t_array(buf, 42, led_green, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, buf, 46, 130);
#else
mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t packet;
packet.group = group;
packet.mode = mode;
mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*4);
mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*4);
mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*4);
mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*4);
mav_array_memcpy(packet.led_red, led_red, sizeof(uint8_t)*4);
mav_array_memcpy(packet.led_blue, led_blue, sizeof(uint8_t)*4);
mav_array_memcpy(packet.led_green, led_green, sizeof(uint8_t)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, (const char *)&packet, 46, 130);
#endif
}
#endif
// MESSAGE SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST UNPACKING
/**
* @brief Get field group from set_quad_swarm_led_roll_pitch_yaw_thrust message
*
* @return ID of the quadrotor group (0 - 255, up to 256 groups supported)
*/
static inline uint8_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_group(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 32);
}
/**
* @brief Get field mode from set_quad_swarm_led_roll_pitch_yaw_thrust message
*
* @return ID of the flight mode (0 - 255, up to 256 modes supported)
*/
static inline uint8_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 33);
}
/**
* @brief Get field led_red from set_quad_swarm_led_roll_pitch_yaw_thrust message
*
* @return RGB red channel (0-255)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_led_red(const mavlink_message_t* msg, uint8_t *led_red)
{
return _MAV_RETURN_uint8_t_array(msg, led_red, 4, 34);
}
/**
* @brief Get field led_blue from set_quad_swarm_led_roll_pitch_yaw_thrust message
*
* @return RGB green channel (0-255)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_led_blue(const mavlink_message_t* msg, uint8_t *led_blue)
{
return _MAV_RETURN_uint8_t_array(msg, led_blue, 4, 38);
}
/**
* @brief Get field led_green from set_quad_swarm_led_roll_pitch_yaw_thrust message
*
* @return RGB blue channel (0-255)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_led_green(const mavlink_message_t* msg, uint8_t *led_green)
{
return _MAV_RETURN_uint8_t_array(msg, led_green, 4, 42);
}
/**
* @brief Get field roll from set_quad_swarm_led_roll_pitch_yaw_thrust message
*
* @return Desired roll angle in radians +-PI (+-32767)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_roll(const mavlink_message_t* msg, int16_t *roll)
{
return _MAV_RETURN_int16_t_array(msg, roll, 4, 0);
}
/**
* @brief Get field pitch from set_quad_swarm_led_roll_pitch_yaw_thrust message
*
* @return Desired pitch angle in radians +-PI (+-32767)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_pitch(const mavlink_message_t* msg, int16_t *pitch)
{
return _MAV_RETURN_int16_t_array(msg, pitch, 4, 8);
}
/**
* @brief Get field yaw from set_quad_swarm_led_roll_pitch_yaw_thrust message
*
* @return Desired yaw angle in radians, scaled to int16 +-PI (+-32767)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_yaw(const mavlink_message_t* msg, int16_t *yaw)
{
return _MAV_RETURN_int16_t_array(msg, yaw, 4, 16);
}
/**
* @brief Get field thrust from set_quad_swarm_led_roll_pitch_yaw_thrust message
*
* @return Collective thrust, scaled to uint16 (0..65535)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_thrust(const mavlink_message_t* msg, uint16_t *thrust)
{
return _MAV_RETURN_uint16_t_array(msg, thrust, 4, 24);
}
/**
* @brief Decode a set_quad_swarm_led_roll_pitch_yaw_thrust message into a struct
*
* @param msg The message to decode
* @param set_quad_swarm_led_roll_pitch_yaw_thrust C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_decode(const mavlink_message_t* msg, mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t* set_quad_swarm_led_roll_pitch_yaw_thrust)
{
#if MAVLINK_NEED_BYTE_SWAP
mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_roll(msg, set_quad_swarm_led_roll_pitch_yaw_thrust->roll);
mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_pitch(msg, set_quad_swarm_led_roll_pitch_yaw_thrust->pitch);
mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_yaw(msg, set_quad_swarm_led_roll_pitch_yaw_thrust->yaw);
mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_thrust(msg, set_quad_swarm_led_roll_pitch_yaw_thrust->thrust);
set_quad_swarm_led_roll_pitch_yaw_thrust->group = mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_group(msg);
set_quad_swarm_led_roll_pitch_yaw_thrust->mode = mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_mode(msg);
mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_led_red(msg, set_quad_swarm_led_roll_pitch_yaw_thrust->led_red);
mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_led_blue(msg, set_quad_swarm_led_roll_pitch_yaw_thrust->led_blue);
mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_led_green(msg, set_quad_swarm_led_roll_pitch_yaw_thrust->led_green);
#else
memcpy(set_quad_swarm_led_roll_pitch_yaw_thrust, _MAV_PAYLOAD(msg), 46);
#endif
}

View File

@ -4,30 +4,31 @@
typedef struct __mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t
{
int16_t roll[6]; ///< Desired roll angle in radians, scaled to int16 for 6 quadrotors: 0..5
int16_t pitch[6]; ///< Desired pitch angle in radians, scaled to int16 for 6 quadrotors: 0..5
int16_t yaw[6]; ///< Desired yaw angle in radians, scaled to int16 for 6 quadrotors: 0..5
uint16_t thrust[6]; ///< Collective thrust, scaled to uint16 for 6 quadrotors: 0..5
uint8_t target_systems[6]; ///< System IDs for 6 quadrotors: 0..5, the ID's are the MAVLink IDs
int16_t roll[4]; ///< Desired roll angle in radians +-PI (+-32767)
int16_t pitch[4]; ///< Desired pitch angle in radians +-PI (+-32767)
int16_t yaw[4]; ///< Desired yaw angle in radians, scaled to int16 +-PI (+-32767)
uint16_t thrust[4]; ///< Collective thrust, scaled to uint16 (0..65535)
uint8_t group; ///< ID of the quadrotor group (0 - 255, up to 256 groups supported)
uint8_t mode; ///< ID of the flight mode (0 - 255, up to 256 modes supported)
} mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t;
#define MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN 54
#define MAVLINK_MSG_ID_61_LEN 54
#define MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN 34
#define MAVLINK_MSG_ID_61_LEN 34
#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_ROLL_LEN 6
#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_PITCH_LEN 6
#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_YAW_LEN 6
#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_THRUST_LEN 6
#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_TARGET_SYSTEMS_LEN 6
#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_ROLL_LEN 4
#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_PITCH_LEN 4
#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_YAW_LEN 4
#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_THRUST_LEN 4
#define MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST { \
"SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST", \
5, \
{ { "roll", NULL, MAVLINK_TYPE_INT16_T, 6, 0, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_INT16_T, 6, 12, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_INT16_T, 6, 24, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, yaw) }, \
{ "thrust", NULL, MAVLINK_TYPE_UINT16_T, 6, 36, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, thrust) }, \
{ "target_systems", NULL, MAVLINK_TYPE_UINT8_T, 6, 48, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, target_systems) }, \
6, \
{ { "roll", NULL, MAVLINK_TYPE_INT16_T, 4, 0, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_INT16_T, 4, 8, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_INT16_T, 4, 16, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, yaw) }, \
{ "thrust", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, thrust) }, \
{ "group", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, group) }, \
{ "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, mode) }, \
} \
}
@ -38,38 +39,39 @@ typedef struct __mavlink_set_quad_swarm_roll_pitch_yaw_thrust_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_systems System IDs for 6 quadrotors: 0..5, the ID's are the MAVLink IDs
* @param roll Desired roll angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @param pitch Desired pitch angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @param yaw Desired yaw angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @param thrust Collective thrust, scaled to uint16 for 6 quadrotors: 0..5
* @param group ID of the quadrotor group (0 - 255, up to 256 groups supported)
* @param mode ID of the flight mode (0 - 255, up to 256 modes supported)
* @param roll Desired roll angle in radians +-PI (+-32767)
* @param pitch Desired pitch angle in radians +-PI (+-32767)
* @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-32767)
* @param thrust Collective thrust, scaled to uint16 (0..65535)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const uint8_t *target_systems, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust)
uint8_t group, uint8_t mode, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[54];
_mav_put_int16_t_array(buf, 0, roll, 6);
_mav_put_int16_t_array(buf, 12, pitch, 6);
_mav_put_int16_t_array(buf, 24, yaw, 6);
_mav_put_uint16_t_array(buf, 36, thrust, 6);
_mav_put_uint8_t_array(buf, 48, target_systems, 6);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 54);
char buf[34];
_mav_put_uint8_t(buf, 32, group);
_mav_put_uint8_t(buf, 33, mode);
_mav_put_int16_t_array(buf, 0, roll, 4);
_mav_put_int16_t_array(buf, 8, pitch, 4);
_mav_put_int16_t_array(buf, 16, yaw, 4);
_mav_put_uint16_t_array(buf, 24, thrust, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 34);
#else
mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet;
mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*6);
mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*6);
mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*6);
mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*6);
mav_array_memcpy(packet.target_systems, target_systems, sizeof(uint8_t)*6);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 54);
packet.group = group;
packet.mode = mode;
mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*4);
mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*4);
mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*4);
mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 34);
#endif
msg->msgid = MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST;
return mavlink_finalize_message(msg, system_id, component_id, 54, 200);
return mavlink_finalize_message(msg, system_id, component_id, 34, 240);
}
/**
@ -78,39 +80,40 @@ static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack(uin
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_systems System IDs for 6 quadrotors: 0..5, the ID's are the MAVLink IDs
* @param roll Desired roll angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @param pitch Desired pitch angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @param yaw Desired yaw angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @param thrust Collective thrust, scaled to uint16 for 6 quadrotors: 0..5
* @param group ID of the quadrotor group (0 - 255, up to 256 groups supported)
* @param mode ID of the flight mode (0 - 255, up to 256 modes supported)
* @param roll Desired roll angle in radians +-PI (+-32767)
* @param pitch Desired pitch angle in radians +-PI (+-32767)
* @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-32767)
* @param thrust Collective thrust, scaled to uint16 (0..65535)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const uint8_t *target_systems,const int16_t *roll,const int16_t *pitch,const int16_t *yaw,const uint16_t *thrust)
uint8_t group,uint8_t mode,const int16_t *roll,const int16_t *pitch,const int16_t *yaw,const uint16_t *thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[54];
_mav_put_int16_t_array(buf, 0, roll, 6);
_mav_put_int16_t_array(buf, 12, pitch, 6);
_mav_put_int16_t_array(buf, 24, yaw, 6);
_mav_put_uint16_t_array(buf, 36, thrust, 6);
_mav_put_uint8_t_array(buf, 48, target_systems, 6);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 54);
char buf[34];
_mav_put_uint8_t(buf, 32, group);
_mav_put_uint8_t(buf, 33, mode);
_mav_put_int16_t_array(buf, 0, roll, 4);
_mav_put_int16_t_array(buf, 8, pitch, 4);
_mav_put_int16_t_array(buf, 16, yaw, 4);
_mav_put_uint16_t_array(buf, 24, thrust, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 34);
#else
mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet;
mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*6);
mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*6);
mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*6);
mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*6);
mav_array_memcpy(packet.target_systems, target_systems, sizeof(uint8_t)*6);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 54);
packet.group = group;
packet.mode = mode;
mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*4);
mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*4);
mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*4);
mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 34);
#endif
msg->msgid = MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 54, 200);
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 34, 240);
}
/**
@ -123,41 +126,42 @@ static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack_cha
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t* set_quad_swarm_roll_pitch_yaw_thrust)
{
return mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack(system_id, component_id, msg, set_quad_swarm_roll_pitch_yaw_thrust->target_systems, set_quad_swarm_roll_pitch_yaw_thrust->roll, set_quad_swarm_roll_pitch_yaw_thrust->pitch, set_quad_swarm_roll_pitch_yaw_thrust->yaw, set_quad_swarm_roll_pitch_yaw_thrust->thrust);
return mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack(system_id, component_id, msg, set_quad_swarm_roll_pitch_yaw_thrust->group, set_quad_swarm_roll_pitch_yaw_thrust->mode, set_quad_swarm_roll_pitch_yaw_thrust->roll, set_quad_swarm_roll_pitch_yaw_thrust->pitch, set_quad_swarm_roll_pitch_yaw_thrust->yaw, set_quad_swarm_roll_pitch_yaw_thrust->thrust);
}
/**
* @brief Send a set_quad_swarm_roll_pitch_yaw_thrust message
* @param chan MAVLink channel to send the message
*
* @param target_systems System IDs for 6 quadrotors: 0..5, the ID's are the MAVLink IDs
* @param roll Desired roll angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @param pitch Desired pitch angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @param yaw Desired yaw angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @param thrust Collective thrust, scaled to uint16 for 6 quadrotors: 0..5
* @param group ID of the quadrotor group (0 - 255, up to 256 groups supported)
* @param mode ID of the flight mode (0 - 255, up to 256 modes supported)
* @param roll Desired roll angle in radians +-PI (+-32767)
* @param pitch Desired pitch angle in radians +-PI (+-32767)
* @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-32767)
* @param thrust Collective thrust, scaled to uint16 (0..65535)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_send(mavlink_channel_t chan, const uint8_t *target_systems, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust)
static inline void mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_send(mavlink_channel_t chan, uint8_t group, uint8_t mode, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[54];
_mav_put_int16_t_array(buf, 0, roll, 6);
_mav_put_int16_t_array(buf, 12, pitch, 6);
_mav_put_int16_t_array(buf, 24, yaw, 6);
_mav_put_uint16_t_array(buf, 36, thrust, 6);
_mav_put_uint8_t_array(buf, 48, target_systems, 6);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, buf, 54, 200);
char buf[34];
_mav_put_uint8_t(buf, 32, group);
_mav_put_uint8_t(buf, 33, mode);
_mav_put_int16_t_array(buf, 0, roll, 4);
_mav_put_int16_t_array(buf, 8, pitch, 4);
_mav_put_int16_t_array(buf, 16, yaw, 4);
_mav_put_uint16_t_array(buf, 24, thrust, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, buf, 34, 240);
#else
mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet;
mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*6);
mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*6);
mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*6);
mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*6);
mav_array_memcpy(packet.target_systems, target_systems, sizeof(uint8_t)*6);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, (const char *)&packet, 54, 200);
packet.group = group;
packet.mode = mode;
mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*4);
mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*4);
mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*4);
mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, (const char *)&packet, 34, 240);
#endif
}
@ -167,53 +171,63 @@ static inline void mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_send(mavlink
/**
* @brief Get field target_systems from set_quad_swarm_roll_pitch_yaw_thrust message
* @brief Get field group from set_quad_swarm_roll_pitch_yaw_thrust message
*
* @return System IDs for 6 quadrotors: 0..5, the ID's are the MAVLink IDs
* @return ID of the quadrotor group (0 - 255, up to 256 groups supported)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_target_systems(const mavlink_message_t* msg, uint8_t *target_systems)
static inline uint8_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_group(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t_array(msg, target_systems, 6, 48);
return _MAV_RETURN_uint8_t(msg, 32);
}
/**
* @brief Get field mode from set_quad_swarm_roll_pitch_yaw_thrust message
*
* @return ID of the flight mode (0 - 255, up to 256 modes supported)
*/
static inline uint8_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 33);
}
/**
* @brief Get field roll from set_quad_swarm_roll_pitch_yaw_thrust message
*
* @return Desired roll angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @return Desired roll angle in radians +-PI (+-32767)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_roll(const mavlink_message_t* msg, int16_t *roll)
{
return _MAV_RETURN_int16_t_array(msg, roll, 6, 0);
return _MAV_RETURN_int16_t_array(msg, roll, 4, 0);
}
/**
* @brief Get field pitch from set_quad_swarm_roll_pitch_yaw_thrust message
*
* @return Desired pitch angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @return Desired pitch angle in radians +-PI (+-32767)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_pitch(const mavlink_message_t* msg, int16_t *pitch)
{
return _MAV_RETURN_int16_t_array(msg, pitch, 6, 12);
return _MAV_RETURN_int16_t_array(msg, pitch, 4, 8);
}
/**
* @brief Get field yaw from set_quad_swarm_roll_pitch_yaw_thrust message
*
* @return Desired yaw angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @return Desired yaw angle in radians, scaled to int16 +-PI (+-32767)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_yaw(const mavlink_message_t* msg, int16_t *yaw)
{
return _MAV_RETURN_int16_t_array(msg, yaw, 6, 24);
return _MAV_RETURN_int16_t_array(msg, yaw, 4, 16);
}
/**
* @brief Get field thrust from set_quad_swarm_roll_pitch_yaw_thrust message
*
* @return Collective thrust, scaled to uint16 for 6 quadrotors: 0..5
* @return Collective thrust, scaled to uint16 (0..65535)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_thrust(const mavlink_message_t* msg, uint16_t *thrust)
{
return _MAV_RETURN_uint16_t_array(msg, thrust, 6, 36);
return _MAV_RETURN_uint16_t_array(msg, thrust, 4, 24);
}
/**
@ -229,8 +243,9 @@ static inline void mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(const
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_pitch(msg, set_quad_swarm_roll_pitch_yaw_thrust->pitch);
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_yaw(msg, set_quad_swarm_roll_pitch_yaw_thrust->yaw);
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_thrust(msg, set_quad_swarm_roll_pitch_yaw_thrust->thrust);
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_target_systems(msg, set_quad_swarm_roll_pitch_yaw_thrust->target_systems);
set_quad_swarm_roll_pitch_yaw_thrust->group = mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_group(msg);
set_quad_swarm_roll_pitch_yaw_thrust->mode = mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_mode(msg);
#else
memcpy(set_quad_swarm_roll_pitch_yaw_thrust, _MAV_PAYLOAD(msg), 54);
memcpy(set_quad_swarm_roll_pitch_yaw_thrust, _MAV_PAYLOAD(msg), 34);
#endif
}

View File

@ -2583,20 +2583,22 @@ static void mavlink_test_set_quad_swarm_roll_pitch_yaw_thrust(uint8_t system_id,
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet_in = {
{ 17235, 17236, 17237, 17238, 17239, 17240 },
{ 17859, 17860, 17861, 17862, 17863, 17864 },
{ 18483, 18484, 18485, 18486, 18487, 18488 },
{ 19107, 19108, 19109, 19110, 19111, 19112 },
{ 149, 150, 151, 152, 153, 154 },
{ 17235, 17236, 17237, 17238 },
{ 17651, 17652, 17653, 17654 },
{ 18067, 18068, 18069, 18070 },
{ 18483, 18484, 18485, 18486 },
101,
168,
};
mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.group = packet_in.group;
packet1.mode = packet_in.mode;
mav_array_memcpy(packet1.roll, packet_in.roll, sizeof(int16_t)*6);
mav_array_memcpy(packet1.pitch, packet_in.pitch, sizeof(int16_t)*6);
mav_array_memcpy(packet1.yaw, packet_in.yaw, sizeof(int16_t)*6);
mav_array_memcpy(packet1.thrust, packet_in.thrust, sizeof(uint16_t)*6);
mav_array_memcpy(packet1.target_systems, packet_in.target_systems, sizeof(uint8_t)*6);
mav_array_memcpy(packet1.roll, packet_in.roll, sizeof(int16_t)*4);
mav_array_memcpy(packet1.pitch, packet_in.pitch, sizeof(int16_t)*4);
mav_array_memcpy(packet1.yaw, packet_in.yaw, sizeof(int16_t)*4);
mav_array_memcpy(packet1.thrust, packet_in.thrust, sizeof(uint16_t)*4);
memset(&packet2, 0, sizeof(packet2));
@ -2605,12 +2607,12 @@ static void mavlink_test_set_quad_swarm_roll_pitch_yaw_thrust(uint8_t system_id,
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack(system_id, component_id, &msg , packet1.target_systems , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack(system_id, component_id, &msg , packet1.group , packet1.mode , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_systems , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.group , packet1.mode , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
@ -2623,7 +2625,7 @@ static void mavlink_test_set_quad_swarm_roll_pitch_yaw_thrust(uint8_t system_id,
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_send(MAVLINK_COMM_1 , packet1.target_systems , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_send(MAVLINK_COMM_1 , packet1.group , packet1.mode , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
@ -2685,6 +2687,65 @@ static void mavlink_test_nav_controller_output(uint8_t system_id, uint8_t compon
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_set_quad_swarm_led_roll_pitch_yaw_thrust(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t packet_in = {
{ 17235, 17236, 17237, 17238 },
{ 17651, 17652, 17653, 17654 },
{ 18067, 18068, 18069, 18070 },
{ 18483, 18484, 18485, 18486 },
101,
168,
{ 235, 236, 237, 238 },
{ 247, 248, 249, 250 },
{ 3, 4, 5, 6 },
};
mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.group = packet_in.group;
packet1.mode = packet_in.mode;
mav_array_memcpy(packet1.roll, packet_in.roll, sizeof(int16_t)*4);
mav_array_memcpy(packet1.pitch, packet_in.pitch, sizeof(int16_t)*4);
mav_array_memcpy(packet1.yaw, packet_in.yaw, sizeof(int16_t)*4);
mav_array_memcpy(packet1.thrust, packet_in.thrust, sizeof(uint16_t)*4);
mav_array_memcpy(packet1.led_red, packet_in.led_red, sizeof(uint8_t)*4);
mav_array_memcpy(packet1.led_blue, packet_in.led_blue, sizeof(uint8_t)*4);
mav_array_memcpy(packet1.led_green, packet_in.led_green, sizeof(uint8_t)*4);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack(system_id, component_id, &msg , packet1.group , packet1.mode , packet1.led_red , packet1.led_blue , packet1.led_green , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.group , packet1.mode , packet1.led_red , packet1.led_blue , packet1.led_green , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_send(MAVLINK_COMM_1 , packet1.group , packet1.mode , packet1.led_red , packet1.led_blue , packet1.led_green , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_state_correction(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
@ -3993,6 +4054,7 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink
mavlink_test_set_quad_motors_setpoint(system_id, component_id, last_msg);
mavlink_test_set_quad_swarm_roll_pitch_yaw_thrust(system_id, component_id, last_msg);
mavlink_test_nav_controller_output(system_id, component_id, last_msg);
mavlink_test_set_quad_swarm_led_roll_pitch_yaw_thrust(system_id, component_id, last_msg);
mavlink_test_state_correction(system_id, component_id, last_msg);
mavlink_test_request_data_stream(system_id, component_id, last_msg);
mavlink_test_data_stream(system_id, component_id, last_msg);

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Apr 30 11:40:12 2012"
#define MAVLINK_BUILD_DATE "Fri May 25 17:56:06 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101

View File

@ -87,7 +87,7 @@
<description>Breached minimum altitude</description>
</entry>
<entry name="FENCE_BREACH_MAXALT" value="2">
<description>Breached maximum altitude</description>
<description>Breached minimum altitude</description>
</entry>
<entry name="FENCE_BREACH_BOUNDARY" value="3">
<description>Breached fence boundary</description>
@ -149,7 +149,7 @@
<field name="iso" type="uint8_t">ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)</field>
<field name="exposure_type" type="uint8_t">Exposure type enumeration from 1 to N (0 means ignore)</field>
<field name="command_id" type="uint8_t">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once</field>
<field name="engine_cut_off" type="uint8_t">Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)</field>
<field name="engine_cut_off" type="uint8_t">Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)</field>
<field name="extra_param" type="uint8_t">Extra parameters enumeration (0 means ignore)</field>
<field name="extra_value" type="float">Correspondent value to given extra_param</field>
</message>

View File

@ -149,7 +149,7 @@
<field name="iso" type="uint8_t">ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)</field>
<field name="exposure_type" type="uint8_t">Exposure type enumeration from 1 to N (0 means ignore)</field>
<field name="command_id" type="uint8_t">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once</field>
<field name="engine_cut_off" type="uint8_t">Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)</field>
<field name="engine_cut_off" type="uint8_t">Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)</field>
<field name="extra_param" type="uint8_t">Extra parameters enumeration (0 means ignore)</field>
<field name="extra_value" type="float">Correspondent value to given extra_param</field>
</message>

View File

@ -93,6 +93,9 @@
<entry value="16" name="MAV_TYPE_FLAPPING_WING">
<description>Flapping wing</description>
</entry>
<entry value="17" name="MAV_TYPE_KITE">
<description>Flapping wing</description>
</entry>
</enum>
<!-- WARNING: MAV_ACTION Enum is no longer supported - has been removed. Please use MAV_CMD -->
<enum name="MAV_MODE_FLAG">
@ -748,7 +751,7 @@
<description>The Z or altitude value is out of range.</description>
</entry>
</enum>
<enum name="MAV_VAR">
<!--<enum name="MAV_VAR">
<description>type of a mavlink parameter</description>
<entry value="0" name="MAV_VAR_FLOAT">
<description>32 bit float</description>
@ -771,7 +774,7 @@
<entry value="6" name="MAV_VAR_INT32">
<description>32 bit signed integer</description>
</entry>
</enum>
</enum>-->
<enum name="MAV_RESULT">
<description>result from a mavlink command</description>
<entry value="0" name="MAV_RESULT_ACCEPTED">
@ -932,8 +935,8 @@
<description>Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="char[16]" name="param_id">Onboard parameter id</field>
<field type="int16_t" name="param_index">Parameter index. Send -1 to use the param ID field as identifier</field>
<field type="char[16]" name="param_id">Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string</field>
<field type="int16_t" name="param_index">Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)</field>
</message>
<message id="21" name="PARAM_REQUEST_LIST">
<description>Request all parameters of this component. After his request, all parameters are emitted.</description>
@ -942,9 +945,9 @@
</message>
<message id="22" name="PARAM_VALUE">
<description>Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout.</description>
<field type="char[16]" name="param_id">Onboard parameter id</field>
<field type="char[16]" name="param_id">Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string</field>
<field type="float" name="param_value">Onboard parameter value</field>
<field type="uint8_t" name="param_type">Onboard parameter type: see MAV_VAR enum</field>
<field type="uint8_t" name="param_type">Onboard parameter type: see MAVLINK_TYPE enum in mavlink/mavlink_types.h</field>
<field type="uint16_t" name="param_count">Total number of onboard parameters</field>
<field type="uint16_t" name="param_index">Index of this onboard parameter</field>
</message>
@ -952,9 +955,9 @@
<description>Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="char[16]" name="param_id">Onboard parameter id</field>
<field type="char[16]" name="param_id">Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string</field>
<field type="float" name="param_value">Onboard parameter value</field>
<field type="uint8_t" name="param_type">Onboard parameter type: see MAV_VAR enum</field>
<field type="uint8_t" name="param_type">Onboard parameter type: see MAVLINK_TYPE enum in mavlink/mavlink_types.h</field>
</message>
<message id="24" name="GPS_RAW_INT">
<description>The global position, as returned by the Global Positioning System (GPS). This is
@ -1291,12 +1294,13 @@
<field type="uint16_t" name="motor_left_sw">Left motor in + configuration, back left motor in x configuration</field>
</message>
<message id="61" name="SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST">
<description></description>
<field type="uint8_t[6]" name="target_systems">System IDs for 6 quadrotors: 0..5, the ID's are the MAVLink IDs</field>
<field type="int16_t[6]" name="roll">Desired roll angle in radians, scaled to int16 for 6 quadrotors: 0..5</field>
<field type="int16_t[6]" name="pitch">Desired pitch angle in radians, scaled to int16 for 6 quadrotors: 0..5</field>
<field type="int16_t[6]" name="yaw">Desired yaw angle in radians, scaled to int16 for 6 quadrotors: 0..5</field>
<field type="uint16_t[6]" name="thrust">Collective thrust, scaled to uint16 for 6 quadrotors: 0..5</field>
<description>Setpoint for up to four quadrotors in a group / wing</description>
<field type="uint8_t" name="group">ID of the quadrotor group (0 - 255, up to 256 groups supported)</field>
<field type="uint8_t" name="mode">ID of the flight mode (0 - 255, up to 256 modes supported)</field>
<field type="int16_t[4]" name="roll">Desired roll angle in radians +-PI (+-32767)</field>
<field type="int16_t[4]" name="pitch">Desired pitch angle in radians +-PI (+-32767)</field>
<field type="int16_t[4]" name="yaw">Desired yaw angle in radians, scaled to int16 +-PI (+-32767)</field>
<field type="uint16_t[4]" name="thrust">Collective thrust, scaled to uint16 (0..65535)</field>
</message>
<message id="62" name="NAV_CONTROLLER_OUTPUT">
<description>Outputs of the APM navigation controller. The primary use of this message is to check the response and signs of the controller before actual flight and to assist with tuning controller parameters.</description>
@ -1309,6 +1313,18 @@
<field type="float" name="aspd_error">Current airspeed error in meters/second</field>
<field type="float" name="xtrack_error">Current crosstrack error on x-y plane in meters</field>
</message>
<message id="63" name="SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST">
<description>Setpoint for up to four quadrotors in a group / wing</description>
<field type="uint8_t" name="group">ID of the quadrotor group (0 - 255, up to 256 groups supported)</field>
<field type="uint8_t" name="mode">ID of the flight mode (0 - 255, up to 256 modes supported)</field>
<field type="uint8_t[4]" name="led_red">RGB red channel (0-255)</field>
<field type="uint8_t[4]" name="led_blue">RGB green channel (0-255)</field>
<field type="uint8_t[4]" name="led_green">RGB blue channel (0-255)</field>
<field type="int16_t[4]" name="roll">Desired roll angle in radians +-PI (+-32767)</field>
<field type="int16_t[4]" name="pitch">Desired pitch angle in radians +-PI (+-32767)</field>
<field type="int16_t[4]" name="yaw">Desired yaw angle in radians, scaled to int16 +-PI (+-32767)</field>
<field type="uint16_t[4]" name="thrust">Collective thrust, scaled to uint16 (0..65535)</field>
</message>
<message id="64" name="STATE_CORRECTION">
<description>Corrects the systems state by adding an error correction term to the position and velocity, and by rotating the attitude by a correction angle.</description>
<field type="float" name="xErr">x position error</field>

View File

@ -8,6 +8,21 @@
<entry value="2" name="DATA_TYPE_RAW_IMAGE"/>
<entry value="3" name="DATA_TYPE_KINECT"/>
</enum>
<enum name="MAV_CMD">
<!-- 1-10000 reserved for common commands -->
<entry value="10001" name="MAV_CMD_DO_START_SEARCH">
<description>Starts a search</description>
<param index="1">1 to arm, 0 to disarm</param>
</entry>
<entry value="10002" name="MAV_CMD_DO_FINISH_SEARCH">
<description>Starts a search</description>
<param index="1">1 to arm, 0 to disarm</param>
</entry>
<entry value="10003" name="MAV_CMD_NAV_SWEEP">
<description>Starts a search</description>
<param index="1">1 to arm, 0 to disarm</param>
</entry>
</enum>
</enums>
<messages>
<message id="151" name="SET_CAM_SHUTTER">