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)
{
......
This diff is collapsed.
......@@ -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
......@@ -735,32 +746,41 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
} else {
// Successfully got message
status->msg_received = MAVLINK_FRAMING_OK;
}
rxmsg->ck[1] = c;
}
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;
status->msg_received = MAVLINK_FRAMING_INCOMPLETE;
// 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
status->msg_received = MAVLINK_FRAMING_BAD_SIGNATURE;
(status->signing->accept_unsigned_callback == NULL ||
!status->signing->accept_unsigned_callback(status, rxmsg->msgid))) {
// 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));
}
break;
case MAVLINK_PARSE_STATE_SIGNATURE_WAIT:
rxmsg->signature[MAVLINK_SIGNATURE_BLOCK_LEN-status->signature_wait] = c;
rxmsg->signature[MAVLINK_SIGNATURE_BLOCK_LEN-status->signature_wait] = c;
status->signature_wait--;
if (status->signature_wait == 0) {
// we have the whole signature, check it is OK
bool sig_ok = mavlink_signature_check(status->signing, status->signing_streams, rxmsg);
if (!sig_ok &&
(status->signing->accept_unsigned_callback &&
status->signing->accept_unsigned_callback(status, rxmsg->msgid))) {
(status->signing->accept_unsigned_callback &&
status->signing->accept_unsigned_callback(status, rxmsg->msgid))) {
// accepted via application level override
sig_ok = true;
}
......@@ -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">
......
This diff is collapsed.
......@@ -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