Commit 53bd663d authored by PX4BuildBot's avatar PX4BuildBot

autogenerated headers for rev...

autogenerated headers for rev https://github.com/mavlink/mavlink/tree/ae6b70b692e7dfb4426087714bc6406b2ce31549
parent fb411385
......@@ -60,6 +60,7 @@ typedef enum MAV_CMD
MAV_CMD_NAV_VTOL_LAND=85, /* Land using VTOL mode |Empty| Empty| Empty| Yaw angle in degrees| Latitude| Longitude| Altitude| */
MAV_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_NAV_DELAY=93, /* Delay the next navigation command a number of seconds or until a specified time |Delay in seconds (decimal, -1 to enable time-of-day fields)| hour (24h format, UTC, -1 to ignore)| minute (24h format, UTC, -1 to ignore)| second (24h format, UTC)| Empty| Empty| Empty| */
MAV_CMD_NAV_PAYLOAD_PLACE=94, /* Descend and place payload. Vehicle descends until it detects a hanging payload has reached the ground, the gripper is opened to release the payload |Maximum distance to descend (meters)| Empty| Empty| Empty| Latitude (deg * 1E7)| Longitude (deg * 1E7)| Altitude (meters)| */
MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Mar 27 2017"
#define MAVLINK_BUILD_DATE "Wed Apr 05 2017"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
......@@ -76,6 +76,7 @@ typedef enum MAV_CMD
MAV_CMD_NAV_VTOL_LAND=85, /* Land using VTOL mode |Empty| Empty| Empty| Yaw angle in degrees| Latitude| Longitude| Altitude| */
MAV_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_NAV_DELAY=93, /* Delay the next navigation command a number of seconds or until a specified time |Delay in seconds (decimal, -1 to enable time-of-day fields)| hour (24h format, UTC, -1 to ignore)| minute (24h format, UTC, -1 to ignore)| second (24h format, UTC)| Empty| Empty| Empty| */
MAV_CMD_NAV_PAYLOAD_PLACE=94, /* Descend and place payload. Vehicle descends until it detects a hanging payload has reached the ground, the gripper is opened to release the payload |Maximum distance to descend (meters)| Empty| Empty| Empty| Latitude (deg * 1E7)| Longitude (deg * 1E7)| Altitude (meters)| */
MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
......@@ -663,7 +664,8 @@ typedef enum PID_TUNING_AXIS
PID_TUNING_YAW=3, /* | */
PID_TUNING_ACCZ=4, /* | */
PID_TUNING_STEER=5, /* | */
PID_TUNING_AXIS_ENUM_END=6, /* | */
PID_TUNING_LANDING=6, /* | */
PID_TUNING_AXIS_ENUM_END=7, /* | */
} PID_TUNING_AXIS;
#endif
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Mar 27 2017"
#define MAVLINK_BUILD_DATE "Wed Apr 05 2017"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
......@@ -104,6 +104,7 @@ typedef enum MAV_CMD
MAV_CMD_NAV_VTOL_LAND=85, /* Land using VTOL mode |Empty| Empty| Empty| Yaw angle in degrees| Latitude| Longitude| Altitude| */
MAV_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_NAV_DELAY=93, /* Delay the next navigation command a number of seconds or until a specified time |Delay in seconds (decimal, -1 to enable time-of-day fields)| hour (24h format, UTC, -1 to ignore)| minute (24h format, UTC, -1 to ignore)| second (24h format, UTC)| Empty| Empty| Empty| */
MAV_CMD_NAV_PAYLOAD_PLACE=94, /* Descend and place payload. Vehicle descends until it detects a hanging payload has reached the ground, the gripper is opened to release the payload |Maximum distance to descend (meters)| Empty| Empty| Empty| Latitude (deg * 1E7)| Longitude (deg * 1E7)| Altitude (meters)| */
MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Mar 27 2017"
#define MAVLINK_BUILD_DATE "Wed Apr 05 2017"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
#pragma once
#ifdef __cplusplus
#if defined(MAVLINK_USE_CXX_NAMESPACE)
namespace mavlink {
#elif defined(__cplusplus)
extern "C" {
#endif
......@@ -88,6 +90,6 @@ static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer
}
}
#ifdef __cplusplus
#if defined(MAVLINK_USE_CXX_NAMESPACE) || defined(__cplusplus)
}
#endif
......@@ -268,7 +268,8 @@ typedef enum MAV_SYS_STATUS_SENSOR
MAV_SYS_STATUS_TERRAIN=4194304, /* 0x400000 Terrain subsystem health | */
MAV_SYS_STATUS_REVERSE_MOTOR=8388608, /* 0x800000 Motors are reversed | */
MAV_SYS_STATUS_LOGGING=16777216, /* 0x1000000 Logging | */
MAV_SYS_STATUS_SENSOR_ENUM_END=16777217, /* | */
MAV_SYS_STATUS_SENSOR_BATTERY=33554432, /* 0x2000000 Battery | */
MAV_SYS_STATUS_SENSOR_ENUM_END=33554433, /* | */
} MAV_SYS_STATUS_SENSOR;
#endif
......@@ -375,6 +376,7 @@ typedef enum MAV_CMD
MAV_CMD_NAV_VTOL_LAND=85, /* Land using VTOL mode |Empty| Empty| Empty| Yaw angle in degrees| Latitude| Longitude| Altitude| */
MAV_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_NAV_DELAY=93, /* Delay the next navigation command a number of seconds or until a specified time |Delay in seconds (decimal, -1 to enable time-of-day fields)| hour (24h format, UTC, -1 to ignore)| minute (24h format, UTC, -1 to ignore)| second (24h format, UTC)| Empty| Empty| Empty| */
MAV_CMD_NAV_PAYLOAD_PLACE=94, /* Descend and place payload. Vehicle descends until it detects a hanging payload has reached the ground, the gripper is opened to release the payload |Maximum distance to descend (meters)| Empty| Empty| Empty| Latitude (deg * 1E7)| Longitude (deg * 1E7)| Altitude (meters)| */
MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
......
......@@ -5,7 +5,7 @@
MAVPACKED(
typedef struct __mavlink_gps_rtcm_data_t {
uint8_t flags; /*< LSB: 1 means message is fragmented*/
uint8_t flags; /*< LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order.*/
uint8_t len; /*< data length*/
uint8_t data[180]; /*< RTCM message (may be fragmented)*/
}) mavlink_gps_rtcm_data_t;
......@@ -47,7 +47,7 @@ typedef struct __mavlink_gps_rtcm_data_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param flags LSB: 1 means message is fragmented
* @param flags LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order.
* @param len data length
* @param data RTCM message (may be fragmented)
* @return length of the message in bytes (excluding serial stream start sign)
......@@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_gps_rtcm_data_pack(uint8_t system_id, uint8_t
* @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 flags LSB: 1 means message is fragmented
* @param flags LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order.
* @param len data length
* @param data RTCM message (may be fragmented)
* @return length of the message in bytes (excluding serial stream start sign)
......@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_gps_rtcm_data_encode_chan(uint8_t system_id,
* @brief Send a gps_rtcm_data message
* @param chan MAVLink channel to send the message
*
* @param flags LSB: 1 means message is fragmented
* @param flags LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order.
* @param len data length
* @param data RTCM message (may be fragmented)
*/
......@@ -208,7 +208,7 @@ static inline void mavlink_msg_gps_rtcm_data_send_buf(mavlink_message_t *msgbuf,
/**
* @brief Get field flags from gps_rtcm_data message
*
* @return LSB: 1 means message is fragmented
* @return LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order.
*/
static inline uint8_t mavlink_msg_gps_rtcm_data_get_flags(const mavlink_message_t* msg)
{
......
......@@ -13,11 +13,13 @@ typedef struct __mavlink_optical_flow_t {
int16_t flow_y; /*< Flow in pixels * 10 in y-sensor direction (dezi-pixels)*/
uint8_t sensor_id; /*< Sensor ID*/
uint8_t quality; /*< Optical flow quality / confidence. 0: bad, 255: maximum quality*/
float flow_rate_x; /*< Flow rate in radians/second about X axis*/
float flow_rate_y; /*< Flow rate in radians/second about Y axis*/
}) mavlink_optical_flow_t;
#define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 26
#define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 34
#define MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN 26
#define MAVLINK_MSG_ID_100_LEN 26
#define MAVLINK_MSG_ID_100_LEN 34
#define MAVLINK_MSG_ID_100_MIN_LEN 26
#define MAVLINK_MSG_ID_OPTICAL_FLOW_CRC 175
......@@ -29,7 +31,7 @@ typedef struct __mavlink_optical_flow_t {
#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \
100, \
"OPTICAL_FLOW", \
8, \
10, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \
{ "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \
{ "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \
......@@ -38,12 +40,14 @@ typedef struct __mavlink_optical_flow_t {
{ "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \
{ "flow_rate_x", NULL, MAVLINK_TYPE_FLOAT, 0, 26, offsetof(mavlink_optical_flow_t, flow_rate_x) }, \
{ "flow_rate_y", NULL, MAVLINK_TYPE_FLOAT, 0, 30, offsetof(mavlink_optical_flow_t, flow_rate_y) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \
"OPTICAL_FLOW", \
8, \
10, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \
{ "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \
{ "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \
......@@ -52,6 +56,8 @@ typedef struct __mavlink_optical_flow_t {
{ "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \
{ "flow_rate_x", NULL, MAVLINK_TYPE_FLOAT, 0, 26, offsetof(mavlink_optical_flow_t, flow_rate_x) }, \
{ "flow_rate_y", NULL, MAVLINK_TYPE_FLOAT, 0, 30, offsetof(mavlink_optical_flow_t, flow_rate_y) }, \
} \
}
#endif
......@@ -70,10 +76,12 @@ typedef struct __mavlink_optical_flow_t {
* @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
* @param flow_rate_x Flow rate in radians/second about X axis
* @param flow_rate_y Flow rate in radians/second about Y axis
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance)
uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance, float flow_rate_x, float flow_rate_y)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN];
......@@ -85,6 +93,8 @@ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t
_mav_put_int16_t(buf, 22, flow_y);
_mav_put_uint8_t(buf, 24, sensor_id);
_mav_put_uint8_t(buf, 25, quality);
_mav_put_float(buf, 26, flow_rate_x);
_mav_put_float(buf, 30, flow_rate_y);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
#else
......@@ -97,6 +107,8 @@ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t
packet.flow_y = flow_y;
packet.sensor_id = sensor_id;
packet.quality = quality;
packet.flow_rate_x = flow_rate_x;
packet.flow_rate_y = flow_rate_y;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
#endif
......@@ -119,11 +131,13 @@ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t
* @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
* @param flow_rate_x Flow rate in radians/second about X axis
* @param flow_rate_y Flow rate in radians/second about Y axis
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,uint8_t sensor_id,int16_t flow_x,int16_t flow_y,float flow_comp_m_x,float flow_comp_m_y,uint8_t quality,float ground_distance)
uint64_t time_usec,uint8_t sensor_id,int16_t flow_x,int16_t flow_y,float flow_comp_m_x,float flow_comp_m_y,uint8_t quality,float ground_distance,float flow_rate_x,float flow_rate_y)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN];
......@@ -135,6 +149,8 @@ static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uin
_mav_put_int16_t(buf, 22, flow_y);
_mav_put_uint8_t(buf, 24, sensor_id);
_mav_put_uint8_t(buf, 25, quality);
_mav_put_float(buf, 26, flow_rate_x);
_mav_put_float(buf, 30, flow_rate_y);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
#else
......@@ -147,6 +163,8 @@ static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uin
packet.flow_y = flow_y;
packet.sensor_id = sensor_id;
packet.quality = quality;
packet.flow_rate_x = flow_rate_x;
packet.flow_rate_y = flow_rate_y;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
#endif
......@@ -165,7 +183,7 @@ static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uin
*/
static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow)
{
return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance);
return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance, optical_flow->flow_rate_x, optical_flow->flow_rate_y);
}
/**
......@@ -179,7 +197,7 @@ static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_
*/
static inline uint16_t mavlink_msg_optical_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow)
{
return mavlink_msg_optical_flow_pack_chan(system_id, component_id, chan, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance);
return mavlink_msg_optical_flow_pack_chan(system_id, component_id, chan, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance, optical_flow->flow_rate_x, optical_flow->flow_rate_y);
}
/**
......@@ -194,10 +212,12 @@ static inline uint16_t mavlink_msg_optical_flow_encode_chan(uint8_t system_id, u
* @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
* @param flow_rate_x Flow rate in radians/second about X axis
* @param flow_rate_y Flow rate in radians/second about Y axis
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance)
static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance, float flow_rate_x, float flow_rate_y)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN];
......@@ -209,6 +229,8 @@ static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_
_mav_put_int16_t(buf, 22, flow_y);
_mav_put_uint8_t(buf, 24, sensor_id);
_mav_put_uint8_t(buf, 25, quality);
_mav_put_float(buf, 26, flow_rate_x);
_mav_put_float(buf, 30, flow_rate_y);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
#else
......@@ -221,6 +243,8 @@ static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_
packet.flow_y = flow_y;
packet.sensor_id = sensor_id;
packet.quality = quality;
packet.flow_rate_x = flow_rate_x;
packet.flow_rate_y = flow_rate_y;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
#endif
......@@ -234,7 +258,7 @@ static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_
static inline void mavlink_msg_optical_flow_send_struct(mavlink_channel_t chan, const mavlink_optical_flow_t* optical_flow)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_optical_flow_send(chan, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance);
mavlink_msg_optical_flow_send(chan, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance, optical_flow->flow_rate_x, optical_flow->flow_rate_y);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)optical_flow, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
#endif
......@@ -248,7 +272,7 @@ static inline void mavlink_msg_optical_flow_send_struct(mavlink_channel_t chan,
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_optical_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance)
static inline void mavlink_msg_optical_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance, float flow_rate_x, float flow_rate_y)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
......@@ -260,6 +284,8 @@ static inline void mavlink_msg_optical_flow_send_buf(mavlink_message_t *msgbuf,
_mav_put_int16_t(buf, 22, flow_y);
_mav_put_uint8_t(buf, 24, sensor_id);
_mav_put_uint8_t(buf, 25, quality);
_mav_put_float(buf, 26, flow_rate_x);
_mav_put_float(buf, 30, flow_rate_y);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
#else
......@@ -272,6 +298,8 @@ static inline void mavlink_msg_optical_flow_send_buf(mavlink_message_t *msgbuf,
packet->flow_y = flow_y;
packet->sensor_id = sensor_id;
packet->quality = quality;
packet->flow_rate_x = flow_rate_x;
packet->flow_rate_y = flow_rate_y;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
#endif
......@@ -363,6 +391,26 @@ static inline float mavlink_msg_optical_flow_get_ground_distance(const mavlink_m
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field flow_rate_x from optical_flow message
*
* @return Flow rate in radians/second about X axis
*/
static inline float mavlink_msg_optical_flow_get_flow_rate_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 26);
}
/**
* @brief Get field flow_rate_y from optical_flow message
*
* @return Flow rate in radians/second about Y axis
*/
static inline float mavlink_msg_optical_flow_get_flow_rate_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 30);
}
/**
* @brief Decode a optical_flow message into a struct
*
......@@ -380,6 +428,8 @@ static inline void mavlink_msg_optical_flow_decode(const mavlink_message_t* msg,
optical_flow->flow_y = mavlink_msg_optical_flow_get_flow_y(msg);
optical_flow->sensor_id = mavlink_msg_optical_flow_get_sensor_id(msg);
optical_flow->quality = mavlink_msg_optical_flow_get_quality(msg);
optical_flow->flow_rate_x = mavlink_msg_optical_flow_get_flow_rate_x(msg);
optical_flow->flow_rate_y = mavlink_msg_optical_flow_get_flow_rate_y(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_OPTICAL_FLOW_LEN? msg->len : MAVLINK_MSG_ID_OPTICAL_FLOW_LEN;
memset(optical_flow, 0, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
......
......@@ -4156,7 +4156,7 @@ static void mavlink_test_optical_flow(uint8_t system_id, uint8_t component_id, m
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_optical_flow_t packet_in = {
93372036854775807ULL,73.0,101.0,129.0,18275,18379,77,144
93372036854775807ULL,73.0,101.0,129.0,18275,18379,77,144,199.0,227.0
};
mavlink_optical_flow_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
......@@ -4168,6 +4168,8 @@ static void mavlink_test_optical_flow(uint8_t system_id, uint8_t component_id, m
packet1.flow_y = packet_in.flow_y;
packet1.sensor_id = packet_in.sensor_id;
packet1.quality = packet_in.quality;
packet1.flow_rate_x = packet_in.flow_rate_x;
packet1.flow_rate_y = packet_in.flow_rate_y;
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
......@@ -4182,12 +4184,12 @@ static void mavlink_test_optical_flow(uint8_t system_id, uint8_t component_id, m
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_optical_flow_pack(system_id, component_id, &msg , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance );
mavlink_msg_optical_flow_pack(system_id, component_id, &msg , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance , packet1.flow_rate_x , packet1.flow_rate_y );
mavlink_msg_optical_flow_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_optical_flow_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance );
mavlink_msg_optical_flow_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance , packet1.flow_rate_x , packet1.flow_rate_y );
mavlink_msg_optical_flow_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
......@@ -4200,7 +4202,7 @@ static void mavlink_test_optical_flow(uint8_t system_id, uint8_t component_id, m
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_optical_flow_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance );
mavlink_msg_optical_flow_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance , packet1.flow_rate_x , packet1.flow_rate_y );
mavlink_msg_optical_flow_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Mar 27 2017"
#define MAVLINK_BUILD_DATE "Wed Apr 05 2017"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
......@@ -77,6 +77,7 @@ typedef enum MAV_CMD
MAV_CMD_NAV_VTOL_LAND=85, /* Land using VTOL mode |Empty| Empty| Empty| Yaw angle in degrees| Latitude| Longitude| Altitude| */
MAV_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_NAV_DELAY=93, /* Delay the next navigation command a number of seconds or until a specified time |Delay in seconds (decimal, -1 to enable time-of-day fields)| hour (24h format, UTC, -1 to ignore)| minute (24h format, UTC, -1 to ignore)| second (24h format, UTC)| Empty| Empty| Empty| */
MAV_CMD_NAV_PAYLOAD_PLACE=94, /* Descend and place payload. Vehicle descends until it detects a hanging payload has reached the ground, the gripper is opened to release the payload |Maximum distance to descend (meters)| Empty| Empty| Empty| Latitude (deg * 1E7)| Longitude (deg * 1E7)| Altitude (meters)| */
MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Mar 27 2017"
#define MAVLINK_BUILD_DATE "Wed Apr 05 2017"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
......@@ -12,6 +12,10 @@
#include "mavlink_sha256.h"
#ifdef MAVLINK_USE_CXX_NAMESPACE
namespace mavlink {
#endif
/*
* Internal function to give access to the channel status for each channel
*/
......@@ -195,10 +199,9 @@ MAVLINK_HELPER bool mavlink_signature_check(mavlink_signing_t *signing,
* @param system_id Id of the sending (this) system, 1-127
* @param length Message length
*/
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t chan, uint8_t min_length, uint8_t length, uint8_t crc_extra)
MAVLINK_HELPER uint16_t mavlink_finalize_message_buffer(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
mavlink_status_t* status, uint8_t min_length, uint8_t length, uint8_t crc_extra)
{
mavlink_status_t *status = mavlink_get_channel_status(chan);
bool mavlink1 = (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) != 0;
bool signing = (!mavlink1) && status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING);
uint8_t signature_len = signing? MAVLINK_SIGNATURE_BLOCK_LEN : 0;
......@@ -257,6 +260,12 @@ MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, ui
return msg->len + header_len + 2 + signature_len;
}
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t chan, uint8_t min_length, uint8_t length, uint8_t crc_extra)
{
mavlink_status_t *status = mavlink_get_channel_status(chan);
return mavlink_finalize_message_buffer(msg, system_id, component_id, status, min_length, length, crc_extra);
}
/**
* @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel
......@@ -367,7 +376,7 @@ MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_m
signature_len = 0;
MAVLINK_START_UART_SEND(chan, header_len + msg->len + 2 + signature_len);
// we can't send the structure directly as it has extra mavlink2 elements in it
uint8_t buf[header_len];
uint8_t buf[MAVLINK_CORE_HEADER_MAVLINK1_LEN + 1];
buf[0] = msg->magic;
buf[1] = msg->len;
buf[2] = msg->seq;
......@@ -379,7 +388,7 @@ MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_m
header_len = MAVLINK_CORE_HEADER_LEN + 1;
signature_len = (msg->incompat_flags & MAVLINK_IFLAG_SIGNED)?MAVLINK_SIGNATURE_BLOCK_LEN:0;
MAVLINK_START_UART_SEND(chan, header_len + msg->len + 2 + signature_len);
uint8_t buf[header_len];
uint8_t buf[MAVLINK_CORE_HEADER_LEN + 1];
buf[0] = msg->magic;
buf[1] = msg->len;
buf[2] = msg->incompat_flags;
......@@ -470,6 +479,7 @@ MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
/*
return the crc_entry value for a msgid
*/
#ifndef MAVLINK_GET_MSG_ENTRY
MAVLINK_HELPER const mavlink_msg_entry_t *mavlink_get_msg_entry(uint32_t msgid)
{
static const mavlink_msg_entry_t mavlink_message_crcs[] = MAVLINK_MESSAGE_CRCS;
......@@ -497,6 +507,7 @@ MAVLINK_HELPER const mavlink_msg_entry_t *mavlink_get_msg_entry(uint32_t msgid)
}
return &mavlink_message_crcs[low];
}
#endif // MAVLINK_GET_MSG_ENTRY
/*
return the crc_extra value for a message
......@@ -737,17 +748,26 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
status->msg_received = MAVLINK_FRAMING_OK;
}
rxmsg->ck[1] = c;
if (rxmsg->incompat_flags & MAVLINK_IFLAG_SIGNED) {
status->parse_state = MAVLINK_PARSE_STATE_SIGNATURE_WAIT;
status->signature_wait = MAVLINK_SIGNATURE_BLOCK_LEN;
// If the CRC is already wrong, don't overwrite msg_received,
// otherwise we can end up with garbage flagged as valid.
if (status->msg_received != MAVLINK_FRAMING_BAD_CRC) {
status->msg_received = MAVLINK_FRAMING_INCOMPLETE;
}
} else {
if (status->signing &&
(status->signing->accept_unsigned_callback == NULL ||
!status->signing->accept_unsigned_callback(status, rxmsg->msgid))) {
// don't accept this unsigned packet
// If the CRC is already wrong, don't overwrite msg_received.
if (status->msg_received != MAVLINK_FRAMING_BAD_CRC) {
status->msg_received = MAVLINK_FRAMING_BAD_SIGNATURE;
}
}
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
}
......@@ -1094,5 +1114,6 @@ MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf,
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
#ifdef MAVLINK_USE_CXX_NAMESPACE
} // namespace mavlink
#endif
......@@ -42,6 +42,10 @@
*/
#ifndef HAVE_MAVLINK_SHA256
#ifdef MAVLINK_USE_CXX_NAMESPACE
namespace mavlink {
#endif
#ifndef MAVLINK_HELPER
#define MAVLINK_HELPER
#endif
......@@ -241,4 +245,8 @@ MAVLINK_HELPER void mavlink_sha256_final_48(mavlink_sha256_ctx *m, uint8_t resul
#undef sigma0
#undef sigma1
#ifdef MAVLINK_USE_CXX_NAMESPACE
} // namespace mavlink
#endif
#endif // HAVE_MAVLINK_SHA256
......@@ -8,6 +8,10 @@
#include <stdbool.h>
#include <stdint.h>
#ifdef MAVLINK_USE_CXX_NAMESPACE
namespace mavlink {
#endif
// Macro to define packed structures
#ifdef __GNUC__
#define MAVPACKED( __Declaration__ ) __Declaration__ __attribute__((packed))
......@@ -289,4 +293,6 @@ typedef struct __mavlink_msg_entry {
#define MAVLINK_IFLAG_SIGNED 0x01
#define MAVLINK_IFLAG_MASK 0x01 // mask of all understood bits
#ifdef MAVLINK_USE_CXX_NAMESPACE
} // namespace mavlink
#endif
......@@ -807,6 +807,7 @@
<entry name="PID_TUNING_YAW" value="3"/>
<entry name="PID_TUNING_ACCZ" value="4"/>
<entry name="PID_TUNING_STEER" value="5"/>
<entry name="PID_TUNING_LANDING" value="6"/>
</enum>
<enum name="MAG_CAL_STATUS">
<entry name="MAG_CAL_NOT_STARTED" value="0"/>
......@@ -1081,7 +1082,7 @@
<!-- Path planned landings are still in the future, but we want these fields ready: -->
<field name="break_alt" type="int16_t">Break altitude in meters relative to home</field>
<field name="land_dir" type="uint16_t">Heading to aim for when landing. In centi-degrees.</field>
<field name="flags" type="uint8_t">See RALLY_FLAGS enum for definition of the bitmask.</field>
<field name="flags" type="uint8_t" enum="RALLY_FLAGS">See RALLY_FLAGS enum for definition of the bitmask.</field>
</message>
<message id="176" name="RALLY_FETCH_POINT">
<description>Request a current rally point from MAV. MAV should respond with a RALLY_POINT message. MAV should not respond if the request is invalid.</description>
......@@ -1118,7 +1119,7 @@
<!-- component ID, to support multiple cameras -->
<field name="img_idx" type="uint16_t">Image index</field>
<!-- per camera image index, should be unique+sequential within a mission, preferably non-wrapping -->
<field name="event_id" type="uint8_t">See CAMERA_STATUS_TYPES enum for definition of the bitmask</field>
<field name="event_id" type="uint8_t" enum="CAMERA_STATUS_TYPES">See CAMERA_STATUS_TYPES enum for definition of the bitmask</field>
<field name="p1" type="float">Parameter 1 (meaning depends on event, see CAMERA_STATUS_TYPES enum)</field>
<field name="p2" type="float">Parameter 2 (meaning depends on event, see CAMERA_STATUS_TYPES enum)</field>
<field name="p3" type="float">Parameter 3 (meaning depends on event, see CAMERA_STATUS_TYPES enum)</field>
......@@ -1146,7 +1147,7 @@
<!-- initially only supporting fixed cameras, in future we'll need feedback messages from the gimbal so we can include that offset here -->
<field name="foc_len" type="float">Focal Length (mm)</field>
<!-- per-image to support zooms. Zero means fixed focal length or unknown. Should be true mm, not scaled to 35mm film equivalent -->
<field name="flags" type="uint8_t">See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask</field>
<field name="flags" type="uint8_t" enum="CAMERA_FEEDBACK_FLAGS">See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask</field>
<!-- future proofing -->
</message>
<message id="181" name="BATTERY2">
......@@ -1200,7 +1201,7 @@
<description>Reports progress of compass calibration.</description>
<field name="compass_id" type="uint8_t">Compass being calibrated</field>
<field name="cal_mask" type="uint8_t">Bitmask of compasses being calibrated</field>
<field name="cal_status" type="uint8_t">Status (see MAG_CAL_STATUS enum)</field>
<field name="cal_status" type="uint8_t" enum="MAG_CAL_STATUS">Status (see MAG_CAL_STATUS enum)</field>
<field name="attempt" type="uint8_t">Attempt number</field>
<field name="completion_pct" type="uint8_t">Completion percentage</field>
<field name="completion_mask" type="uint8_t[10]">Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid)</field>
......@@ -1212,7 +1213,7 @@
<description>Reports results of completed compass calibration. Sent until MAG_CAL_ACK received.</description>
<field name="compass_id" type="uint8_t">Compass being calibrated</field>
<field name="cal_mask" type="uint8_t">Bitmask of compasses being calibrated</field>
<field name="cal_status" type="uint8_t">Status (see MAG_CAL_STATUS enum)</field>
<field name="cal_status" type="uint8_t" enum="MAG_CAL_STATUS">Status (see MAG_CAL_STATUS enum)</field>
<field name="autosaved" type="uint8_t">0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters</field>
<field name="fitness" type="float">RMS milligauss residuals</field>
<field name="ofs_x" type="float">X offset</field>
......@@ -1228,7 +1229,7 @@
<!-- EKF status message from autopilot to GCS. -->
<message id="193" name="EKF_STATUS_REPORT">
<description>EKF Status message including flags and variances</description>
<field name="flags" type="uint16_t">Flags</field>
<field name="flags" type="uint16_t" enum="EKF_STATUS_FLAGS">Flags</field>
<!-- supported flags see EKF_STATUS_FLAGS enum -->
<field name="velocity_variance" type="float">Velocity variance</field>
<!-- below 0.5 is good, 0.5~0.79 is warning, 0.8 or higher is bad -->
......@@ -1284,7 +1285,7 @@
<description>Heartbeat from a HeroBus attached GoPro</description>
<field enum="GOPRO_HEARTBEAT_STATUS" name="status" type="uint8_t">Status</field>
<field enum="GOPRO_CAPTURE_MODE" name="capture_mode" type="uint8_t">Current capture mode</field>
<field name="flags" type="uint8_t">additional status bits</field>
<field name="flags" type="uint8_t" enum="GOPRO_HEARTBEAT_FLAGS">additional status bits</field>
<!-- see GOPRO_HEARTBEAT_FLAGS -->
</message>
<message id="216" name="GOPRO_GET_REQUEST">
......
......@@ -473,6 +473,9 @@
<entry value="16777216" name="MAV_SYS_STATUS_LOGGING">
<description>0x1000000 Logging</description>
</entry>
<entry value="33554432" name="MAV_SYS_STATUS_SENSOR_BATTERY">
<description>0x2000000 Battery</description>
</entry>
</enum>
<enum name="MAV_FRAME">
<entry value="0" name="MAV_FRAME_GLOBAL">
......@@ -799,6 +802,16 @@
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="94" name="MAV_CMD_NAV_PAYLOAD_PLACE">
<description>Descend and place payload. Vehicle descends until it detects a hanging payload has reached the ground, the gripper is opened to release the payload</description>
<param index="1">Maximum distance to descend (meters)</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Latitude (deg * 1E7)</param>
<param index="6">Longitude (deg * 1E7)</param>
<param index="7">Altitude (meters)</param>
</entry>
<entry value="95" name="MAV_CMD_NAV_LAST">
<description>NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration</description>
<param index="1">Empty</param>
......@@ -2412,18 +2425,18 @@
<messages>
<message id="0" name="HEARTBEAT">
<description>The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).</description>
<field type="uint8_t" name="type">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field>
<field type="uint8_t" name="autopilot">Autopilot type / class. defined in MAV_AUTOPILOT ENUM</field>
<field type="uint8_t" name="base_mode">System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h</field>
<field type="uint8_t" name="type" enum="MAV_TYPE">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field>
<field type="uint8_t" name="autopilot" enum="MAV_AUTOPILOT">Autopilot type / class. defined in MAV_AUTOPILOT ENUM</field>
<field type="uint8_t" name="base_mode" enum="MAV_MODE_FLAG">System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h</field>
<field type="uint32_t" name="custom_mode">A bitfield for use for autopilot-specific flags.</field>
<field type="uint8_t" name="system_status">System status flag, see MAV_STATE ENUM</field>
<field type="uint8_t" name="system_status" enum="MAV_STATE">System status flag, see MAV_STATE ENUM</field>
<field type="uint8_t_mavlink_version" name="mavlink_version">MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version</field>
</message>
<message id="1" name="SYS_STATUS">
<description>The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout.</description>
<field type="uint32_t" name="onboard_control_sensors_present" print_format="0x%04x">Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR</field>
<field type="uint32_t" name="onboard_control_sensors_enabled" print_format="0x%04x">Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR</field>
<field type="uint32_t" name="onboard_control_sensors_health" print_format="0x%04x">Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR</field>
<field type="uint32_t" name="onboard_control_sensors_present" enum="MAV_SYS_STATUS_SENSOR" print_format="0x%04x">Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR</field>
<field type="uint32_t" name="onboard_control_sensors_enabled" enum="MAV_SYS_STATUS_SENSOR" print_format="0x%04x">Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR</field>
<field type="uint32_t" name="onboard_control_sensors_health" enum="MAV_SYS_STATUS_SENSOR" print_format="0x%04x">Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR</field>
<field type="uint16_t" name="load">Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000</field>
<field type="uint16_t" name="voltage_battery">Battery voltage, in millivolts (1 = 1 millivolt)</field>
<field type="int16_t" name="current_battery">Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current</field>
......@@ -2665,7 +2678,7 @@
<field type="int16_t" name="start_index">Start index, 0 by default</field>
<field type="int16_t" name="end_index">End index, -1 by default (-1: send list to end). Else a valid index of the list</field>
<extensions/>
<field type="uint8_t" name="mission_type">Mission type, see MAV_MISSION_TYPE</field>
<field type="uint8_t" name="mission_type" enum="MAV_MISSION_TYPE">Mission type, see MAV_MISSION_TYPE</field>
</message>
<message id="38" name="MISSION_WRITE_PARTIAL_LIST">
<description>This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED!</description>
......@@ -2674,7 +2687,7 @@
<field type="int16_t" name="start_index">Start index, 0 by default and smaller / equal to the largest index of the current onboard list.</field>
<field type="int16_t" name="end_index">End index, equal or greater than start index.</field>
<extensions/>
<field type="uint8_t" name="mission_type">Mission type, see MAV_MISSION_TYPE</field>
<field type="uint8_t" name="mission_type" enum="MAV_MISSION_TYPE">Mission type, see MAV_MISSION_TYPE</field>
</message>
<message id="39" name="MISSION_ITEM">
<description>Message encoding a mission item. This message is emitted to announce
......@@ -2682,8 +2695,8 @@
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint16_t" name="seq">Sequence</field>
<field type="uint8_t" name="frame">The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h</field>
<field type="uint16_t" name="command">The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs</field>
<field type="uint8_t" name="frame" enum="MAV_FRAME">The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h</field>
<field type="uint16_t" name="command" enum="MAV_CMD">The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs</field>
<field type="uint8_t" name="current">false:0, true:1</field>
<field type="uint8_t" name="autocontinue">autocontinue to next wp</field>
<field type="float" name="param1">PARAM1, see MAV_CMD enum</field>
......@@ -2694,7 +2707,7 @@
<field type="float" name="y">PARAM6 / y position: global: longitude</field>
<field type="float" name="z">PARAM7 / z position: global: altitude (relative or absolute, depending on frame.</field>
<extensions/>
<field type="uint8_t" name="mission_type">Mission type, see MAV_MISSION_TYPE</field>
<field type="uint8_t" name="mission_type" enum="MAV_MISSION_TYPE">Mission type, see MAV_MISSION_TYPE</field>
</message>
<message id="40" name="MISSION_REQUEST">
<description>Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. http://qgroundcontrol.org/mavlink/waypoint_protocol</description>
......@@ -2702,7 +2715,7 @@
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint16_t" name="seq">Sequence</field>
<extensions/>
<field type="uint8_t" name="mission_type">Mission type, see MAV_MISSION_TYPE</field>
<field type="uint8_t" name="mission_type" enum="MAV_MISSION_TYPE">Mission type, see MAV_MISSION_TYPE</field>
</message>
<message id="41" name="MISSION_SET_CURRENT">
<description>Set the mission item with sequence number seq as current item. This means that the MAV will continue to this mission item on the shortest path (not following the mission items in-between).</description>
......@@ -2719,7 +2732,7 @@
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<extensions/>
<field type="uint8_t" name="mission_type">Mission type, see MAV_MISSION_TYPE</field>
<field type="uint8_t" name="mission_type" enum="MAV_MISSION_TYPE">Mission type, see MAV_MISSION_TYPE</field>
</message>
<message id="44" name="MISSION_COUNT">
<description>This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of MISSIONs.</description>
......@@ -2727,14 +2740,14 @@
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint16_t" name="count">Number of mission items in the sequence</field>
<extensions/>
<field type="uint8_t" name="mission_type">Mission type, see MAV_MISSION_TYPE</field>
<field type="uint8_t" name="mission_type" enum="MAV_MISSION_TYPE">Mission type, see MAV_MISSION_TYPE</field>
</message>
<message id="45" name="MISSION_CLEAR_ALL">
<description>Delete all mission items at once.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<extensions/>
<field type="uint8_t" name="mission_type">Mission type, see MAV_MISSION_TYPE</field>
<field type="uint8_t" name="mission_type" enum="MAV_MISSION_TYPE">Mission type, see MAV_MISSION_TYPE</field>
</message>
<message id="46" name="MISSION_ITEM_REACHED">
<description>A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next MISSION.</description>
......@@ -2746,7 +2759,7 @@
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint8_t" name="type" enum="MAV_MISSION_RESULT">See MAV_MISSION_RESULT enum</field>
<extensions/>
<field type="uint8_t" name="mission_type">Mission type, see MAV_MISSION_TYPE</field>
<field type="uint8_t" name="mission_type" enum="MAV_MISSION_TYPE">Mission type, see MAV_MISSION_TYPE</field>
</message>
<message id="48" name="SET_GPS_GLOBAL_ORIGIN">
<description>As local waypoints exist, the global MISSION reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor.</description>
......@@ -2779,7 +2792,7 @@
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint16_t" name="seq">Sequence</field>
<extensions/>
<field type="uint8_t" name="mission_type">Mission type, see MAV_MISSION_TYPE</field>
<field type="uint8_t" name="mission_type" enum="MAV_MISSION_TYPE">Mission type, see MAV_MISSION_TYPE</field>
</message>
<message id="54" name="SAFETY_SET_ALLOWED_AREA">
<description>Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/MISSIONs to accept and which to reject. Safety areas are often enforced by national or competition regulations.</description>
......@@ -2917,8 +2930,8 @@
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint16_t" name="seq">Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).</field>
<field type="uint8_t" name="frame">The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h</field>
<field type="uint16_t" name="command">The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs</field>
<field type="uint8_t" name="frame" enum="MAV_FRAME">The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h</field>
<field type="uint16_t" name="command" enum="MAV_CMD">The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs</field>
<field type="uint8_t" name="current">false:0, true:1</field>
<field type="uint8_t" name="autocontinue">autocontinue to next wp</field>
<field type="float" name="param1">PARAM1, see MAV_CMD enum</field>
......@@ -2929,7 +2942,7 @@
<field type="int32_t" name="y">PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7</field>
<field type="float" name="z">PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.</field>
<extensions/>
<field type="uint8_t" name="mission_type">Mission type, see MAV_MISSION_TYPE</field>
<field type="uint8_t" name="mission_type" enum="MAV_MISSION_TYPE">Mission type, see MAV_MISSION_TYPE</field>
</message>
<message id="74" name="VFR_HUD">
<description>Metrics typically displayed on a HUD for fixed wing aircraft</description>
......@@ -2944,8 +2957,8 @@
<description>Message encoding a command with parameters as scaled integers. Scaling depends on the actual command value.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint8_t" name="frame">The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h</field>
<field type="uint16_t" name="command">The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs</field>
<field type="uint8_t" name="frame" enum="MAV_FRAME">The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h</field>
<field type="uint16_t" name="command" enum="MAV_CMD">The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs</field>
<field type="uint8_t" name="current">false:0, true:1</field>
<field type="uint8_t" name="autocontinue">autocontinue to next wp</field>
<field type="float" name="param1">PARAM1, see MAV_CMD enum</field>
......@@ -2973,7 +2986,7 @@
<message id="77" name="COMMAND_ACK">
<description>Report status of a command. Includes feedback wether the command was executed.</description>
<field type="uint16_t" name="command" enum="MAV_CMD">Command ID, as defined by MAV_CMD enum.</field>
<field type="uint8_t" name="result">See MAV_RESULT enum</field>
<field type="uint8_t" name="result" enum="MAV_RESULT">See MAV_RESULT enum</field>
</message>
<message id="81" name="MANUAL_SETPOINT">
<description>Setpoint in roll, pitch, yaw and thrust from the operator</description>
......@@ -3156,6 +3169,9 @@
<field type="float" name="flow_comp_m_y">Flow in meters in y-sensor direction, angular-speed compensated</field>
<field type="uint8_t" name="quality">Optical flow quality / confidence. 0: bad, 255: maximum quality</field>
<field type="float" name="ground_distance">Ground distance in meters. Positive value: distance known. Negative value: Unknown distance</field>
<extensions/>
<field type="float" name="flow_rate_x">Flow rate in radians/second about X axis</field>
<field type="float" name="flow_rate_y">Flow rate in radians/second about Y axis</field>
</message>
<message id="101" name="GLOBAL_VISION_POSITION_ESTIMATE">
<field type="uint64_t" name="usec">Timestamp (microseconds, synced to UNIX time or since system boot)</field>
......@@ -3422,12 +3438,12 @@
<description>Power supply status</description>
<field type="uint16_t" name="Vcc">5V rail voltage in millivolts</field>
<field type="uint16_t" name="Vservo">servo rail voltage in millivolts</field>
<field type="uint16_t" name="flags">power supply status flags (see MAV_POWER_STATUS enum)</field>
<field type="uint16_t" name="flags" enum="MAV_POWER_STATUS">power supply status flags (see MAV_POWER_STATUS enum)</field>
</message>
<message name="SERIAL_CONTROL" id="126">
<description>Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate.</description>
<field type="uint8_t" name="device">See SERIAL_CONTROL_DEV enum</field>
<field type="uint8_t" name="flags">See SERIAL_CONTROL_FLAG enum</field>
<field type="uint8_t" name="device" enum="SERIAL_CONTROL_DEV">See SERIAL_CONTROL_DEV enum</field>
<field type="uint8_t" name="flags" enum="SERIAL_CONTROL_FLAG">See SERIAL_CONTROL_FLAG enum</field>
<field type="uint16_t" name="timeout">Timeout for reply data in milliseconds</field>
<field type="uint32_t" name="baudrate">Baudrate of transfer. Zero means no change.</field>
<field type="uint8_t" name="count">how many bytes in this transfer</field>
......@@ -3496,9 +3512,9 @@
<field type="uint16_t" name="min_distance">Minimum distance the sensor can measure in centimeters</field>
<field type="uint16_t" name="max_distance">Maximum distance the sensor can measure in centimeters</field>
<field type="uint16_t" name="current_distance">Current distance reading</field>
<field type="uint8_t" name="type">Type from MAV_DISTANCE_SENSOR enum.</field>
<field type="uint8_t" name="type" enum="MAV_DISTANCE_SENSOR">Type from MAV_DISTANCE_SENSOR enum.</field>
<field type="uint8_t" name="id">Onboard ID of the sensor</field>
<field type="uint8_t" name="orientation">Direction the sensor faces from MAV_SENSOR_ORIENTATION enum.</field>
<field type="uint8_t" name="orientation" enum="MAV_SENSOR_ORIENTATION">Direction the sensor faces from MAV_SENSOR_ORIENTATION enum.</field>
<field type="uint8_t" name="covariance">Measurement covariance in centimeters, 0 for unknown / invalid readings</field>
</message>
<message id="133" name="TERRAIN_REQUEST">
......@@ -3633,7 +3649,7 @@
</message>
<message id="148" name="AUTOPILOT_VERSION">
<description>Version and capability of autopilot software</description>
<field type="uint64_t" name="capabilities">bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)</field>
<field type="uint64_t" name="capabilities" enum="MAV_PROTOCOL_CAPABILITY">bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)</field>
<field type="uint32_t" name="flight_sw_version">Firmware version number</field>
<field type="uint32_t" name="middleware_sw_version">Middleware version number</field>
<field type="uint32_t" name="os_sw_version">Operating system version number</field>
......@@ -3649,7 +3665,7 @@
<description>The location of a landing area captured from a downward facing camera</description>
<field type="uint64_t" name="time_usec">Timestamp (micros since boot or Unix epoch)</field>
<field type="uint8_t" name="target_num">The ID of the target if multiple targets are present</field>
<field type="uint8_t" name="frame">MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc.</field>
<field type="uint8_t" name="frame" enum="MAV_FRAME">MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc.</field>
<field type="float" name="angle_x">X-axis angular offset (in radians) of the target from the center of the image</field>
<field type="float" name="angle_y">Y-axis angular offset (in radians) of the target from the center of the image</field>
<field type="float" name="distance">Distance to the target from the vehicle in meters</field>
......@@ -3704,13 +3720,13 @@
</message>
<message id="233" name="GPS_RTCM_DATA">
<description>WORK IN PROGRESS! RTCM message for injecting into the onboard GPS (used for DGPS)</description>
<field type="uint8_t" name="flags">LSB: 1 means message is fragmented</field>
<field type="uint8_t" name="flags">LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order.</field>
<field type="uint8_t" name="len">data length</field>
<field type="uint8_t[180]" name="data">RTCM message (may be fragmented)</field>
</message>
<message id="234" name="HIGH_LATENCY">
<description>Message appropriate for high latency connections like Iridium</description>
<field name="base_mode" type="uint8_t">System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h</field>
<field name="base_mode" type="uint8_t" enum="MAV_MODE_FLAG">System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h</field>
<field name="custom_mode" type="uint32_t">A bitfield for use for autopilot-specific flags.</field>
<field name="landed_state" type="uint8_t" enum="MAV_LANDED_STATE">The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.</field>
<field name="roll" type="int16_t">roll (centidegrees)</field>
......@@ -3727,7 +3743,7 @@
<field name="groundspeed" type="uint8_t">groundspeed (m/s)</field>
<field name="climb_rate" type="int8_t">climb rate (m/s)</field>
<field name="gps_nsat" type="uint8_t">Number of satellites visible. If unknown, set to 255</field>
<field name="gps_fix_type" type="uint8_t">See the GPS_FIX_TYPE enum.</field>
<field name="gps_fix_type" type="uint8_t" enum="GPS_FIX_TYPE">See the GPS_FIX_TYPE enum.</field>
<field name="battery_remaining" type="uint8_t">Remaining battery (percentage)</field>
<field name="temperature" type="int8_t">Autopilot temperature (degrees C)</field>
<field name="temperature_air" type="int8_t">Air temperature (degrees C) from airspeed sensor</field>
......
......@@ -178,11 +178,11 @@
<messages>
<message id="0" name="HEARTBEAT">
<description>The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).</description>
<field type="uint8_t" name="type">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field>
<field type="uint8_t" name="autopilot">Autopilot type / class. defined in MAV_AUTOPILOT ENUM</field>
<field type="uint8_t" name="type" enum="MAV_TYPE">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field>
<field type="uint8_t" name="autopilot" enum="MAV_AUTOPILOT">Autopilot type / class. defined in MAV_AUTOPILOT ENUM</field>
<field type="uint8_t" name="base_mode">System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h</field>
<field type="uint32_t" name="custom_mode">A bitfield for use for autopilot-specific flags.</field>
<field type="uint8_t" name="system_status">System status flag, see MAV_STATE ENUM</field>
<field type="uint8_t" name="system_status" enum="MAV_STATE">System status flag, see MAV_STATE ENUM</field>
<field type="uint8_t_mavlink_version" name="mavlink_version">MAVLink version</field>
</message>
</messages>
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Mar 27 2017"
#define MAVLINK_BUILD_DATE "Wed Apr 05 2017"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 9
......
......@@ -60,6 +60,7 @@ typedef enum MAV_CMD
MAV_CMD_NAV_VTOL_LAND=85, /* Land using VTOL mode |Empty| Empty| Empty| Yaw angle in degrees| Latitude| Longitude| Altitude| */
MAV_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_NAV_DELAY=93, /* Delay the next navigation command a number of seconds or until a specified time |Delay in seconds (decimal, -1 to enable time-of-day fields)| hour (24h format, UTC, -1 to ignore)| minute (24h format, UTC, -1 to ignore)| second (24h format, UTC)| Empty| Empty| Empty| */
MAV_CMD_NAV_PAYLOAD_PLACE=94, /* Descend and place payload. Vehicle descends until it detects a hanging payload has reached the ground, the gripper is opened to release the payload |Maximum distance to descend (meters)| Empty| Empty| Empty| Latitude (deg * 1E7)| Longitude (deg * 1E7)| Altitude (meters)| */
MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Mar 27 2017"
#define MAVLINK_BUILD_DATE "Wed Apr 05 2017"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Mar 27 2017"
#define MAVLINK_BUILD_DATE "Wed Apr 05 2017"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Mar 27 2017"
#define MAVLINK_BUILD_DATE "Wed Apr 05 2017"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 179
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Mar 27 2017"
#define MAVLINK_BUILD_DATE "Wed Apr 05 2017"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
Markdown is supported
0%
or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment