Commit 053eb5a8 authored by pixhawk's avatar pixhawk
parents 0075f512 c4bc93c3
......@@ -52,7 +52,7 @@ static inline void crc_init(uint16_t* crcAccum)
* @param length length of the byte array
* @return the checksum over the buffer bytes
**/
static inline uint16_t crc_calculate(uint8_t* pBuffer, uint16_t length)
static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length)
{
uint16_t crcTmp;
crc_init(&crcTmp);
......
......@@ -18,6 +18,24 @@ MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
return &m_mavlink_status[chan];
}
/*
internal function to give access to the channel buffer for each channel
*/
MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan)
{
#if MAVLINK_EXTERNAL_RX_BUFFER
// No m_mavlink_message array defined in function,
// has to be defined externally
#ifndef m_mavlink_message
#error ERROR: IF #define MAVLINK_EXTERNAL_RX_BUFFER IS SET, THE BUFFER HAS TO BE ALLOCATED OUTSIDE OF THIS FUNCTION (mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];)
#endif
#else
static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];
#endif
return &m_mavlink_buffer[chan];
}
/**
* @brief Finalize a MAVLink message with channel assignment
*
......@@ -120,7 +138,7 @@ MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint
*/
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg)
{
memcpy(buffer, (uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len);
memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len);
return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len;
}
......@@ -182,8 +200,6 @@ MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
*/
MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
{
static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS];
/*
default message crc function. You can override this per-system to
put this data in a different memory segment
......@@ -195,7 +211,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa
#endif
#endif
mavlink_message_t* rxmsg = &m_mavlink_message[chan]; ///< The currently decoded message
mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan); ///< The currently decoded message
mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status
int bufferIndex = 0;
......@@ -209,14 +225,15 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
rxmsg->len = 0;
rxmsg->magic = c;
mavlink_start_checksum(rxmsg);
}
break;
case MAVLINK_PARSE_STATE_GOT_STX:
if (status->msg_received
/* Support shorter buffers than the
default maximum packet size */
/* Support shorter buffers than the
default maximum packet size */
#if (MAVLINK_MAX_PAYLOAD_LEN < 255)
|| c > MAVLINK_MAX_PAYLOAD_LEN
#endif
......@@ -269,7 +286,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa
break;
case MAVLINK_PARSE_STATE_GOT_MSGID:
_MAV_PAYLOAD(rxmsg)[status->packet_idx++] = (char)c;
_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c;
mavlink_update_checksum(rxmsg, c);
if (status->packet_idx == rxmsg->len)
{
......@@ -296,6 +313,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa
else
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1;
_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c;
}
break;
......@@ -317,6 +335,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa
// Successfully got message
status->msg_received = 1;
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c;
memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
}
break;
......
......@@ -140,6 +140,7 @@ enum MAV_COMPONENT
MAV_COMP_ID_AIRSLAM,
MAV_COMP_ID_MAPPER,
MAV_COMP_ID_CAMERA,
MAV_COMP_ID_RADIO = 68,
MAV_COMP_ID_IMU = 200,
MAV_COMP_ID_IMU_2 = 201,
MAV_COMP_ID_IMU_3 = 202,
......@@ -179,11 +180,26 @@ enum MAVLINK_DATA_STREAM_TYPE
#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length
#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255
#define MAVLINK_EXTENDED_HEADER_LEN 14
#if (defined _MSC_VER) | ((defined __APPLE__) & (defined __MACH__)) | (defined __linux__)
/* full fledged 32bit++ OS */
#define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507
#else
/* small microcontrollers */
#define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048
#endif
#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)
typedef struct param_union {
union {
float param_float;
int32_t param_int32;
uint32_t param_uint32;
uint8_t param_uint8;
uint8_t bytes[4];
};
uint8_t type;
} mavlink_param_union_t;
......@@ -208,6 +224,14 @@ typedef struct __mavlink_message {
uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
} mavlink_message_t;
typedef struct __mavlink_extended_message {
mavlink_message_t base_msg;
int32_t extended_payload_len; ///< Length of extended payload if any
uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];
} mavlink_extended_message_t;
typedef enum {
MAVLINK_TYPE_CHAR = 0,
MAVLINK_TYPE_UINT8_T = 1,
......@@ -228,9 +252,9 @@ typedef struct __mavlink_field_info {
const char *name; // name of this field
const char *print_format; // printing format hint, or NULL
mavlink_message_type_t type; // type of this field
unsigned array_length; // if non-zero, field is an array
unsigned wire_offset; // offset of each field in the payload
unsigned structure_offset; // offset in a C structure
unsigned int array_length; // if non-zero, field is an array
unsigned int wire_offset; // offset of each field in the payload
unsigned int structure_offset; // offset in a C structure
} mavlink_field_info_t;
// note that in this structure the order of fields is the order
......@@ -241,11 +265,12 @@ typedef struct __mavlink_message_info {
mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information
} mavlink_message_info_t;
#define _MAV_PAYLOAD(msg) ((char *)(&(msg)->payload64[0]))
#define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0])))
#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0])))
// checksum is immediately after the payload bytes
#define mavlink_ck_a(msg) *(msg->len + (uint8_t *)_MAV_PAYLOAD(msg))
#define mavlink_ck_b(msg) *((msg->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD(msg))
#define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
#define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
typedef enum {
MAVLINK_COMM_0,
......
......@@ -155,7 +155,7 @@ static inline void byte_copy_8(char *dst, const char *src)
/*
like memcpy(), but if src is NULL, do a memset to zero
*/
*/
static void mav_array_memcpy(void *dest, const void *src, size_t n)
{
if (src == NULL) {
......@@ -171,6 +171,7 @@ static void mav_array_memcpy(void *dest, const void *src, size_t n)
static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
{
mav_array_memcpy(&buf[wire_offset], b, array_length);
}
/*
......@@ -179,6 +180,7 @@ static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const cha
static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
{
mav_array_memcpy(&buf[wire_offset], b, array_length);
}
/*
......@@ -187,6 +189,7 @@ static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const
static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length)
{
mav_array_memcpy(&buf[wire_offset], b, array_length);
}
#if MAVLINK_NEED_BYTE_SWAP
......@@ -206,7 +209,7 @@ static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, co
#define _MAV_PUT_ARRAY(TYPE, V) \
static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
{ \
mav_array_memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \
mav_array_memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \
}
#endif
......@@ -219,9 +222,9 @@ _MAV_PUT_ARRAY(int64_t, i64)
_MAV_PUT_ARRAY(float, f)
_MAV_PUT_ARRAY(double, d)
#define _MAV_RETURN_char(msg, wire_offset) _MAV_PAYLOAD(msg)[wire_offset]
#define _MAV_RETURN_int8_t(msg, wire_offset) (int8_t)_MAV_PAYLOAD(msg)[wire_offset]
#define _MAV_RETURN_uint8_t(msg, wire_offset) (uint8_t)_MAV_PAYLOAD(msg)[wire_offset]
#define _MAV_RETURN_char(msg, wire_offset) (const char)_MAV_PAYLOAD(msg)[wire_offset]
#define _MAV_RETURN_int8_t(msg, wire_offset) (const int8_t)_MAV_PAYLOAD(msg)[wire_offset]
#define _MAV_RETURN_uint8_t(msg, wire_offset) (const uint8_t)_MAV_PAYLOAD(msg)[wire_offset]
#if MAVLINK_NEED_BYTE_SWAP
#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
......
......@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Mar 1 01:19:41 2012"
#define MAVLINK_BUILD_DATE "Thu Mar 1 15:11:54 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 179
......
......@@ -24,6 +24,30 @@ public:
, kExtendedHeaderSize(MAVLINK_EXTENDED_HEADER_LEN)
, kExtendedPayloadMaxSize(MAVLINK_MAX_EXTENDED_PAYLOAD_LEN)
{
// register GLOverlay
{
std::tr1::shared_ptr<px::GLOverlay> msg(new px::GLOverlay);
registerType(msg);
}
// register ObstacleList
{
std::tr1::shared_ptr<px::ObstacleList> msg(new px::ObstacleList);
registerType(msg);
}
// register ObstacleMap
{
std::tr1::shared_ptr<px::ObstacleMap> msg(new px::ObstacleMap);
registerType(msg);
}
// register Path
{
std::tr1::shared_ptr<px::Path> msg(new px::Path);
registerType(msg);
}
// register PointCloudXYZI
{
std::tr1::shared_ptr<px::PointCloudXYZI> msg(new px::PointCloudXYZI);
......@@ -144,7 +168,7 @@ public:
if (typecode >= mTypeMap.size())
{
std::cout << "# WARNING: Protobuf message with type code "
<< typecode << " is not registered." << std::endl;
<< static_cast<int>(typecode) << " is not registered." << std::endl;
return false;
}
......@@ -186,6 +210,11 @@ public:
if (offset == 0)
{
queue.push_back(msg);
if ((flags & 0x1) != 0x1)
{
reassemble = true;
}
}
else
{
......
......@@ -17,7 +17,15 @@
#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255
#define MAVLINK_EXTENDED_HEADER_LEN 14
#define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507
#if (defined _MSC_VER) | ((defined __APPLE__) & (defined __MACH__)) | (defined __linux__)
/* full fledged 32bit++ OS */
#define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507
#else
/* small microcontrollers */
#define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048
#endif
#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)
typedef struct param_union {
......
This source diff could not be displayed because it is too large. You can view the blob instead.
/** @file
* @brief MAVLink comm protocol generated from minimal.xml
* @brief MAVLink comm protocol generated from test.xml
* @see http://qgroundcontrol.org/mavlink/
*/
#ifndef MINIMAL_H
#define MINIMAL_H
#ifndef TEST_H
#define TEST_H
#ifdef __cplusplus
extern "C" {
......@@ -12,32 +12,32 @@ extern "C" {
// MESSAGE LENGTHS AND CRCS
#ifndef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS {3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#define MAVLINK_MESSAGE_LENGTHS {179, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#endif
#ifndef MAVLINK_MESSAGE_CRCS
#define MAVLINK_MESSAGE_CRCS {72, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#define MAVLINK_MESSAGE_CRCS {103, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#endif
#ifndef MAVLINK_MESSAGE_INFO
#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}}
#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_TEST_TYPES, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}}
#endif
#include "../protocol.h"
#define MAVLINK_ENABLED_MINIMAL
#define MAVLINK_ENABLED_TEST
// MAVLINK VERSION
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 2
#define MAVLINK_VERSION 3
#endif
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 2
#define MAVLINK_VERSION 3
#endif
// ENUM DEFINITIONS
......@@ -45,9 +45,9 @@ extern "C" {
// MESSAGE DEFINITIONS
#include "./mavlink_msg_heartbeat.h"
#include "./mavlink_msg_test_types.h"
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // MINIMAL_H
#endif // TEST_H
......@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Feb 9 16:35:37 2012"
#define MAVLINK_BUILD_DATE "Thu Mar 1 15:11:58 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 179
......
/testmav0.9
/testmav1.0
/testmav1.0_nonstrict
/*
simple MAVLink testsuite for C
*/
#include <stdio.h>
#include <stdlib.h>
#include <stdint.h>
#include <assert.h>
#include <stddef.h>
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
#define MAVLINK_COMM_NUM_BUFFERS 2
// this trick allows us to make mavlink_message_t as small as possible
// for this dialect, which saves some memory
#include <version.h>
#define MAVLINK_MAX_PAYLOAD_LEN MAVLINK_MAX_DIALECT_PAYLOAD_SIZE
#include <mavlink_types.h>
static mavlink_system_t mavlink_system = {42,11,};
#define MAVLINK_ASSERT(x) assert(x)
static void comm_send_ch(mavlink_channel_t chan, uint8_t c);
static mavlink_message_t last_msg;
#include <mavlink.h>
#include <testsuite.h>
static unsigned chan_counts[MAVLINK_COMM_NUM_BUFFERS];
static const unsigned message_lengths[] = MAVLINK_MESSAGE_LENGTHS;
static unsigned error_count;
static const mavlink_message_info_t message_info[256] = MAVLINK_MESSAGE_INFO;
static void print_one_field(mavlink_message_t *msg, const mavlink_field_info_t *f, int idx)
{
#define PRINT_FORMAT(f, def) (f->print_format?f->print_format:def)
switch (f->type) {
case MAVLINK_TYPE_CHAR:
printf(PRINT_FORMAT(f, "%c"), _MAV_RETURN_char(msg, f->wire_offset+idx*1));
break;
case MAVLINK_TYPE_UINT8_T:
printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint8_t(msg, f->wire_offset+idx*1));
break;
case MAVLINK_TYPE_INT8_T:
printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int8_t(msg, f->wire_offset+idx*1));
break;
case MAVLINK_TYPE_UINT16_T:
printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint16_t(msg, f->wire_offset+idx*2));
break;
case MAVLINK_TYPE_INT16_T:
printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int16_t(msg, f->wire_offset+idx*2));
break;
case MAVLINK_TYPE_UINT32_T:
printf(PRINT_FORMAT(f, "%lu"), (unsigned long)_MAV_RETURN_uint32_t(msg, f->wire_offset+idx*4));
break;
case MAVLINK_TYPE_INT32_T:
printf(PRINT_FORMAT(f, "%ld"), (long)_MAV_RETURN_int32_t(msg, f->wire_offset+idx*4));
break;
case MAVLINK_TYPE_UINT64_T:
printf(PRINT_FORMAT(f, "%llu"), (unsigned long long)_MAV_RETURN_uint64_t(msg, f->wire_offset+idx*8));
break;
case MAVLINK_TYPE_INT64_T:
printf(PRINT_FORMAT(f, "%lld"), (long long)_MAV_RETURN_int64_t(msg, f->wire_offset+idx*8));
break;
case MAVLINK_TYPE_FLOAT:
printf(PRINT_FORMAT(f, "%f"), (double)_MAV_RETURN_float(msg, f->wire_offset+idx*4));
break;
case MAVLINK_TYPE_DOUBLE:
printf(PRINT_FORMAT(f, "%f"), _MAV_RETURN_double(msg, f->wire_offset+idx*8));
break;
}
}
static void print_field(mavlink_message_t *msg, const mavlink_field_info_t *f)
{
printf("%s: ", f->name);
if (f->array_length == 0) {
print_one_field(msg, f, 0);
printf(" ");
} else {
unsigned i;
/* print an array */
if (f->type == MAVLINK_TYPE_CHAR) {
printf("'%.*s'", f->array_length,
f->wire_offset+(const char *)_MAV_PAYLOAD(msg));
} else {
printf("[ ");
for (i=0; i<f->array_length; i++) {
print_one_field(msg, f, i);
if (i < f->array_length) {
printf(", ");
}
}
printf("]");
}
}
printf(" ");
}
static void print_message(mavlink_message_t *msg)
{
const mavlink_message_info_t *m = &message_info[msg->msgid];
const mavlink_field_info_t *f = m->fields;
unsigned i;
printf("%s { ", m->name);
for (i=0; i<m->num_fields; i++) {
print_field(msg, &f[i]);
}
printf("}\n");
}
static void comm_send_ch(mavlink_channel_t chan, uint8_t c)
{
mavlink_status_t status;
if (mavlink_parse_char(chan, c, &last_msg, &status)) {
print_message(&last_msg);
chan_counts[chan]++;
/* channel 0 gets 3 messages per message, because of
the channel defaults for _pack() and _encode() */
if (chan == MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)(chan_counts[chan]*3)) {
printf("Channel 0 sequence mismatch error at packet %u (rx_seq=%u)\n",
chan_counts[chan], status.current_rx_seq);
error_count++;
} else if (chan > MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)chan_counts[chan]) {
printf("Channel %u sequence mismatch error at packet %u (rx_seq=%u)\n",
(unsigned)chan, chan_counts[chan], status.current_rx_seq);
error_count++;
}
if (message_lengths[last_msg.msgid] != last_msg.len) {
printf("Incorrect message length %u for message %u - expected %u\n",
(unsigned)last_msg.len, (unsigned)last_msg.msgid, message_lengths[last_msg.msgid]);
error_count++;
}
}
if (status.packet_rx_drop_count != 0) {
printf("Parse error at packet %u\n", chan_counts[chan]);
error_count++;
}
}
int main(void)
{
mavlink_channel_t chan;
mavlink_test_all(11, 10, &last_msg);
for (chan=MAVLINK_COMM_0; chan<=MAVLINK_COMM_1; chan++) {
printf("Received %u messages on channel %u OK\n",
chan_counts[chan], (unsigned)chan);
}
if (error_count != 0) {
printf("Error count %u\n", error_count);
exit(1);
}
printf("No errors detected\n");
return 0;
}
// stdafx.cpp : source file that includes just the standard includes
// testmav.pch will be the pre-compiled header
// stdafx.obj will contain the pre-compiled type information
#include "stdafx.h"
// TODO: reference any additional headers you need in STDAFX.H
// and not in this file
// stdafx.h : include file for standard system include files,
// or project specific include files that are used frequently, but
// are changed infrequently
//
#pragma once
#include "targetver.h"
#include <stdio.h>
#include <tchar.h>
// TODO: reference additional headers your program requires here
#pragma once
// Including SDKDDKVer.h defines the highest available Windows platform.
// If you wish to build your application for a previous Windows platform, include WinSDKVer.h and
// set the _WIN32_WINNT macro to the platform you wish to support before including SDKDDKVer.h.
#include <SDKDDKVer.h>
// testmav.cpp : Defines the entry point for the console application.
//
#include "stdafx.h"
#include "stdio.h"
#include "stdint.h"
#include "stddef.h"
#include "assert.h"
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
#define MAVLINK_COMM_NUM_BUFFERS 2
#include <mavlink_types.h>
static mavlink_system_t mavlink_system = {42,11,};
#define MAVLINK_ASSERT(x) assert(x)
static void comm_send_ch(mavlink_channel_t chan, uint8_t c);
static mavlink_message_t last_msg;
#include <common/mavlink.h>
#include <common/testsuite.h>
static unsigned chan_counts[MAVLINK_COMM_NUM_BUFFERS];
static const unsigned message_lengths[] = MAVLINK_MESSAGE_LENGTHS;
static unsigned error_count;
static const mavlink_message_info_t message_info[256] = MAVLINK_MESSAGE_INFO;
static void print_one_field(mavlink_message_t *msg, const mavlink_field_info_t *f, int idx)
{
#define PRINT_FORMAT(f, def) (f->print_format?f->print_format:def)
switch (f->type) {
case MAVLINK_TYPE_CHAR:
printf(PRINT_FORMAT(f, "%c"), _MAV_RETURN_char(msg, f->wire_offset+idx*1));
break;
case MAVLINK_TYPE_UINT8_T:
printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint8_t(msg, f->wire_offset+idx*1));
break;
case MAVLINK_TYPE_INT8_T:
printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int8_t(msg, f->wire_offset+idx*1));
break;
case MAVLINK_TYPE_UINT16_T:
printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint16_t(msg, f->wire_offset+idx*2));
break;
case MAVLINK_TYPE_INT16_T:
printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int16_t(msg, f->wire_offset+idx*2));
break;
case MAVLINK_TYPE_UINT32_T:
printf(PRINT_FORMAT(f, "%lu"), (unsigned long)_MAV_RETURN_uint32_t(msg, f->wire_offset+idx*4));
break;
case MAVLINK_TYPE_INT32_T:
printf(PRINT_FORMAT(f, "%ld"), (long)_MAV_RETURN_int32_t(msg, f->wire_offset+idx*4));
break;
case MAVLINK_TYPE_UINT64_T:
printf(PRINT_FORMAT(f, "%llu"), (unsigned long long)_MAV_RETURN_uint64_t(msg, f->wire_offset+idx*8));
break;
case MAVLINK_TYPE_INT64_T:
printf(PRINT_FORMAT(f, "%lld"), (long long)_MAV_RETURN_int64_t(msg, f->wire_offset+idx*8));
break;
case MAVLINK_TYPE_FLOAT:
printf(PRINT_FORMAT(f, "%f"), (double)_MAV_RETURN_float(msg, f->wire_offset+idx*4));
break;
case MAVLINK_TYPE_DOUBLE:
printf(PRINT_FORMAT(f, "%f"), _MAV_RETURN_double(msg, f->wire_offset+idx*8));
break;
}
}
static void print_field(mavlink_message_t *msg, const mavlink_field_info_t *f)
{
printf("%s: ", f->name);
if (f->array_length == 0) {
print_one_field(msg, f, 0);
printf(" ");
} else {
unsigned i;
/* print an array */
if (f->type == MAVLINK_TYPE_CHAR) {
printf("'%.*s'", f->array_length,
f->wire_offset+(const char *)_MAV_PAYLOAD(msg));
} else {
printf("[ ");
for (i=0; i<f->array_length; i++) {
print_one_field(msg, f, i);
if (i < f->array_length) {
printf(", ");
}
}
printf("]");
}
}
printf(" ");
}
static void print_message(mavlink_message_t *msg)
{
const mavlink_message_info_t *m = &message_info[msg->msgid];
const mavlink_field_info_t *f = m->fields;
unsigned i;
printf("%s { ", m->name);
for (i=0; i<m->num_fields; i++) {
print_field(msg, &f[i]);
}
printf("}\n");
}
static void comm_send_ch(mavlink_channel_t chan, uint8_t c)
{
mavlink_status_t status;
if (mavlink_parse_char(chan, c, &last_msg, &status)) {
print_message(&last_msg);
chan_counts[chan]++;
/* channel 0 gets 3 messages per message, because of
the channel defaults for _pack() and _encode() */
if (chan == MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)(chan_counts[chan]*3)) {
printf("Channel 0 sequence mismatch error at packet %u (rx_seq=%u)\n",
chan_counts[chan], status.current_rx_seq);
error_count++;
} else if (chan > MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)chan_counts[chan]) {
printf("Channel %u sequence mismatch error at packet %u (rx_seq=%u)\n",
(unsigned)chan, chan_counts[chan], status.current_rx_seq);
error_count++;
}
if (message_lengths[last_msg.msgid] != last_msg.len) {
printf("Incorrect message length %u for message %u - expected %u\n",
(unsigned)last_msg.len, (unsigned)last_msg.msgid, message_lengths[last_msg.msgid]);
error_count++;
}
}
if (status.packet_rx_drop_count != 0) {
printf("Parse error at packet %u\n", chan_counts[chan]);
error_count++;
}
}
int _tmain(int argc, _TCHAR* argv[])
{
int chan;
mavlink_test_all(11, 10, &last_msg);
for (chan=MAVLINK_COMM_0; chan<=MAVLINK_COMM_1; chan++) {
printf("Received %u messages on channel %u OK\n",
chan_counts[chan], (unsigned)chan);
}
if (error_count != 0) {
printf("Error count %u\n", error_count);
return(1);
}
printf("No errors detected\n");
return 0;
}
#!/usr/bin/env python
'''
useful extra functions for use by mavlink clients
Copyright Andrew Tridgell 2011
Released under GNU GPL version 3 or later
'''
from math import *
def norm_heading(RAW_IMU, ATTITUDE, declination):
'''calculate heading from RAW_IMU and ATTITUDE'''
xmag = RAW_IMU.xmag
ymag = RAW_IMU.ymag
zmag = RAW_IMU.zmag
pitch = ATTITUDE.pitch
roll = ATTITUDE.roll
headX = xmag*cos(pitch) + ymag*sin(roll)*sin(pitch) + zmag*cos(roll)*sin(pitch)
headY = ymag*cos(roll) - zmag*sin(roll)
heading = atan2(-headY, headX)
heading = fmod(degrees(heading) + declination + 360, 360)
return heading
def TrueHeading(SERVO_OUTPUT_RAW):
rc3_min = 1060
rc3_max = 1850
p = float(SERVO_OUTPUT_RAW.servo3_raw - rc3_min) / (rc3_max - rc3_min)
return 172 + (1.0-p)*(326 - 172)
def kmh(mps):
'''convert m/s to Km/h'''
return mps*3.6
def altitude(press_abs, ground_press=955.0, ground_temp=30):
'''calculate barometric altitude'''
return log(ground_press/press_abs)*(ground_temp+273.15)*29271.267*0.001
......@@ -71,10 +71,10 @@ if __name__=="__main__":
import mavgen_python
import mavgen_c
parser = OptionParser("mavgen.py [options] <XML files>")
parser.add_option("-o", "--output", dest="output", default="mavlink", help="output base name")
parser.add_option("--lang", dest="language", default="python", help="language to generate")
parser.add_option("--wire-protocol", dest="wire_protocol", default=mavparse.PROTOCOL_0_9, help="wire protocol version")
parser = OptionParser("%prog [options] <XML files>")
parser.add_option("-o", "--output", dest="output", default="mavlink", help="output directory.")
parser.add_option("--lang", dest="language", default="python", help="language of generated code: 'Python' or 'C' [default: %default]")
parser.add_option("--wire-protocol", dest="wire_protocol", default=mavparse.PROTOCOL_0_9, help="MAVLink protocol version: '0.9' or '1.0'. [default: %default]")
(opts, args) = parser.parse_args()
if len(args) < 1:
......
......@@ -404,16 +404,41 @@ ${{message: mavlink_test_${name_lower}(system_id, component_id, last_msg);
def copy_fixed_headers(directory, xml):
'''copy the fixed protocol headers to the target directory'''
import shutil
hlist = [ 'protocol.h', 'mavlink_helpers.h', 'mavlink_types.h', 'checksum.h' ]
hlist = [ 'protocol.h', 'mavlink_helpers.h', 'mavlink_types.h', 'checksum.h', 'mavlink_protobuf_manager.hpp' ]
basepath = os.path.dirname(os.path.realpath(__file__))
srcpath = os.path.join(basepath, 'C/include_v%s' % xml.wire_protocol_version)
print("Copying fixed headers")
for h in hlist:
if (not (h == 'mavlink_protobuf_manager.hpp' and xml.wire_protocol_version == '0.9')):
src = os.path.realpath(os.path.join(srcpath, h))
dest = os.path.realpath(os.path.join(directory, h))
if src == dest:
continue
shutil.copy(src, dest)
# XXX This is a hack - to be removed
if (xml.basename == 'pixhawk' and xml.wire_protocol_version == '1.0'):
h = 'pixhawk/pixhawk.pb.h'
src = os.path.realpath(os.path.join(srcpath, h))
dest = os.path.realpath(os.path.join(directory, h))
if src == dest:
continue
shutil.copy(src, dest)
def copy_fixed_sources(directory, xml):
# XXX This is a hack - to be removed
import shutil
basepath = os.path.dirname(os.path.realpath(__file__))
srcpath = os.path.join(basepath, 'C/src_v%s' % xml.wire_protocol_version)
if (xml.basename == 'pixhawk' and xml.wire_protocol_version == '1.0'):
print("Copying fixed sources")
src = os.path.realpath(os.path.join(srcpath, 'pixhawk/pixhawk.pb.cc'))
dest = os.path.realpath(os.path.join(directory, '../../../share/mavlink/src/v%s/pixhawk/pixhawk.pb.cc' % xml.wire_protocol_version))
destdir = os.path.realpath(os.path.join(directory, '../../../share/mavlink/src/v%s/pixhawk' % xml.wire_protocol_version))
try:
os.makedirs(destdir)
except:
print("Not re-creating directory")
shutil.copy(src, dest)
print("Copied to"),
print(dest)
class mav_include(object):
def __init__(self, base):
......@@ -553,3 +578,4 @@ def generate(basename, xml_list):
for xml in xml_list:
generate_one(basename, xml)
copy_fixed_headers(basename, xml_list[0])
copy_fixed_sources(basename, xml_list[0])
This diff is collapsed.
This diff is collapsed.
......@@ -6,7 +6,7 @@ Copyright Andrew Tridgell 2011
Released under GNU GPL version 3 or later
'''
import xml.parsers.expat, os, time, sys, operator, mavutil
import xml.parsers.expat, os, errno, time, sys, operator, mavutil
PROTOCOL_0_9 = "0.9"
PROTOCOL_1_0 = "1.0"
......@@ -272,7 +272,7 @@ class MAVXML(object):
self.largest_payload = m.wire_length
if m.wire_length+8 > 64:
print("Warning: message %s is longer than 64 bytes long (%u bytes)" % (m.name, m.wire_length+8))
print("Note: message %s is longer than 64 bytes long (%u bytes), which can cause fragmentation since many radio modems use 64 bytes as maximum air transfer unit." % (m.name, m.wire_length+8))
def __str__(self):
return "MAVXML for %s from %s (%u message, %u enums)" % (
......@@ -359,16 +359,12 @@ def total_msgs(xml):
return count
def mkdir_p(dir):
'''like mkdir -p'''
if not dir:
return
if dir.endswith("/"):
mkdir_p(dir[:-1])
return
if os.path.isdir(dir):
return
mkdir_p(os.path.dirname(dir))
os.mkdir(dir)
try:
os.makedirs(dir)
except OSError as exc:
if exc.errno == errno.EEXIST:
pass
else: raise
# check version consistent
# add test.xml
......
......@@ -8,6 +8,9 @@ Released under GNU GPL version 3 or later
import sys, textwrap
from optparse import OptionParser
# mavparse is up a directory level
sys.path.append('..')
import mavparse
def gen_value(f, i, language):
......@@ -62,11 +65,11 @@ Note: this file has been auto-generated. DO NOT EDIT
import mavlink
def generate_outputs(mav):
'''generate all message types as outputs'''
'''generate all message types as outputs'''
""")
for m in msgs:
if m.name == "HEARTBEAT": continue
outf.write("\tmav.%s_send(" % m.name.lower())
outf.write("\tmav.%s_send(" % m.name.lower())
for i in range(0, len(m.fields)):
f = m.fields[i]
outf.write("%s=%s" % (f.name, gen_value(f, i, 'py')))
......@@ -90,7 +93,7 @@ static void mavtest_generate_outputs(mavlink_channel_t chan)
""")
for m in msgs:
if m.name == "HEARTBEAT": continue
outf.write("\tmavlink_msg_%s_send(chan," % m.name.lower())
outf.write("\tmavlink_msg_%s_send(chan," % m.name.lower())
for i in range(0, len(m.fields)):
f = m.fields[i]
outf.write("%s" % gen_value(f, i, 'C'))
......@@ -104,8 +107,8 @@ static void mavtest_generate_outputs(mavlink_channel_t chan)
######################################################################
'''main program'''
parser = OptionParser("mavtestgen.py [options] <XML files>")
parser.add_option("-o", "--output", dest="output", default="mavtest", help="output file base name")
parser = OptionParser("%prog [options] <XML files>")
parser.add_option("-o", "--output", dest="output", default="mavtest", help="output folder [default: %default]")
(opts, args) = parser.parse_args()
if len(args) < 1:
......@@ -116,9 +119,9 @@ msgs = []
enums = []
for fname in args:
(m, e) = mavparse.parse_mavlink_xml(fname)
msgs.extend(m)
enums.extend(e)
(m, e) = mavparse.parse_mavlink_xml(fname)
msgs.extend(m)
enums.extend(e)
if mavparse.check_duplicates(msgs):
......
This diff is collapsed.
'''
module for loading/saving waypoints
'''
import os
if os.getenv('MAVLINK10'):
import mavlinkv10 as mavlink
else:
import mavlink
class MAVWPError(Exception):
'''MAVLink WP error class'''
def __init__(self, msg):
Exception.__init__(self, msg)
self.message = msg
class MAVWPLoader(object):
'''MAVLink waypoint loader'''
def __init__(self, target_system=0, target_component=0):
self.wpoints = []
self.target_system = target_system
self.target_component = target_component
def count(self):
'''return number of waypoints'''
return len(self.wpoints)
def wp(self, i):
'''return a waypoint'''
return self.wpoints[i]
def add(self, w):
'''add a waypoint'''
w.seq = self.count()
self.wpoints.append(w)
def remove(self, w):
'''remove a waypoint'''
self.wpoints.remove(w)
def clear(self):
'''clear waypoint list'''
self.wpoints = []
def _read_waypoint_v100(self, line):
'''read a version 100 waypoint'''
cmdmap = {
2 : mavlink.MAV_CMD_NAV_TAKEOFF,
3 : mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH,
4 : mavlink.MAV_CMD_NAV_LAND,
24: mavlink.MAV_CMD_NAV_TAKEOFF,
26: mavlink.MAV_CMD_NAV_LAND,
25: mavlink.MAV_CMD_NAV_WAYPOINT ,
27: mavlink.MAV_CMD_NAV_LOITER_UNLIM
}
a = line.split()
if len(a) != 13:
raise MAVWPError("invalid waypoint line with %u values" % len(a))
w = mavlink.MAVLink_waypoint_message(self.target_system, self.target_component,
int(a[0]), # seq
int(a[1]), # frame
int(a[2]), # action
int(a[7]), # current
int(a[12]), # autocontinue
float(a[5]), # param1,
float(a[6]), # param2,
float(a[3]), # param3
float(a[4]), # param4
float(a[9]), # x, latitude
float(a[8]), # y, longitude
float(a[10]) # z
)
if not w.command in cmdmap:
raise MAVWPError("Unknown v100 waypoint action %u" % w.command)
w.command = cmdmap[w.command]
return w
def _read_waypoint_v110(self, line):
'''read a version 110 waypoint'''
a = line.split()
if len(a) != 12:
raise MAVWPError("invalid waypoint line with %u values" % len(a))
w = mavlink.MAVLink_waypoint_message(self.target_system, self.target_component,
int(a[0]), # seq
int(a[2]), # frame
int(a[3]), # command
int(a[1]), # current
int(a[11]), # autocontinue
float(a[4]), # param1,
float(a[5]), # param2,
float(a[6]), # param3
float(a[7]), # param4
float(a[8]), # x (latitude)
float(a[9]), # y (longitude)
float(a[10]) # z (altitude)
)
return w
def load(self, filename):
'''load waypoints from a file.
returns number of waypoints loaded'''
f = open(filename, mode='r')
version_line = f.readline().strip()
if version_line == "QGC WPL 100":
readfn = self._read_waypoint_v100
elif version_line == "QGC WPL 110":
readfn = self._read_waypoint_v110
else:
f.close()
raise MAVWPError("Unsupported waypoint format '%s'" % version_line)
self.clear()
for line in f:
if line.startswith('#'):
continue
line = line.strip()
if not line:
continue
w = readfn(line)
if w is not None:
self.add(w)
f.close()
return len(self.wpoints)
def save(self, filename):
'''save waypoints to a file'''
f = open(filename, mode='w')
f.write("QGC WPL 110\n")
for w in self.wpoints:
f.write("%u\t%u\t%u\t%u\t%f\t%f\t%f\t%f\t%f\t%f\t%f\t%u\n" % (
w.seq, w.current, w.frame, w.command,
w.param1, w.param2, w.param3, w.param4,
w.x, w.y, w.z, w.autocontinue))
f.close()
class MAVFenceError(Exception):
'''MAVLink fence error class'''
def __init__(self, msg):
Exception.__init__(self, msg)
self.message = msg
class MAVFenceLoader(object):
'''MAVLink geo-fence loader'''
def __init__(self, target_system=0, target_component=0):
self.points = []
self.target_system = target_system
self.target_component = target_component
def count(self):
'''return number of points'''
return len(self.points)
def point(self, i):
'''return a point'''
return self.points[i]
def add(self, p):
'''add a point'''
self.points.append(p)
def clear(self):
'''clear point list'''
self.points = []
def load(self, filename):
'''load points from a file.
returns number of points loaded'''
f = open(filename, mode='r')
self.clear()
for line in f:
if line.startswith('#'):
continue
line = line.strip()
if not line:
continue
a = line.split()
if len(a) != 2:
raise MAVFenceError("invalid fence point line: %s" % line)
p = mavlink.MAVLink_fence_point_message(self.target_system, self.target_component,
self.count(), 0, float(a[0]), float(a[1]))
self.add(p)
f.close()
for i in range(self.count()):
self.points[i].count = self.count()
return len(self.points)
def save(self, filename):
'''save fence points to a file'''
f = open(filename, mode='w')
for p in self.points:
f.write("%f\t%f\n" % (p.lat, p.lng))
f.close()
#!/usr/bin/env python
# this is taken from the pySerial documentation at
# http://pyserial.sourceforge.net/examples.html
import ctypes
import re
def ValidHandle(value):
if value == 0:
raise ctypes.WinError()
return value
NULL = 0
HDEVINFO = ctypes.c_int
BOOL = ctypes.c_int
CHAR = ctypes.c_char
PCTSTR = ctypes.c_char_p
HWND = ctypes.c_uint
DWORD = ctypes.c_ulong
PDWORD = ctypes.POINTER(DWORD)
ULONG = ctypes.c_ulong
ULONG_PTR = ctypes.POINTER(ULONG)
#~ PBYTE = ctypes.c_char_p
PBYTE = ctypes.c_void_p
class GUID(ctypes.Structure):
_fields_ = [
('Data1', ctypes.c_ulong),
('Data2', ctypes.c_ushort),
('Data3', ctypes.c_ushort),
('Data4', ctypes.c_ubyte*8),
]
def __str__(self):
return "{%08x-%04x-%04x-%s-%s}" % (
self.Data1,
self.Data2,
self.Data3,
''.join(["%02x" % d for d in self.Data4[:2]]),
''.join(["%02x" % d for d in self.Data4[2:]]),
)
class SP_DEVINFO_DATA(ctypes.Structure):
_fields_ = [
('cbSize', DWORD),
('ClassGuid', GUID),
('DevInst', DWORD),
('Reserved', ULONG_PTR),
]
def __str__(self):
return "ClassGuid:%s DevInst:%s" % (self.ClassGuid, self.DevInst)
PSP_DEVINFO_DATA = ctypes.POINTER(SP_DEVINFO_DATA)
class SP_DEVICE_INTERFACE_DATA(ctypes.Structure):
_fields_ = [
('cbSize', DWORD),
('InterfaceClassGuid', GUID),
('Flags', DWORD),
('Reserved', ULONG_PTR),
]
def __str__(self):
return "InterfaceClassGuid:%s Flags:%s" % (self.InterfaceClassGuid, self.Flags)
PSP_DEVICE_INTERFACE_DATA = ctypes.POINTER(SP_DEVICE_INTERFACE_DATA)
PSP_DEVICE_INTERFACE_DETAIL_DATA = ctypes.c_void_p
class dummy(ctypes.Structure):
_fields_=[("d1", DWORD), ("d2", CHAR)]
_pack_ = 1
SIZEOF_SP_DEVICE_INTERFACE_DETAIL_DATA_A = ctypes.sizeof(dummy)
SetupDiDestroyDeviceInfoList = ctypes.windll.setupapi.SetupDiDestroyDeviceInfoList
SetupDiDestroyDeviceInfoList.argtypes = [HDEVINFO]
SetupDiDestroyDeviceInfoList.restype = BOOL
SetupDiGetClassDevs = ctypes.windll.setupapi.SetupDiGetClassDevsA
SetupDiGetClassDevs.argtypes = [ctypes.POINTER(GUID), PCTSTR, HWND, DWORD]
SetupDiGetClassDevs.restype = ValidHandle # HDEVINFO
SetupDiEnumDeviceInterfaces = ctypes.windll.setupapi.SetupDiEnumDeviceInterfaces
SetupDiEnumDeviceInterfaces.argtypes = [HDEVINFO, PSP_DEVINFO_DATA, ctypes.POINTER(GUID), DWORD, PSP_DEVICE_INTERFACE_DATA]
SetupDiEnumDeviceInterfaces.restype = BOOL
SetupDiGetDeviceInterfaceDetail = ctypes.windll.setupapi.SetupDiGetDeviceInterfaceDetailA
SetupDiGetDeviceInterfaceDetail.argtypes = [HDEVINFO, PSP_DEVICE_INTERFACE_DATA, PSP_DEVICE_INTERFACE_DETAIL_DATA, DWORD, PDWORD, PSP_DEVINFO_DATA]
SetupDiGetDeviceInterfaceDetail.restype = BOOL
SetupDiGetDeviceRegistryProperty = ctypes.windll.setupapi.SetupDiGetDeviceRegistryPropertyA
SetupDiGetDeviceRegistryProperty.argtypes = [HDEVINFO, PSP_DEVINFO_DATA, DWORD, PDWORD, PBYTE, DWORD, PDWORD]
SetupDiGetDeviceRegistryProperty.restype = BOOL
GUID_CLASS_COMPORT = GUID(0x86e0d1e0L, 0x8089, 0x11d0,
(ctypes.c_ubyte*8)(0x9c, 0xe4, 0x08, 0x00, 0x3e, 0x30, 0x1f, 0x73))
DIGCF_PRESENT = 2
DIGCF_DEVICEINTERFACE = 16
INVALID_HANDLE_VALUE = 0
ERROR_INSUFFICIENT_BUFFER = 122
SPDRP_HARDWAREID = 1
SPDRP_FRIENDLYNAME = 12
SPDRP_LOCATION_INFORMATION = 13
ERROR_NO_MORE_ITEMS = 259
def comports(available_only=True):
"""This generator scans the device registry for com ports and yields
(order, port, desc, hwid). If available_only is true only return currently
existing ports. Order is a helper to get sorted lists. it can be ignored
otherwise."""
flags = DIGCF_DEVICEINTERFACE
if available_only:
flags |= DIGCF_PRESENT
g_hdi = SetupDiGetClassDevs(ctypes.byref(GUID_CLASS_COMPORT), None, NULL, flags);
#~ for i in range(256):
for dwIndex in range(256):
did = SP_DEVICE_INTERFACE_DATA()
did.cbSize = ctypes.sizeof(did)
if not SetupDiEnumDeviceInterfaces(
g_hdi,
None,
ctypes.byref(GUID_CLASS_COMPORT),
dwIndex,
ctypes.byref(did)
):
if ctypes.GetLastError() != ERROR_NO_MORE_ITEMS:
raise ctypes.WinError()
break
dwNeeded = DWORD()
# get the size
if not SetupDiGetDeviceInterfaceDetail(
g_hdi,
ctypes.byref(did),
None, 0, ctypes.byref(dwNeeded),
None
):
# Ignore ERROR_INSUFFICIENT_BUFFER
if ctypes.GetLastError() != ERROR_INSUFFICIENT_BUFFER:
raise ctypes.WinError()
# allocate buffer
class SP_DEVICE_INTERFACE_DETAIL_DATA_A(ctypes.Structure):
_fields_ = [
('cbSize', DWORD),
('DevicePath', CHAR*(dwNeeded.value - ctypes.sizeof(DWORD))),
]
def __str__(self):
return "DevicePath:%s" % (self.DevicePath,)
idd = SP_DEVICE_INTERFACE_DETAIL_DATA_A()
idd.cbSize = SIZEOF_SP_DEVICE_INTERFACE_DETAIL_DATA_A
devinfo = SP_DEVINFO_DATA()
devinfo.cbSize = ctypes.sizeof(devinfo)
if not SetupDiGetDeviceInterfaceDetail(
g_hdi,
ctypes.byref(did),
ctypes.byref(idd), dwNeeded, None,
ctypes.byref(devinfo)
):
raise ctypes.WinError()
# hardware ID
szHardwareID = ctypes.create_string_buffer(250)
if not SetupDiGetDeviceRegistryProperty(
g_hdi,
ctypes.byref(devinfo),
SPDRP_HARDWAREID,
None,
ctypes.byref(szHardwareID), ctypes.sizeof(szHardwareID) - 1,
None
):
# Ignore ERROR_INSUFFICIENT_BUFFER
if ctypes.GetLastError() != ERROR_INSUFFICIENT_BUFFER:
raise ctypes.WinError()
# friendly name
szFriendlyName = ctypes.create_string_buffer(1024)
if not SetupDiGetDeviceRegistryProperty(
g_hdi,
ctypes.byref(devinfo),
SPDRP_FRIENDLYNAME,
None,
ctypes.byref(szFriendlyName), ctypes.sizeof(szFriendlyName) - 1,
None
):
# Ignore ERROR_INSUFFICIENT_BUFFER
if ctypes.GetLastError() != ERROR_INSUFFICIENT_BUFFER:
#~ raise ctypes.WinError()
# not getting friendly name for com0com devices, try something else
szFriendlyName = ctypes.create_string_buffer(1024)
if SetupDiGetDeviceRegistryProperty(
g_hdi,
ctypes.byref(devinfo),
SPDRP_LOCATION_INFORMATION,
None,
ctypes.byref(szFriendlyName), ctypes.sizeof(szFriendlyName) - 1,
None
):
port_name = "\\\\.\\" + szFriendlyName.value
order = None
else:
port_name = szFriendlyName.value
order = None
else:
try:
m = re.search(r"\((.*?(\d+))\)", szFriendlyName.value)
#~ print szFriendlyName.value, m.groups()
port_name = m.group(1)
order = int(m.group(2))
except AttributeError, msg:
port_name = szFriendlyName.value
order = None
yield order, port_name, szFriendlyName.value, szHardwareID.value
SetupDiDestroyDeviceInfoList(g_hdi)
if __name__ == '__main__':
import serial
print "-"*78
print "Serial ports"
print "-"*78
for order, port, desc, hwid in sorted(comports()):
print "%-10s: %s (%s) ->" % (port, desc, hwid),
try:
serial.Serial(port) # test open
except serial.serialutil.SerialException:
print "can't be openend"
else:
print "Ready"
print
# list of all ports the system knows
print "-"*78
print "All serial ports (registry)"
print "-"*78
for order, port, desc, hwid in sorted(comports(False)):
print "%-10s: %s (%s)" % (port, desc, hwid)
// MESSAGE AHRS PACKING
#define MAVLINK_MSG_ID_AHRS 163
typedef struct __mavlink_ahrs_t
{
float omegaIx; ///< X gyro drift estimate rad/s
float omegaIy; ///< Y gyro drift estimate rad/s
float omegaIz; ///< Z gyro drift estimate rad/s
float accel_weight; ///< average accel_weight
float renorm_val; ///< average renormalisation value
float error_rp; ///< average error_roll_pitch value
float error_yaw; ///< average error_yaw value
} mavlink_ahrs_t;
#define MAVLINK_MSG_ID_AHRS_LEN 28
#define MAVLINK_MSG_ID_163_LEN 28
#define MAVLINK_MESSAGE_INFO_AHRS { \
"AHRS", \
7, \
{ { "omegaIx", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ahrs_t, omegaIx) }, \
{ "omegaIy", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ahrs_t, omegaIy) }, \
{ "omegaIz", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ahrs_t, omegaIz) }, \
{ "accel_weight", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ahrs_t, accel_weight) }, \
{ "renorm_val", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ahrs_t, renorm_val) }, \
{ "error_rp", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ahrs_t, error_rp) }, \
{ "error_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ahrs_t, error_yaw) }, \
} \
}
/**
* @brief Pack a ahrs message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param omegaIx X gyro drift estimate rad/s
* @param omegaIy Y gyro drift estimate rad/s
* @param omegaIz Z gyro drift estimate rad/s
* @param accel_weight average accel_weight
* @param renorm_val average renormalisation value
* @param error_rp average error_roll_pitch value
* @param error_yaw average error_yaw value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ahrs_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_float(buf, 0, omegaIx);
_mav_put_float(buf, 4, omegaIy);
_mav_put_float(buf, 8, omegaIz);
_mav_put_float(buf, 12, accel_weight);
_mav_put_float(buf, 16, renorm_val);
_mav_put_float(buf, 20, error_rp);
_mav_put_float(buf, 24, error_yaw);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_ahrs_t packet;
packet.omegaIx = omegaIx;
packet.omegaIy = omegaIy;
packet.omegaIz = omegaIz;
packet.accel_weight = accel_weight;
packet.renorm_val = renorm_val;
packet.error_rp = error_rp;
packet.error_yaw = error_yaw;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
msg->msgid = MAVLINK_MSG_ID_AHRS;
return mavlink_finalize_message(msg, system_id, component_id, 28);
}
/**
* @brief Pack a ahrs message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param omegaIx X gyro drift estimate rad/s
* @param omegaIy Y gyro drift estimate rad/s
* @param omegaIz Z gyro drift estimate rad/s
* @param accel_weight average accel_weight
* @param renorm_val average renormalisation value
* @param error_rp average error_roll_pitch value
* @param error_yaw average error_yaw value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ahrs_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float omegaIx,float omegaIy,float omegaIz,float accel_weight,float renorm_val,float error_rp,float error_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_float(buf, 0, omegaIx);
_mav_put_float(buf, 4, omegaIy);
_mav_put_float(buf, 8, omegaIz);
_mav_put_float(buf, 12, accel_weight);
_mav_put_float(buf, 16, renorm_val);
_mav_put_float(buf, 20, error_rp);
_mav_put_float(buf, 24, error_yaw);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_ahrs_t packet;
packet.omegaIx = omegaIx;
packet.omegaIy = omegaIy;
packet.omegaIz = omegaIz;
packet.accel_weight = accel_weight;
packet.renorm_val = renorm_val;
packet.error_rp = error_rp;
packet.error_yaw = error_yaw;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
msg->msgid = MAVLINK_MSG_ID_AHRS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28);
}
/**
* @brief Encode a ahrs struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param ahrs C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ahrs_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ahrs_t* ahrs)
{
return mavlink_msg_ahrs_pack(system_id, component_id, msg, ahrs->omegaIx, ahrs->omegaIy, ahrs->omegaIz, ahrs->accel_weight, ahrs->renorm_val, ahrs->error_rp, ahrs->error_yaw);
}
/**
* @brief Send a ahrs message
* @param chan MAVLink channel to send the message
*
* @param omegaIx X gyro drift estimate rad/s
* @param omegaIy Y gyro drift estimate rad/s
* @param omegaIz Z gyro drift estimate rad/s
* @param accel_weight average accel_weight
* @param renorm_val average renormalisation value
* @param error_rp average error_roll_pitch value
* @param error_yaw average error_yaw value
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_ahrs_send(mavlink_channel_t chan, float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_float(buf, 0, omegaIx);
_mav_put_float(buf, 4, omegaIy);
_mav_put_float(buf, 8, omegaIz);
_mav_put_float(buf, 12, accel_weight);
_mav_put_float(buf, 16, renorm_val);
_mav_put_float(buf, 20, error_rp);
_mav_put_float(buf, 24, error_yaw);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, buf, 28);
#else
mavlink_ahrs_t packet;
packet.omegaIx = omegaIx;
packet.omegaIy = omegaIy;
packet.omegaIz = omegaIz;
packet.accel_weight = accel_weight;
packet.renorm_val = renorm_val;
packet.error_rp = error_rp;
packet.error_yaw = error_yaw;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)&packet, 28);
#endif
}
#endif
// MESSAGE AHRS UNPACKING
/**
* @brief Get field omegaIx from ahrs message
*
* @return X gyro drift estimate rad/s
*/
static inline float mavlink_msg_ahrs_get_omegaIx(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field omegaIy from ahrs message
*
* @return Y gyro drift estimate rad/s
*/
static inline float mavlink_msg_ahrs_get_omegaIy(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field omegaIz from ahrs message
*
* @return Z gyro drift estimate rad/s
*/
static inline float mavlink_msg_ahrs_get_omegaIz(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field accel_weight from ahrs message
*
* @return average accel_weight
*/
static inline float mavlink_msg_ahrs_get_accel_weight(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field renorm_val from ahrs message
*
* @return average renormalisation value
*/
static inline float mavlink_msg_ahrs_get_renorm_val(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field error_rp from ahrs message
*
* @return average error_roll_pitch value
*/
static inline float mavlink_msg_ahrs_get_error_rp(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field error_yaw from ahrs message
*
* @return average error_yaw value
*/
static inline float mavlink_msg_ahrs_get_error_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Decode a ahrs message into a struct
*
* @param msg The message to decode
* @param ahrs C-struct to decode the message contents into
*/
static inline void mavlink_msg_ahrs_decode(const mavlink_message_t* msg, mavlink_ahrs_t* ahrs)
{
#if MAVLINK_NEED_BYTE_SWAP
ahrs->omegaIx = mavlink_msg_ahrs_get_omegaIx(msg);
ahrs->omegaIy = mavlink_msg_ahrs_get_omegaIy(msg);
ahrs->omegaIz = mavlink_msg_ahrs_get_omegaIz(msg);
ahrs->accel_weight = mavlink_msg_ahrs_get_accel_weight(msg);
ahrs->renorm_val = mavlink_msg_ahrs_get_renorm_val(msg);
ahrs->error_rp = mavlink_msg_ahrs_get_error_rp(msg);
ahrs->error_yaw = mavlink_msg_ahrs_get_error_yaw(msg);
#else
memcpy(ahrs, _MAV_PAYLOAD(msg), 28);
#endif
}
......@@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t compon
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
memcpy(_MAV_PAYLOAD(msg), buf, 12);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_ap_adc_t packet;
packet.adc1 = adc1;
......@@ -66,7 +66,7 @@ static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t compon
packet.adc5 = adc5;
packet.adc6 = adc6;
memcpy(_MAV_PAYLOAD(msg), &packet, 12);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
msg->msgid = MAVLINK_MSG_ID_AP_ADC;
......@@ -100,7 +100,7 @@ static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t c
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
memcpy(_MAV_PAYLOAD(msg), buf, 12);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_ap_adc_t packet;
packet.adc1 = adc1;
......@@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t c
packet.adc5 = adc5;
packet.adc6 = adc6;
memcpy(_MAV_PAYLOAD(msg), &packet, 12);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
msg->msgid = MAVLINK_MSG_ID_AP_ADC;
......
......@@ -60,7 +60,7 @@ static inline uint16_t mavlink_msg_dcm_pack(uint8_t system_id, uint8_t component
_mav_put_float(buf, 20, error_rp);
_mav_put_float(buf, 24, error_yaw);
memcpy(_MAV_PAYLOAD(msg), buf, 28);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_dcm_t packet;
packet.omegaIx = omegaIx;
......@@ -71,7 +71,7 @@ static inline uint16_t mavlink_msg_dcm_pack(uint8_t system_id, uint8_t component
packet.error_rp = error_rp;
packet.error_yaw = error_yaw;
memcpy(_MAV_PAYLOAD(msg), &packet, 28);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
msg->msgid = MAVLINK_MSG_ID_DCM;
......@@ -107,7 +107,7 @@ static inline uint16_t mavlink_msg_dcm_pack_chan(uint8_t system_id, uint8_t comp
_mav_put_float(buf, 20, error_rp);
_mav_put_float(buf, 24, error_yaw);
memcpy(_MAV_PAYLOAD(msg), buf, 28);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_dcm_t packet;
packet.omegaIx = omegaIx;
......@@ -118,7 +118,7 @@ static inline uint16_t mavlink_msg_dcm_pack_chan(uint8_t system_id, uint8_t comp
packet.error_rp = error_rp;
packet.error_yaw = error_yaw;
memcpy(_MAV_PAYLOAD(msg), &packet, 28);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
msg->msgid = MAVLINK_MSG_ID_DCM;
......
......@@ -76,7 +76,7 @@ static inline uint16_t mavlink_msg_digicam_configure_pack(uint8_t system_id, uin
_mav_put_uint8_t(buf, 10, extra_param);
_mav_put_float(buf, 11, extra_value);
memcpy(_MAV_PAYLOAD(msg), buf, 15);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15);
#else
mavlink_digicam_configure_t packet;
packet.target_system = target_system;
......@@ -91,7 +91,7 @@ static inline uint16_t mavlink_msg_digicam_configure_pack(uint8_t system_id, uin
packet.extra_param = extra_param;
packet.extra_value = extra_value;
memcpy(_MAV_PAYLOAD(msg), &packet, 15);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15);
#endif
msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE;
......@@ -135,7 +135,7 @@ static inline uint16_t mavlink_msg_digicam_configure_pack_chan(uint8_t system_id
_mav_put_uint8_t(buf, 10, extra_param);
_mav_put_float(buf, 11, extra_value);
memcpy(_MAV_PAYLOAD(msg), buf, 15);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15);
#else
mavlink_digicam_configure_t packet;
packet.target_system = target_system;
......@@ -150,7 +150,7 @@ static inline uint16_t mavlink_msg_digicam_configure_pack_chan(uint8_t system_id
packet.extra_param = extra_param;
packet.extra_value = extra_value;
memcpy(_MAV_PAYLOAD(msg), &packet, 15);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15);
#endif
msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE;
......
......@@ -72,7 +72,7 @@ static inline uint16_t mavlink_msg_digicam_control_pack(uint8_t system_id, uint8
_mav_put_uint8_t(buf, 8, extra_param);
_mav_put_float(buf, 9, extra_value);
memcpy(_MAV_PAYLOAD(msg), buf, 13);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 13);
#else
mavlink_digicam_control_t packet;
packet.target_system = target_system;
......@@ -86,7 +86,7 @@ static inline uint16_t mavlink_msg_digicam_control_pack(uint8_t system_id, uint8
packet.extra_param = extra_param;
packet.extra_value = extra_value;
memcpy(_MAV_PAYLOAD(msg), &packet, 13);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 13);
#endif
msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONTROL;
......@@ -128,7 +128,7 @@ static inline uint16_t mavlink_msg_digicam_control_pack_chan(uint8_t system_id,
_mav_put_uint8_t(buf, 8, extra_param);
_mav_put_float(buf, 9, extra_value);
memcpy(_MAV_PAYLOAD(msg), buf, 13);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 13);
#else
mavlink_digicam_control_t packet;
packet.target_system = target_system;
......@@ -142,7 +142,7 @@ static inline uint16_t mavlink_msg_digicam_control_pack_chan(uint8_t system_id,
packet.extra_param = extra_param;
packet.extra_value = extra_value;
memcpy(_MAV_PAYLOAD(msg), &packet, 13);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 13);
#endif
msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONTROL;
......
......@@ -44,14 +44,14 @@ static inline uint16_t mavlink_msg_fence_fetch_point_pack(uint8_t system_id, uin
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, idx);
memcpy(_MAV_PAYLOAD(msg), buf, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_fence_fetch_point_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
memcpy(_MAV_PAYLOAD(msg), &packet, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
msg->msgid = MAVLINK_MSG_ID_FENCE_FETCH_POINT;
......@@ -79,14 +79,14 @@ static inline uint16_t mavlink_msg_fence_fetch_point_pack_chan(uint8_t system_id
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, idx);
memcpy(_MAV_PAYLOAD(msg), buf, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_fence_fetch_point_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
memcpy(_MAV_PAYLOAD(msg), &packet, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
msg->msgid = MAVLINK_MSG_ID_FENCE_FETCH_POINT;
......
......@@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_fence_point_pack(uint8_t system_id, uint8_t c
_mav_put_float(buf, 4, lat);
_mav_put_float(buf, 8, lng);
memcpy(_MAV_PAYLOAD(msg), buf, 12);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_fence_point_t packet;
packet.target_system = target_system;
......@@ -66,7 +66,7 @@ static inline uint16_t mavlink_msg_fence_point_pack(uint8_t system_id, uint8_t c
packet.lat = lat;
packet.lng = lng;
memcpy(_MAV_PAYLOAD(msg), &packet, 12);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
msg->msgid = MAVLINK_MSG_ID_FENCE_POINT;
......@@ -100,7 +100,7 @@ static inline uint16_t mavlink_msg_fence_point_pack_chan(uint8_t system_id, uint
_mav_put_float(buf, 4, lat);
_mav_put_float(buf, 8, lng);
memcpy(_MAV_PAYLOAD(msg), buf, 12);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_fence_point_t packet;
packet.target_system = target_system;
......@@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_fence_point_pack_chan(uint8_t system_id, uint
packet.lat = lat;
packet.lng = lng;
memcpy(_MAV_PAYLOAD(msg), &packet, 12);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
msg->msgid = MAVLINK_MSG_ID_FENCE_POINT;
......
......@@ -48,7 +48,7 @@ static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t
_mav_put_uint8_t(buf, 3, breach_type);
_mav_put_uint32_t(buf, 4, breach_time);
memcpy(_MAV_PAYLOAD(msg), buf, 8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
#else
mavlink_fence_status_t packet;
packet.breach_status = breach_status;
......@@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t
packet.breach_type = breach_type;
packet.breach_time = breach_time;
memcpy(_MAV_PAYLOAD(msg), &packet, 8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
#endif
msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS;
......@@ -86,7 +86,7 @@ static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uin
_mav_put_uint8_t(buf, 3, breach_type);
_mav_put_uint32_t(buf, 4, breach_time);
memcpy(_MAV_PAYLOAD(msg), buf, 8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
#else
mavlink_fence_status_t packet;
packet.breach_status = breach_status;
......@@ -94,7 +94,7 @@ static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uin
packet.breach_type = breach_type;
packet.breach_time = breach_time;
memcpy(_MAV_PAYLOAD(msg), &packet, 8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
#endif
msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS;
......
......@@ -40,13 +40,13 @@ static inline uint16_t mavlink_msg_hwstatus_pack(uint8_t system_id, uint8_t comp
_mav_put_uint16_t(buf, 0, Vcc);
_mav_put_uint8_t(buf, 2, I2Cerr);
memcpy(_MAV_PAYLOAD(msg), buf, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_hwstatus_t packet;
packet.Vcc = Vcc;
packet.I2Cerr = I2Cerr;
memcpy(_MAV_PAYLOAD(msg), &packet, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
msg->msgid = MAVLINK_MSG_ID_HWSTATUS;
......@@ -72,13 +72,13 @@ static inline uint16_t mavlink_msg_hwstatus_pack_chan(uint8_t system_id, uint8_t
_mav_put_uint16_t(buf, 0, Vcc);
_mav_put_uint8_t(buf, 2, I2Cerr);
memcpy(_MAV_PAYLOAD(msg), buf, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_hwstatus_t packet;
packet.Vcc = Vcc;
packet.I2Cerr = I2Cerr;
memcpy(_MAV_PAYLOAD(msg), &packet, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
msg->msgid = MAVLINK_MSG_ID_HWSTATUS;
......
......@@ -40,13 +40,13 @@ static inline uint16_t mavlink_msg_meminfo_pack(uint8_t system_id, uint8_t compo
_mav_put_uint16_t(buf, 0, brkval);
_mav_put_uint16_t(buf, 2, freemem);
memcpy(_MAV_PAYLOAD(msg), buf, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_meminfo_t packet;
packet.brkval = brkval;
packet.freemem = freemem;
memcpy(_MAV_PAYLOAD(msg), &packet, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
msg->msgid = MAVLINK_MSG_ID_MEMINFO;
......@@ -72,13 +72,13 @@ static inline uint16_t mavlink_msg_meminfo_pack_chan(uint8_t system_id, uint8_t
_mav_put_uint16_t(buf, 0, brkval);
_mav_put_uint16_t(buf, 2, freemem);
memcpy(_MAV_PAYLOAD(msg), buf, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_meminfo_t packet;
packet.brkval = brkval;
packet.freemem = freemem;
memcpy(_MAV_PAYLOAD(msg), &packet, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
msg->msgid = MAVLINK_MSG_ID_MEMINFO;
......
......@@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_mount_configure_pack(uint8_t system_id, uint8
_mav_put_uint8_t(buf, 4, stab_pitch);
_mav_put_uint8_t(buf, 5, stab_yaw);
memcpy(_MAV_PAYLOAD(msg), buf, 6);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
#else
mavlink_mount_configure_t packet;
packet.target_system = target_system;
......@@ -66,7 +66,7 @@ static inline uint16_t mavlink_msg_mount_configure_pack(uint8_t system_id, uint8
packet.stab_pitch = stab_pitch;
packet.stab_yaw = stab_yaw;
memcpy(_MAV_PAYLOAD(msg), &packet, 6);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
#endif
msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE;
......@@ -100,7 +100,7 @@ static inline uint16_t mavlink_msg_mount_configure_pack_chan(uint8_t system_id,
_mav_put_uint8_t(buf, 4, stab_pitch);
_mav_put_uint8_t(buf, 5, stab_yaw);
memcpy(_MAV_PAYLOAD(msg), buf, 6);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
#else
mavlink_mount_configure_t packet;
packet.target_system = target_system;
......@@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_mount_configure_pack_chan(uint8_t system_id,
packet.stab_pitch = stab_pitch;
packet.stab_yaw = stab_yaw;
memcpy(_MAV_PAYLOAD(msg), &packet, 6);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
#endif
msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE;
......
......@@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_mount_control_pack(uint8_t system_id, uint8_t
_mav_put_int32_t(buf, 10, input_c);
_mav_put_uint8_t(buf, 14, save_position);
memcpy(_MAV_PAYLOAD(msg), buf, 15);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15);
#else
mavlink_mount_control_t packet;
packet.target_system = target_system;
......@@ -66,7 +66,7 @@ static inline uint16_t mavlink_msg_mount_control_pack(uint8_t system_id, uint8_t
packet.input_c = input_c;
packet.save_position = save_position;
memcpy(_MAV_PAYLOAD(msg), &packet, 15);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15);
#endif
msg->msgid = MAVLINK_MSG_ID_MOUNT_CONTROL;
......@@ -100,7 +100,7 @@ static inline uint16_t mavlink_msg_mount_control_pack_chan(uint8_t system_id, ui
_mav_put_int32_t(buf, 10, input_c);
_mav_put_uint8_t(buf, 14, save_position);
memcpy(_MAV_PAYLOAD(msg), buf, 15);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15);
#else
mavlink_mount_control_t packet;
packet.target_system = target_system;
......@@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_mount_control_pack_chan(uint8_t system_id, ui
packet.input_c = input_c;
packet.save_position = save_position;
memcpy(_MAV_PAYLOAD(msg), &packet, 15);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15);
#endif
msg->msgid = MAVLINK_MSG_ID_MOUNT_CONTROL;
......
......@@ -52,7 +52,7 @@ static inline uint16_t mavlink_msg_mount_status_pack(uint8_t system_id, uint8_t
_mav_put_int32_t(buf, 6, pointing_b);
_mav_put_int32_t(buf, 10, pointing_c);
memcpy(_MAV_PAYLOAD(msg), buf, 14);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
#else
mavlink_mount_status_t packet;
packet.target_system = target_system;
......@@ -61,7 +61,7 @@ static inline uint16_t mavlink_msg_mount_status_pack(uint8_t system_id, uint8_t
packet.pointing_b = pointing_b;
packet.pointing_c = pointing_c;
memcpy(_MAV_PAYLOAD(msg), &packet, 14);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
#endif
msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS;
......@@ -93,7 +93,7 @@ static inline uint16_t mavlink_msg_mount_status_pack_chan(uint8_t system_id, uin
_mav_put_int32_t(buf, 6, pointing_b);
_mav_put_int32_t(buf, 10, pointing_c);
memcpy(_MAV_PAYLOAD(msg), buf, 14);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
#else
mavlink_mount_status_t packet;
packet.target_system = target_system;
......@@ -102,7 +102,7 @@ static inline uint16_t mavlink_msg_mount_status_pack_chan(uint8_t system_id, uin
packet.pointing_b = pointing_b;
packet.pointing_c = pointing_c;
memcpy(_MAV_PAYLOAD(msg), &packet, 14);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
#endif
msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS;
......
// MESSAGE RADIO PACKING
#define MAVLINK_MSG_ID_RADIO 166
typedef struct __mavlink_radio_t
{
uint8_t rssi; ///< local signal strength
uint8_t remrssi; ///< remote signal strength
uint8_t txbuf; ///< how full the tx buffer is as a percentage
uint8_t noise; ///< background noise level
uint8_t remnoise; ///< remote background noise level
uint16_t rxerrors; ///< receive errors
uint16_t fixed; ///< count of error corrected packets
} mavlink_radio_t;
#define MAVLINK_MSG_ID_RADIO_LEN 9
#define MAVLINK_MSG_ID_166_LEN 9
#define MAVLINK_MESSAGE_INFO_RADIO { \
"RADIO", \
7, \
{ { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_radio_t, rssi) }, \
{ "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_radio_t, remrssi) }, \
{ "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_radio_t, txbuf) }, \
{ "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_radio_t, noise) }, \
{ "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_t, remnoise) }, \
{ "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 5, offsetof(mavlink_radio_t, rxerrors) }, \
{ "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 7, offsetof(mavlink_radio_t, fixed) }, \
} \
}
/**
* @brief Pack a radio message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param rssi local signal strength
* @param remrssi remote signal strength
* @param txbuf how full the tx buffer is as a percentage
* @param noise background noise level
* @param remnoise remote background noise level
* @param rxerrors receive errors
* @param fixed count of error corrected packets
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint8_t(buf, 0, rssi);
_mav_put_uint8_t(buf, 1, remrssi);
_mav_put_uint8_t(buf, 2, txbuf);
_mav_put_uint8_t(buf, 3, noise);
_mav_put_uint8_t(buf, 4, remnoise);
_mav_put_uint16_t(buf, 5, rxerrors);
_mav_put_uint16_t(buf, 7, fixed);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9);
#else
mavlink_radio_t packet;
packet.rssi = rssi;
packet.remrssi = remrssi;
packet.txbuf = txbuf;
packet.noise = noise;
packet.remnoise = remnoise;
packet.rxerrors = rxerrors;
packet.fixed = fixed;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9);
#endif
msg->msgid = MAVLINK_MSG_ID_RADIO;
return mavlink_finalize_message(msg, system_id, component_id, 9);
}
/**
* @brief Pack a radio message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param rssi local signal strength
* @param remrssi remote signal strength
* @param txbuf how full the tx buffer is as a percentage
* @param noise background noise level
* @param remnoise remote background noise level
* @param rxerrors receive errors
* @param fixed count of error corrected packets
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint8_t noise,uint8_t remnoise,uint16_t rxerrors,uint16_t fixed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint8_t(buf, 0, rssi);
_mav_put_uint8_t(buf, 1, remrssi);
_mav_put_uint8_t(buf, 2, txbuf);
_mav_put_uint8_t(buf, 3, noise);
_mav_put_uint8_t(buf, 4, remnoise);
_mav_put_uint16_t(buf, 5, rxerrors);
_mav_put_uint16_t(buf, 7, fixed);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9);
#else
mavlink_radio_t packet;
packet.rssi = rssi;
packet.remrssi = remrssi;
packet.txbuf = txbuf;
packet.noise = noise;
packet.remnoise = remnoise;
packet.rxerrors = rxerrors;
packet.fixed = fixed;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9);
#endif
msg->msgid = MAVLINK_MSG_ID_RADIO;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9);
}
/**
* @brief Encode a radio struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param radio C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_radio_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_t* radio)
{
return mavlink_msg_radio_pack(system_id, component_id, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed);
}
/**
* @brief Send a radio message
* @param chan MAVLink channel to send the message
*
* @param rssi local signal strength
* @param remrssi remote signal strength
* @param txbuf how full the tx buffer is as a percentage
* @param noise background noise level
* @param remnoise remote background noise level
* @param rxerrors receive errors
* @param fixed count of error corrected packets
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint8_t(buf, 0, rssi);
_mav_put_uint8_t(buf, 1, remrssi);
_mav_put_uint8_t(buf, 2, txbuf);
_mav_put_uint8_t(buf, 3, noise);
_mav_put_uint8_t(buf, 4, remnoise);
_mav_put_uint16_t(buf, 5, rxerrors);
_mav_put_uint16_t(buf, 7, fixed);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, 9);
#else
mavlink_radio_t packet;
packet.rssi = rssi;
packet.remrssi = remrssi;
packet.txbuf = txbuf;
packet.noise = noise;
packet.remnoise = remnoise;
packet.rxerrors = rxerrors;
packet.fixed = fixed;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, 9);
#endif
}
#endif
// MESSAGE RADIO UNPACKING
/**
* @brief Get field rssi from radio message
*
* @return local signal strength
*/
static inline uint8_t mavlink_msg_radio_get_rssi(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field remrssi from radio message
*
* @return remote signal strength
*/
static inline uint8_t mavlink_msg_radio_get_remrssi(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field txbuf from radio message
*
* @return how full the tx buffer is as a percentage
*/
static inline uint8_t mavlink_msg_radio_get_txbuf(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Get field noise from radio message
*
* @return background noise level
*/
static inline uint8_t mavlink_msg_radio_get_noise(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
/**
* @brief Get field remnoise from radio message
*
* @return remote background noise level
*/
static inline uint8_t mavlink_msg_radio_get_remnoise(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field rxerrors from radio message
*
* @return receive errors
*/
static inline uint16_t mavlink_msg_radio_get_rxerrors(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 5);
}
/**
* @brief Get field fixed from radio message
*
* @return count of error corrected packets
*/
static inline uint16_t mavlink_msg_radio_get_fixed(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 7);
}
/**
* @brief Decode a radio message into a struct
*
* @param msg The message to decode
* @param radio C-struct to decode the message contents into
*/
static inline void mavlink_msg_radio_decode(const mavlink_message_t* msg, mavlink_radio_t* radio)
{
#if MAVLINK_NEED_BYTE_SWAP
radio->rssi = mavlink_msg_radio_get_rssi(msg);
radio->remrssi = mavlink_msg_radio_get_remrssi(msg);
radio->txbuf = mavlink_msg_radio_get_txbuf(msg);
radio->noise = mavlink_msg_radio_get_noise(msg);
radio->remnoise = mavlink_msg_radio_get_remnoise(msg);
radio->rxerrors = mavlink_msg_radio_get_rxerrors(msg);
radio->fixed = mavlink_msg_radio_get_fixed(msg);
#else
memcpy(radio, _MAV_PAYLOAD(msg), 9);
#endif
}
......@@ -80,7 +80,7 @@ static inline uint16_t mavlink_msg_sensor_offsets_pack(uint8_t system_id, uint8_
_mav_put_float(buf, 34, accel_cal_y);
_mav_put_float(buf, 38, accel_cal_z);
memcpy(_MAV_PAYLOAD(msg), buf, 42);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 42);
#else
mavlink_sensor_offsets_t packet;
packet.mag_ofs_x = mag_ofs_x;
......@@ -96,7 +96,7 @@ static inline uint16_t mavlink_msg_sensor_offsets_pack(uint8_t system_id, uint8_
packet.accel_cal_y = accel_cal_y;
packet.accel_cal_z = accel_cal_z;
memcpy(_MAV_PAYLOAD(msg), &packet, 42);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 42);
#endif
msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS;
......@@ -142,7 +142,7 @@ static inline uint16_t mavlink_msg_sensor_offsets_pack_chan(uint8_t system_id, u
_mav_put_float(buf, 34, accel_cal_y);
_mav_put_float(buf, 38, accel_cal_z);
memcpy(_MAV_PAYLOAD(msg), buf, 42);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 42);
#else
mavlink_sensor_offsets_t packet;
packet.mag_ofs_x = mag_ofs_x;
......@@ -158,7 +158,7 @@ static inline uint16_t mavlink_msg_sensor_offsets_pack_chan(uint8_t system_id, u
packet.accel_cal_y = accel_cal_y;
packet.accel_cal_z = accel_cal_z;
memcpy(_MAV_PAYLOAD(msg), &packet, 42);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 42);
#endif
msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS;
......
......@@ -52,7 +52,7 @@ static inline uint16_t mavlink_msg_set_mag_offsets_pack(uint8_t system_id, uint8
_mav_put_int16_t(buf, 4, mag_ofs_y);
_mav_put_int16_t(buf, 6, mag_ofs_z);
memcpy(_MAV_PAYLOAD(msg), buf, 8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
#else
mavlink_set_mag_offsets_t packet;
packet.target_system = target_system;
......@@ -61,7 +61,7 @@ static inline uint16_t mavlink_msg_set_mag_offsets_pack(uint8_t system_id, uint8
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
memcpy(_MAV_PAYLOAD(msg), &packet, 8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
#endif
msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
......@@ -93,7 +93,7 @@ static inline uint16_t mavlink_msg_set_mag_offsets_pack_chan(uint8_t system_id,
_mav_put_int16_t(buf, 4, mag_ofs_y);
_mav_put_int16_t(buf, 6, mag_ofs_z);
memcpy(_MAV_PAYLOAD(msg), buf, 8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
#else
mavlink_set_mag_offsets_t packet;
packet.target_system = target_system;
......@@ -102,7 +102,7 @@ static inline uint16_t mavlink_msg_set_mag_offsets_pack_chan(uint8_t system_id,
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
memcpy(_MAV_PAYLOAD(msg), &packet, 8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
#endif
msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
......
......@@ -68,7 +68,7 @@ static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t comp
_mav_put_float(buf, 28, ygyro);
_mav_put_float(buf, 32, zgyro);
memcpy(_MAV_PAYLOAD(msg), buf, 36);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36);
#else
mavlink_simstate_t packet;
packet.roll = roll;
......@@ -81,7 +81,7 @@ static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t comp
packet.ygyro = ygyro;
packet.zgyro = zgyro;
memcpy(_MAV_PAYLOAD(msg), &packet, 36);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36);
#endif
msg->msgid = MAVLINK_MSG_ID_SIMSTATE;
......@@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t
_mav_put_float(buf, 28, ygyro);
_mav_put_float(buf, 32, zgyro);
memcpy(_MAV_PAYLOAD(msg), buf, 36);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36);
#else
mavlink_simstate_t packet;
packet.roll = roll;
......@@ -134,7 +134,7 @@ static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t
packet.ygyro = ygyro;
packet.zgyro = zgyro;
memcpy(_MAV_PAYLOAD(msg), &packet, 36);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36);
#endif
msg->msgid = MAVLINK_MSG_ID_SIMSTATE;
......
This diff is collapsed.
......@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Mar 1 01:19:37 2012"
#define MAVLINK_BUILD_DATE "Thu Apr 19 19:46:08 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
......
......@@ -44,14 +44,14 @@ static inline uint16_t mavlink_msg_action_pack(uint8_t system_id, uint8_t compon
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, action);
memcpy(_MAV_PAYLOAD(msg), buf, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_action_t packet;
packet.target = target;
packet.target_component = target_component;
packet.action = action;
memcpy(_MAV_PAYLOAD(msg), &packet, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
msg->msgid = MAVLINK_MSG_ID_ACTION;
......@@ -79,14 +79,14 @@ static inline uint16_t mavlink_msg_action_pack_chan(uint8_t system_id, uint8_t c
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, action);
memcpy(_MAV_PAYLOAD(msg), buf, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_action_t packet;
packet.target = target;
packet.target_component = target_component;
packet.action = action;
memcpy(_MAV_PAYLOAD(msg), &packet, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
msg->msgid = MAVLINK_MSG_ID_ACTION;
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
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