Browse Source

GCS_MAVLink: re-generate with updated upstream mavlink

mission-4.1.18
Andrew Tridgell 10 years ago
parent
commit
f98e283091
  1. 2
      libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h
  2. 2
      libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h
  3. 48
      libraries/GCS_MAVLink/include/mavlink/v1.0/mavlink_conversions.h
  4. 24
      libraries/GCS_MAVLink/include/mavlink/v1.0/mavlink_types.h

2
libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H #ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H #define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Tue Nov 25 10:42:23 2014" #define MAVLINK_BUILD_DATE "Wed Dec 3 09:05:50 2014"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255

2
libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H #ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H #define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Tue Nov 25 10:42:23 2014" #define MAVLINK_BUILD_DATE "Wed Dec 3 09:05:50 2014"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255

48
libraries/GCS_MAVLink/include/mavlink/v1.0/mavlink_conversions.h

@ -45,13 +45,13 @@ MAVLINK_HELPER void mavlink_quaternion_to_dcm(const float quaternion[4], float d
double cSq = c * c; double cSq = c * c;
double dSq = d * d; double dSq = d * d;
dcm[0][0] = aSq + bSq - cSq - dSq; dcm[0][0] = aSq + bSq - cSq - dSq;
dcm[0][1] = 2.0 * (b * c - a * d); dcm[0][1] = 2 * (b * c - a * d);
dcm[0][2] = 2.0 * (a * c + b * d); dcm[0][2] = 2 * (a * c + b * d);
dcm[1][0] = 2.0 * (b * c + a * d); dcm[1][0] = 2 * (b * c + a * d);
dcm[1][1] = aSq - bSq + cSq - dSq; dcm[1][1] = aSq - bSq + cSq - dSq;
dcm[1][2] = 2.0 * (c * d - a * b); dcm[1][2] = 2 * (c * d - a * b);
dcm[2][0] = 2.0 * (b * d - a * c); dcm[2][0] = 2 * (b * d - a * c);
dcm[2][1] = 2.0 * (a * b + c * d); dcm[2][1] = 2 * (a * b + c * d);
dcm[2][2] = aSq - bSq - cSq + dSq; dcm[2][2] = aSq - bSq - cSq + dSq;
} }
@ -116,12 +116,12 @@ MAVLINK_HELPER void mavlink_quaternion_to_euler(const float quaternion[4], float
*/ */
MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4]) MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4])
{ {
double cosPhi_2 = cos((double)roll / 2.0); float cosPhi_2 = cosf(roll / 2);
double sinPhi_2 = sin((double)roll / 2.0); float sinPhi_2 = sinf(roll / 2);
double cosTheta_2 = cos((double)pitch / 2.0); float cosTheta_2 = cosf(pitch / 2);
double sinTheta_2 = sin((double)pitch / 2.0); float sinTheta_2 = sinf(pitch / 2);
double cosPsi_2 = cos((double)yaw / 2.0); float cosPsi_2 = cosf(yaw / 2);
double sinPsi_2 = sin((double)yaw / 2.0); float sinPsi_2 = sinf(yaw / 2);
quaternion[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 + quaternion[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 +
sinPhi_2 * sinTheta_2 * sinPsi_2); sinPhi_2 * sinTheta_2 * sinPsi_2);
quaternion[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 - quaternion[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 -
@ -141,14 +141,10 @@ MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float y
*/ */
MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quaternion[4]) MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quaternion[4])
{ {
quaternion[0] = (0.5 * sqrt(1.0 + quaternion[0] = 0.5f * sqrtf(1 + dcm[0][0] + dcm[1][1] + dcm[2][2]);
(double)(dcm[0][0] + dcm[1][1] + dcm[2][2]))); quaternion[1] = 0.5f * sqrtf(1 + dcm[0][0] - dcm[1][1] - dcm[2][2]);
quaternion[1] = (0.5 * sqrt(1.0 + quaternion[2] = 0.5f * sqrtf(1 - dcm[0][0] + dcm[1][1] - dcm[2][2]);
(double)(dcm[0][0] - dcm[1][1] - dcm[2][2]))); quaternion[3] = 0.5f * sqrtf(1 - dcm[0][0] - dcm[1][1] + dcm[2][2]);
quaternion[2] = (0.5 * sqrt(1.0 +
(double)(-dcm[0][0] + dcm[1][1] - dcm[2][2])));
quaternion[3] = (0.5 * sqrt(1.0 +
(double)(-dcm[0][0] - dcm[1][1] + dcm[2][2])));
} }
@ -162,12 +158,12 @@ MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quate
*/ */
MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, float dcm[3][3]) MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, float dcm[3][3])
{ {
double cosPhi = cos(roll); float cosPhi = cosf(roll);
double sinPhi = sin(roll); float sinPhi = sinf(roll);
double cosThe = cos(pitch); float cosThe = cosf(pitch);
double sinThe = sin(pitch); float sinThe = sinf(pitch);
double cosPsi = cos(yaw); float cosPsi = cosf(yaw);
double sinPsi = sin(yaw); float sinPsi = sinf(yaw);
dcm[0][0] = cosThe * cosPsi; dcm[0][0] = cosThe * cosPsi;
dcm[0][1] = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi; dcm[0][1] = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi;

24
libraries/GCS_MAVLink/include/mavlink/v1.0/mavlink_types.h

@ -8,6 +8,13 @@
#include <inttypes.h> #include <inttypes.h>
#endif #endif
// Macro to define packed structures
#ifdef __GNUC__
#define MAVPACKED( __Declaration__ ) __Declaration__ __attribute__((packed))
#else
#define MAVPACKED( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) )
#endif
#ifndef MAVLINK_MAX_PAYLOAD_LEN #ifndef MAVLINK_MAX_PAYLOAD_LEN
// it is possible to override this, but be careful! // it is possible to override this, but be careful!
#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length #define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length
@ -33,7 +40,6 @@
#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES) #define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)
#pragma pack(push, 1)
/** /**
* Old-style 4 byte param union * Old-style 4 byte param union
@ -44,6 +50,7 @@
* and re-instanted on the receiving side using the * and re-instanted on the receiving side using the
* native type as well. * native type as well.
*/ */
MAVPACKED(
typedef struct param_union { typedef struct param_union {
union { union {
float param_float; float param_float;
@ -56,7 +63,7 @@ typedef struct param_union {
uint8_t bytes[4]; uint8_t bytes[4];
}; };
uint8_t type; uint8_t type;
} mavlink_param_union_t; }) mavlink_param_union_t;
/** /**
@ -72,6 +79,7 @@ typedef struct param_union {
* which should be the same as gcc on little-endian arm. When using shifts/masks the value will be treated as a 64 bit unsigned number, * which should be the same as gcc on little-endian arm. When using shifts/masks the value will be treated as a 64 bit unsigned number,
* and the bits pulled out using the shifts/masks. * and the bits pulled out using the shifts/masks.
*/ */
MAVPACKED(
typedef union { typedef union {
struct { struct {
uint8_t is_double:1; uint8_t is_double:1;
@ -89,17 +97,19 @@ typedef union {
}; };
}; };
uint8_t data[8]; uint8_t data[8];
} mavlink_param_union_double_t; }) mavlink_param_union_double_t;
/** /**
* This structure is required to make the mavlink_send_xxx convenience functions * This structure is required to make the mavlink_send_xxx convenience functions
* work, as it tells the library what the current system and component ID are. * work, as it tells the library what the current system and component ID are.
*/ */
MAVPACKED(
typedef struct __mavlink_system { typedef struct __mavlink_system {
uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function
uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function
} mavlink_system_t; }) mavlink_system_t;
MAVPACKED(
typedef struct __mavlink_message { typedef struct __mavlink_message {
uint16_t checksum; ///< sent at end of packet uint16_t checksum; ///< sent at end of packet
uint8_t magic; ///< protocol magic marker uint8_t magic; ///< protocol magic marker
@ -109,14 +119,14 @@ typedef struct __mavlink_message {
uint8_t compid; ///< ID of the message sender component uint8_t compid; ///< ID of the message sender component
uint8_t msgid; ///< ID of message in payload uint8_t msgid; ///< ID of message in payload
uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8]; uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
} mavlink_message_t; }) mavlink_message_t;
MAVPACKED(
typedef struct __mavlink_extended_message { typedef struct __mavlink_extended_message {
mavlink_message_t base_msg; mavlink_message_t base_msg;
int32_t extended_payload_len; ///< Length of extended payload if any int32_t extended_payload_len; ///< Length of extended payload if any
uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN]; uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];
} mavlink_extended_message_t; }) mavlink_extended_message_t;
#pragma pack(pop)
typedef enum { typedef enum {
MAVLINK_TYPE_CHAR = 0, MAVLINK_TYPE_CHAR = 0,

Loading…
Cancel
Save