Skip to content

Commit

Permalink
autogenerated headers for rev https://github.com/mavlink/mavlink/tree…
Browse files Browse the repository at this point in the history
  • Loading branch information
PX4BuildBot committed Apr 5, 2017
1 parent fb41138 commit 53bd663
Show file tree
Hide file tree
Showing 26 changed files with 210 additions and 96 deletions.
1 change: 1 addition & 0 deletions ASLUAV/ASLUAV.h
Expand Up @@ -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| */
Expand Down
2 changes: 1 addition & 1 deletion ASLUAV/version.h
Expand Up @@ -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

Expand Down
4 changes: 3 additions & 1 deletion ardupilotmega/ardupilotmega.h
Expand Up @@ -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| */
Expand Down Expand Up @@ -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

Expand Down
2 changes: 1 addition & 1 deletion ardupilotmega/version.h
Expand Up @@ -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

Expand Down
1 change: 1 addition & 0 deletions autoquad/autoquad.h
Expand Up @@ -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| */
Expand Down
2 changes: 1 addition & 1 deletion autoquad/version.h
Expand Up @@ -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

Expand Down
6 changes: 4 additions & 2 deletions checksum.h
@@ -1,6 +1,8 @@
#pragma once

#ifdef __cplusplus
#if defined(MAVLINK_USE_CXX_NAMESPACE)
namespace mavlink {
#elif defined(__cplusplus)
extern "C" {
#endif

Expand Down Expand Up @@ -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
4 changes: 3 additions & 1 deletion common/common.h
Expand Up @@ -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

Expand Down Expand Up @@ -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| */
Expand Down
10 changes: 5 additions & 5 deletions common/mavlink_msg_gps_rtcm_data.h
Expand Up @@ -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;
Expand Down Expand Up @@ -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)
Expand Down Expand Up @@ -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)
Expand Down Expand Up @@ -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)
*/
Expand Down Expand Up @@ -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)
{
Expand Down

0 comments on commit 53bd663

Please sign in to comment.