mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: regenerate MAVLink headers
This commit is contained in:
parent
8d04deff6a
commit
b8b235c33c
|
@ -5,7 +5,7 @@
|
|||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Thu Jul 24 21:34:30 2014"
|
||||
#define MAVLINK_BUILD_DATE "Thu Jul 24 21:48:38 2014"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
|
||||
|
||||
|
|
|
@ -36,6 +36,7 @@ static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
|
|||
}
|
||||
#endif
|
||||
|
||||
|
||||
/**
|
||||
* @brief Initiliaze the buffer for the X.25 CRC
|
||||
*
|
||||
|
@ -64,6 +65,7 @@ static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length)
|
|||
return crcTmp;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Accumulate the X.25 CRC by adding an array of bytes
|
||||
*
|
||||
|
@ -81,9 +83,6 @@ static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer
|
|||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
#endif /* _CHECKSUM_H_ */
|
||||
|
||||
#ifdef __cplusplus
|
||||
|
|
|
@ -255,7 +255,8 @@ typedef enum MAV_FRAME
|
|||
MAV_FRAME_LOCAL_OFFSET_NED=7, /* Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position. | */
|
||||
MAV_FRAME_BODY_NED=8, /* Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. | */
|
||||
MAV_FRAME_BODY_OFFSET_NED=9, /* Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east. | */
|
||||
MAV_FRAME_ENUM_END=10, /* | */
|
||||
MAV_FRAME_GLOBAL_TERRAIN_ALT=10, /* Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at ground level in terrain model. | */
|
||||
MAV_FRAME_ENUM_END=11, /* | */
|
||||
} MAV_FRAME;
|
||||
#endif
|
||||
|
||||
|
|
|
@ -5,7 +5,7 @@
|
|||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Thu Jul 24 21:34:30 2014"
|
||||
#define MAVLINK_BUILD_DATE "Thu Jul 24 21:48:38 2014"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
|
||||
|
||||
|
|
|
@ -77,7 +77,7 @@ MAVLINK_HELPER void mavlink_quaternion_to_euler(const float quaternion[4], float
|
|||
{
|
||||
float dcm[3][3];
|
||||
mavlink_quaternion_to_dcm(quaternion, dcm);
|
||||
mavlink_dcm_to_euler(dcm, roll, pitch, yaw);
|
||||
mavlink_dcm_to_euler((const float(*)[3])dcm, roll, pitch, yaw);
|
||||
}
|
||||
|
||||
MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4])
|
||||
|
|
|
@ -34,6 +34,14 @@
|
|||
#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)
|
||||
|
||||
#pragma pack(push, 1)
|
||||
|
||||
/**
|
||||
* This struct is the data format to be used when sending
|
||||
* parameters. The parameter should be copied to the native
|
||||
* type (without type conversion)
|
||||
* and re-instanted on the receiving side using the
|
||||
* native type as well.
|
||||
*/
|
||||
typedef struct param_union {
|
||||
union {
|
||||
float param_float;
|
||||
|
|
Loading…
Reference in New Issue