22 changed files with 3958 additions and 1477 deletions
@ -0,0 +1,89 @@
@@ -0,0 +1,89 @@
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
#ifndef _CHECKSUM_H_ |
||||
#define _CHECKSUM_H_ |
||||
|
||||
|
||||
/**
|
||||
* |
||||
* CALCULATE THE CHECKSUM |
||||
* |
||||
*/ |
||||
|
||||
#define X25_INIT_CRC 0xffff |
||||
#define X25_VALIDATE_CRC 0xf0b8 |
||||
|
||||
/**
|
||||
* @brief Accumulate the X.25 CRC by adding one char at a time. |
||||
* |
||||
* The checksum function adds the hash of one char at a time to the |
||||
* 16 bit checksum (uint16_t). |
||||
* |
||||
* @param data new char to hash |
||||
* @param crcAccum the already accumulated checksum |
||||
**/ |
||||
static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum) |
||||
{ |
||||
/*Accumulate one byte of data into the CRC*/ |
||||
uint8_t tmp; |
||||
|
||||
tmp = data ^ (uint8_t)(*crcAccum &0xff); |
||||
tmp ^= (tmp<<4); |
||||
*crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Initiliaze the buffer for the X.25 CRC |
||||
* |
||||
* @param crcAccum the 16 bit X.25 CRC |
||||
*/ |
||||
static inline void crc_init(uint16_t* crcAccum) |
||||
{ |
||||
*crcAccum = X25_INIT_CRC; |
||||
} |
||||
|
||||
|
||||
/**
|
||||
* @brief Calculates the X.25 checksum on a byte buffer |
||||
* |
||||
* @param pBuffer buffer containing the byte array to hash |
||||
* @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) |
||||
{ |
||||
uint16_t crcTmp; |
||||
crc_init(&crcTmp); |
||||
while (length--) { |
||||
crc_accumulate(*pBuffer++, &crcTmp); |
||||
} |
||||
return crcTmp; |
||||
} |
||||
|
||||
/**
|
||||
* @brief Accumulate the X.25 CRC by adding an array of bytes |
||||
* |
||||
* The checksum function adds the hash of one char at a time to the |
||||
* 16 bit checksum (uint16_t). |
||||
* |
||||
* @param data new bytes to hash |
||||
* @param crcAccum the already accumulated checksum |
||||
**/ |
||||
static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint8_t length) |
||||
{ |
||||
const uint8_t *p = (const uint8_t *)pBuffer; |
||||
while (length--) { |
||||
crc_accumulate(*p++, crcAccum); |
||||
} |
||||
} |
||||
|
||||
|
||||
|
||||
|
||||
#endif /* _CHECKSUM_H_ */ |
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
@ -0,0 +1,488 @@
@@ -0,0 +1,488 @@
|
||||
#ifndef _MAVLINK_HELPERS_H_ |
||||
#define _MAVLINK_HELPERS_H_ |
||||
|
||||
#include "string.h" |
||||
#include "checksum.h" |
||||
#include "mavlink_types.h" |
||||
|
||||
#ifndef MAVLINK_HELPER |
||||
#define MAVLINK_HELPER |
||||
#endif |
||||
|
||||
/*
|
||||
internal function to give access to the channel status for each channel |
||||
*/ |
||||
MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan) |
||||
{ |
||||
static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS]; |
||||
return &m_mavlink_status[chan]; |
||||
} |
||||
|
||||
/**
|
||||
* @brief Finalize a MAVLink message with channel assignment |
||||
* |
||||
* This function calculates the checksum and sets length and aircraft id correctly. |
||||
* It assumes that the message id and the payload are already correctly set. This function |
||||
* can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack |
||||
* instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead. |
||||
* |
||||
* @param msg Message to finalize |
||||
* @param system_id Id of the sending (this) system, 1-127 |
||||
* @param length Message length |
||||
*/ |
||||
#if MAVLINK_CRC_EXTRA |
||||
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
|
||||
uint8_t chan, uint8_t length, uint8_t crc_extra) |
||||
#else |
||||
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
|
||||
uint8_t chan, uint8_t length) |
||||
#endif |
||||
{ |
||||
// This code part is the same for all messages;
|
||||
uint16_t checksum; |
||||
msg->magic = MAVLINK_STX; |
||||
msg->len = length; |
||||
msg->sysid = system_id; |
||||
msg->compid = component_id; |
||||
// One sequence number per component
|
||||
msg->seq = mavlink_get_channel_status(chan)->current_tx_seq; |
||||
mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1; |
||||
checksum = crc_calculate((uint8_t*)&msg->len, length + MAVLINK_CORE_HEADER_LEN); |
||||
#if MAVLINK_CRC_EXTRA |
||||
crc_accumulate(crc_extra, &checksum); |
||||
#endif |
||||
mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF); |
||||
mavlink_ck_b(msg) = (uint8_t)(checksum >> 8); |
||||
|
||||
return length + MAVLINK_NUM_NON_PAYLOAD_BYTES; |
||||
} |
||||
|
||||
|
||||
/**
|
||||
* @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel |
||||
*/ |
||||
#if MAVLINK_CRC_EXTRA |
||||
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
|
||||
uint8_t length, uint8_t crc_extra) |
||||
{ |
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length, crc_extra); |
||||
} |
||||
#else |
||||
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
|
||||
uint8_t length) |
||||
{ |
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length); |
||||
} |
||||
#endif |
||||
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
||||
MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); |
||||
|
||||
/**
|
||||
* @brief Finalize a MAVLink message with channel assignment and send |
||||
*/ |
||||
#if MAVLINK_CRC_EXTRA |
||||
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
|
||||
uint8_t length, uint8_t crc_extra) |
||||
#else |
||||
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length) |
||||
#endif |
||||
{ |
||||
uint16_t checksum; |
||||
uint8_t buf[MAVLINK_NUM_HEADER_BYTES]; |
||||
uint8_t ck[2]; |
||||
mavlink_status_t *status = mavlink_get_channel_status(chan); |
||||
buf[0] = MAVLINK_STX; |
||||
buf[1] = length; |
||||
buf[2] = status->current_tx_seq; |
||||
buf[3] = mavlink_system.sysid; |
||||
buf[4] = mavlink_system.compid; |
||||
buf[5] = msgid; |
||||
status->current_tx_seq++; |
||||
checksum = crc_calculate((uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN); |
||||
crc_accumulate_buffer(&checksum, packet, length); |
||||
#if MAVLINK_CRC_EXTRA |
||||
crc_accumulate(crc_extra, &checksum); |
||||
#endif |
||||
ck[0] = (uint8_t)(checksum & 0xFF); |
||||
ck[1] = (uint8_t)(checksum >> 8); |
||||
|
||||
MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); |
||||
_mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES); |
||||
_mavlink_send_uart(chan, packet, length); |
||||
_mavlink_send_uart(chan, (const char *)ck, 2); |
||||
MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); |
||||
} |
||||
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
/**
|
||||
* @brief Pack a message to send it over a serial byte stream |
||||
*/ |
||||
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); |
||||
return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len; |
||||
} |
||||
|
||||
union __mavlink_bitfield { |
||||
uint8_t uint8; |
||||
int8_t int8; |
||||
uint16_t uint16; |
||||
int16_t int16; |
||||
uint32_t uint32; |
||||
int32_t int32; |
||||
}; |
||||
|
||||
|
||||
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg) |
||||
{ |
||||
crc_init(&msg->checksum); |
||||
} |
||||
|
||||
MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) |
||||
{ |
||||
crc_accumulate(c, &msg->checksum); |
||||
} |
||||
|
||||
/**
|
||||
* This is a convenience function which handles the complete MAVLink parsing. |
||||
* the function will parse one byte at a time and return the complete packet once |
||||
* it could be successfully decoded. Checksum and other failures will be silently |
||||
* ignored. |
||||
* |
||||
* @param chan ID of the current channel. This allows to parse different channels with this function. |
||||
* a channel is not a physical message channel like a serial port, but a logic partition of |
||||
* the communication streams in this case. COMM_NB is the limit for the number of channels |
||||
* on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows |
||||
* @param c The char to barse |
||||
* |
||||
* @param returnMsg NULL if no message could be decoded, the message data else |
||||
* @return 0 if no message could be decoded, 1 else |
||||
* |
||||
* A typical use scenario of this function call is: |
||||
* |
||||
* @code |
||||
* #include <inttypes.h> // For fixed-width uint8_t type
|
||||
* |
||||
* mavlink_message_t msg; |
||||
* int chan = 0; |
||||
* |
||||
* |
||||
* while(serial.bytesAvailable > 0) |
||||
* { |
||||
* uint8_t byte = serial.getNextByte(); |
||||
* if (mavlink_parse_char(chan, byte, &msg)) |
||||
* { |
||||
* printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); |
||||
* } |
||||
* } |
||||
* |
||||
* |
||||
* @endcode |
||||
*/ |
||||
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 |
||||
*/ |
||||
#if MAVLINK_CRC_EXTRA |
||||
#ifndef MAVLINK_MESSAGE_CRC |
||||
static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS; |
||||
#define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid] |
||||
#endif |
||||
#endif |
||||
|
||||
mavlink_message_t* rxmsg = &m_mavlink_message[chan]; ///< The currently decoded message
|
||||
mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status
|
||||
int bufferIndex = 0; |
||||
|
||||
status->msg_received = 0; |
||||
|
||||
switch (status->parse_state) |
||||
{ |
||||
case MAVLINK_PARSE_STATE_UNINIT: |
||||
case MAVLINK_PARSE_STATE_IDLE: |
||||
if (c == MAVLINK_STX) |
||||
{ |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; |
||||
rxmsg->len = 0; |
||||
mavlink_start_checksum(rxmsg); |
||||
} |
||||
break; |
||||
|
||||
case MAVLINK_PARSE_STATE_GOT_STX: |
||||
if (status->msg_received
|
||||
/* Support shorter buffers than the
|
||||
default maximum packet size */ |
||||
#if (MAVLINK_MAX_PAYLOAD_LEN < 255) |
||||
|| c > MAVLINK_MAX_PAYLOAD_LEN |
||||
#endif |
||||
) |
||||
{ |
||||
status->buffer_overrun++; |
||||
status->parse_error++; |
||||
status->msg_received = 0; |
||||
status->parse_state = MAVLINK_PARSE_STATE_IDLE; |
||||
} |
||||
else |
||||
{ |
||||
// NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2
|
||||
rxmsg->len = c; |
||||
status->packet_idx = 0; |
||||
mavlink_update_checksum(rxmsg, c); |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH; |
||||
} |
||||
break; |
||||
|
||||
case MAVLINK_PARSE_STATE_GOT_LENGTH: |
||||
rxmsg->seq = c; |
||||
mavlink_update_checksum(rxmsg, c); |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ; |
||||
break; |
||||
|
||||
case MAVLINK_PARSE_STATE_GOT_SEQ: |
||||
rxmsg->sysid = c; |
||||
mavlink_update_checksum(rxmsg, c); |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID; |
||||
break; |
||||
|
||||
case MAVLINK_PARSE_STATE_GOT_SYSID: |
||||
rxmsg->compid = c; |
||||
mavlink_update_checksum(rxmsg, c); |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID; |
||||
break; |
||||
|
||||
case MAVLINK_PARSE_STATE_GOT_COMPID: |
||||
rxmsg->msgid = c; |
||||
mavlink_update_checksum(rxmsg, c); |
||||
if (rxmsg->len == 0) |
||||
{ |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; |
||||
} |
||||
else |
||||
{ |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID; |
||||
} |
||||
break; |
||||
|
||||
case MAVLINK_PARSE_STATE_GOT_MSGID: |
||||
_MAV_PAYLOAD(rxmsg)[status->packet_idx++] = (char)c; |
||||
mavlink_update_checksum(rxmsg, c); |
||||
if (status->packet_idx == rxmsg->len) |
||||
{ |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; |
||||
} |
||||
break; |
||||
|
||||
case MAVLINK_PARSE_STATE_GOT_PAYLOAD: |
||||
#if MAVLINK_CRC_EXTRA |
||||
mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid)); |
||||
#endif |
||||
if (c != (rxmsg->checksum & 0xFF)) { |
||||
// Check first checksum byte
|
||||
status->parse_error++; |
||||
status->msg_received = 0; |
||||
status->parse_state = MAVLINK_PARSE_STATE_IDLE; |
||||
if (c == MAVLINK_STX) |
||||
{ |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; |
||||
rxmsg->len = 0; |
||||
mavlink_start_checksum(rxmsg); |
||||
} |
||||
} |
||||
else |
||||
{ |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; |
||||
} |
||||
break; |
||||
|
||||
case MAVLINK_PARSE_STATE_GOT_CRC1: |
||||
if (c != (rxmsg->checksum >> 8)) { |
||||
// Check second checksum byte
|
||||
status->parse_error++; |
||||
status->msg_received = 0; |
||||
status->parse_state = MAVLINK_PARSE_STATE_IDLE; |
||||
if (c == MAVLINK_STX) |
||||
{ |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; |
||||
rxmsg->len = 0; |
||||
mavlink_start_checksum(rxmsg); |
||||
} |
||||
} |
||||
else |
||||
{ |
||||
// Successfully got message
|
||||
status->msg_received = 1; |
||||
status->parse_state = MAVLINK_PARSE_STATE_IDLE; |
||||
memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); |
||||
} |
||||
break; |
||||
} |
||||
|
||||
bufferIndex++; |
||||
// If a message has been sucessfully decoded, check index
|
||||
if (status->msg_received == 1) |
||||
{ |
||||
//while(status->current_seq != rxmsg->seq)
|
||||
//{
|
||||
// status->packet_rx_drop_count++;
|
||||
// status->current_seq++;
|
||||
//}
|
||||
status->current_rx_seq = rxmsg->seq; |
||||
// Initial condition: If no packet has been received so far, drop count is undefined
|
||||
if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0; |
||||
// Count this packet as received
|
||||
status->packet_rx_success_count++; |
||||
} |
||||
|
||||
r_mavlink_status->current_rx_seq = status->current_rx_seq+1; |
||||
r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; |
||||
r_mavlink_status->packet_rx_drop_count = status->parse_error; |
||||
status->parse_error = 0; |
||||
return status->msg_received; |
||||
} |
||||
|
||||
/**
|
||||
* @brief Put a bitfield of length 1-32 bit into the buffer |
||||
* |
||||
* @param b the value to add, will be encoded in the bitfield |
||||
* @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc. |
||||
* @param packet_index the position in the packet (the index of the first byte to use) |
||||
* @param bit_index the position in the byte (the index of the first bit to use) |
||||
* @param buffer packet buffer to write into |
||||
* @return new position of the last used byte in the buffer |
||||
*/ |
||||
MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer) |
||||
{ |
||||
uint16_t bits_remain = bits; |
||||
// Transform number into network order
|
||||
int32_t v; |
||||
uint8_t i_bit_index, i_byte_index, curr_bits_n; |
||||
#if MAVLINK_NEED_BYTE_SWAP |
||||
union { |
||||
int32_t i; |
||||
uint8_t b[4]; |
||||
} bin, bout; |
||||
bin.i = b; |
||||
bout.b[0] = bin.b[3]; |
||||
bout.b[1] = bin.b[2]; |
||||
bout.b[2] = bin.b[1]; |
||||
bout.b[3] = bin.b[0]; |
||||
v = bout.i; |
||||
#else |
||||
v = b; |
||||
#endif |
||||
|
||||
// buffer in
|
||||
// 01100000 01000000 00000000 11110001
|
||||
// buffer out
|
||||
// 11110001 00000000 01000000 01100000
|
||||
|
||||
// Existing partly filled byte (four free slots)
|
||||
// 0111xxxx
|
||||
|
||||
// Mask n free bits
|
||||
// 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1
|
||||
// = ((uint32_t)(1 << n)) - 1; // = 2^n - 1
|
||||
|
||||
// Shift n bits into the right position
|
||||
// out = in >> n;
|
||||
|
||||
// Mask and shift bytes
|
||||
i_bit_index = bit_index; |
||||
i_byte_index = packet_index; |
||||
if (bit_index > 0) |
||||
{ |
||||
// If bits were available at start, they were available
|
||||
// in the byte before the current index
|
||||
i_byte_index--; |
||||
} |
||||
|
||||
// While bits have not been packed yet
|
||||
while (bits_remain > 0) |
||||
{ |
||||
// Bits still have to be packed
|
||||
// there can be more than 8 bits, so
|
||||
// we might have to pack them into more than one byte
|
||||
|
||||
// First pack everything we can into the current 'open' byte
|
||||
//curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8
|
||||
//FIXME
|
||||
if (bits_remain <= (uint8_t)(8 - i_bit_index)) |
||||
{ |
||||
// Enough space
|
||||
curr_bits_n = (uint8_t)bits_remain; |
||||
} |
||||
else |
||||
{ |
||||
curr_bits_n = (8 - i_bit_index); |
||||
} |
||||
|
||||
// Pack these n bits into the current byte
|
||||
// Mask out whatever was at that position with ones (xxx11111)
|
||||
buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n)); |
||||
// Put content to this position, by masking out the non-used part
|
||||
buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v); |
||||
|
||||
// Increment the bit index
|
||||
i_bit_index += curr_bits_n; |
||||
|
||||
// Now proceed to the next byte, if necessary
|
||||
bits_remain -= curr_bits_n; |
||||
if (bits_remain > 0) |
||||
{ |
||||
// Offer another 8 bits / one byte
|
||||
i_byte_index++; |
||||
i_bit_index = 0; |
||||
} |
||||
} |
||||
|
||||
*r_bit_index = i_bit_index; |
||||
// If a partly filled byte is present, mark this as consumed
|
||||
if (i_bit_index != 7) i_byte_index++; |
||||
return i_byte_index - packet_index; |
||||
} |
||||
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
||||
|
||||
// To make MAVLink work on your MCU, define comm_send_ch() if you wish
|
||||
// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a
|
||||
// whole packet at a time
|
||||
|
||||
/*
|
||||
|
||||
#include "mavlink_types.h" |
||||
|
||||
void comm_send_ch(mavlink_channel_t chan, uint8_t ch) |
||||
{ |
||||
if (chan == MAVLINK_COMM_0) |
||||
{ |
||||
uart0_transmit(ch); |
||||
} |
||||
if (chan == MAVLINK_COMM_1) |
||||
{ |
||||
uart1_transmit(ch); |
||||
} |
||||
} |
||||
*/ |
||||
|
||||
MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len) |
||||
{ |
||||
#ifdef MAVLINK_SEND_UART_BYTES |
||||
/* this is the more efficient approach, if the platform
|
||||
defines it */ |
||||
MAVLINK_SEND_UART_BYTES(chan, (uint8_t *)buf, len); |
||||
#else |
||||
/* fallback to one byte at a time */ |
||||
uint16_t i; |
||||
for (i = 0; i < len; i++) { |
||||
comm_send_ch(chan, (uint8_t)buf[i]); |
||||
} |
||||
#endif |
||||
} |
||||
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
#endif /* _MAVLINK_HELPERS_H_ */ |
@ -0,0 +1,298 @@
@@ -0,0 +1,298 @@
|
||||
#ifndef MAVLINK_TYPES_H_ |
||||
#define MAVLINK_TYPES_H_ |
||||
|
||||
#include "inttypes.h" |
||||
|
||||
enum MAV_CLASS |
||||
{ |
||||
MAV_CLASS_GENERIC = 0, ///< Generic autopilot, full support for everything
|
||||
MAV_CLASS_PIXHAWK = 1, ///< PIXHAWK autopilot, http://pixhawk.ethz.ch
|
||||
MAV_CLASS_SLUGS = 2, ///< SLUGS autopilot, http://slugsuav.soe.ucsc.edu
|
||||
MAV_CLASS_ARDUPILOTMEGA = 3, ///< ArduPilotMega / ArduCopter, http://diydrones.com
|
||||
MAV_CLASS_OPENPILOT = 4, ///< OpenPilot, http://openpilot.org
|
||||
MAV_CLASS_GENERIC_MISSION_WAYPOINTS_ONLY = 5, ///< Generic autopilot only supporting simple waypoints
|
||||
MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6, ///< Generic autopilot supporting waypoints and other simple navigation commands
|
||||
MAV_CLASS_GENERIC_MISSION_FULL = 7, ///< Generic autopilot supporting the full mission command set
|
||||
MAV_CLASS_NONE = 8, ///< No valid autopilot
|
||||
MAV_CLASS_NB ///< Number of autopilot classes
|
||||
}; |
||||
|
||||
enum MAV_ACTION |
||||
{ |
||||
MAV_ACTION_HOLD = 0, |
||||
MAV_ACTION_MOTORS_START = 1, |
||||
MAV_ACTION_LAUNCH = 2, |
||||
MAV_ACTION_RETURN = 3, |
||||
MAV_ACTION_EMCY_LAND = 4, |
||||
MAV_ACTION_EMCY_KILL = 5, |
||||
MAV_ACTION_CONFIRM_KILL = 6, |
||||
MAV_ACTION_CONTINUE = 7, |
||||
MAV_ACTION_MOTORS_STOP = 8, |
||||
MAV_ACTION_HALT = 9, |
||||
MAV_ACTION_SHUTDOWN = 10, |
||||
MAV_ACTION_REBOOT = 11, |
||||
MAV_ACTION_SET_MANUAL = 12, |
||||
MAV_ACTION_SET_AUTO = 13, |
||||
MAV_ACTION_STORAGE_READ = 14, |
||||
MAV_ACTION_STORAGE_WRITE = 15, |
||||
MAV_ACTION_CALIBRATE_RC = 16, |
||||
MAV_ACTION_CALIBRATE_GYRO = 17, |
||||
MAV_ACTION_CALIBRATE_MAG = 18, |
||||
MAV_ACTION_CALIBRATE_ACC = 19, |
||||
MAV_ACTION_CALIBRATE_PRESSURE = 20, |
||||
MAV_ACTION_REC_START = 21, |
||||
MAV_ACTION_REC_PAUSE = 22, |
||||
MAV_ACTION_REC_STOP = 23, |
||||
MAV_ACTION_TAKEOFF = 24, |
||||
MAV_ACTION_NAVIGATE = 25, |
||||
MAV_ACTION_LAND = 26, |
||||
MAV_ACTION_LOITER = 27, |
||||
MAV_ACTION_SET_ORIGIN = 28, |
||||
MAV_ACTION_RELAY_ON = 29, |
||||
MAV_ACTION_RELAY_OFF = 30, |
||||
MAV_ACTION_GET_IMAGE = 31, |
||||
MAV_ACTION_VIDEO_START = 32, |
||||
MAV_ACTION_VIDEO_STOP = 33, |
||||
MAV_ACTION_RESET_MAP = 34, |
||||
MAV_ACTION_RESET_PLAN = 35, |
||||
MAV_ACTION_DELAY_BEFORE_COMMAND = 36, |
||||
MAV_ACTION_ASCEND_AT_RATE = 37, |
||||
MAV_ACTION_CHANGE_MODE = 38, |
||||
MAV_ACTION_LOITER_MAX_TURNS = 39, |
||||
MAV_ACTION_LOITER_MAX_TIME = 40, |
||||
MAV_ACTION_START_HILSIM = 41, |
||||
MAV_ACTION_STOP_HILSIM = 42,
|
||||
MAV_ACTION_NB ///< Number of MAV actions
|
||||
}; |
||||
|
||||
enum MAV_MODE |
||||
{ |
||||
MAV_MODE_UNINIT = 0, ///< System is in undefined state
|
||||
MAV_MODE_LOCKED = 1, ///< Motors are blocked, system is safe
|
||||
MAV_MODE_MANUAL = 2, ///< System is allowed to be active, under manual (RC) control
|
||||
MAV_MODE_GUIDED = 3, ///< System is allowed to be active, under autonomous control, manual setpoint
|
||||
MAV_MODE_AUTO = 4, ///< System is allowed to be active, under autonomous control and navigation
|
||||
MAV_MODE_TEST1 = 5, ///< Generic test mode, for custom use
|
||||
MAV_MODE_TEST2 = 6, ///< Generic test mode, for custom use
|
||||
MAV_MODE_TEST3 = 7, ///< Generic test mode, for custom use
|
||||
MAV_MODE_READY = 8, ///< System is ready, motors are unblocked, but controllers are inactive
|
||||
MAV_MODE_RC_TRAINING = 9 ///< System is blocked, only RC valued are read and reported back
|
||||
}; |
||||
|
||||
enum MAV_STATE |
||||
{ |
||||
MAV_STATE_UNINIT = 0, |
||||
MAV_STATE_BOOT, |
||||
MAV_STATE_CALIBRATING, |
||||
MAV_STATE_STANDBY, |
||||
MAV_STATE_ACTIVE, |
||||
MAV_STATE_CRITICAL, |
||||
MAV_STATE_EMERGENCY, |
||||
MAV_STATE_HILSIM, |
||||
MAV_STATE_POWEROFF |
||||
}; |
||||
|
||||
enum MAV_NAV |
||||
{ |
||||
MAV_NAV_GROUNDED = 0, |
||||
MAV_NAV_LIFTOFF, |
||||
MAV_NAV_HOLD, |
||||
MAV_NAV_WAYPOINT, |
||||
MAV_NAV_VECTOR, |
||||
MAV_NAV_RETURNING, |
||||
MAV_NAV_LANDING, |
||||
MAV_NAV_LOST, |
||||
MAV_NAV_LOITER, |
||||
MAV_NAV_FREE_DRIFT |
||||
}; |
||||
|
||||
enum MAV_TYPE |
||||
{ |
||||
MAV_GENERIC = 0, |
||||
MAV_FIXED_WING = 1, |
||||
MAV_QUADROTOR = 2, |
||||
MAV_COAXIAL = 3, |
||||
MAV_HELICOPTER = 4, |
||||
MAV_GROUND = 5, |
||||
OCU = 6, |
||||
MAV_AIRSHIP = 7, |
||||
MAV_FREE_BALLOON = 8, |
||||
MAV_ROCKET = 9, |
||||
UGV_GROUND_ROVER = 10, |
||||
UGV_SURFACE_SHIP = 11 |
||||
}; |
||||
|
||||
enum MAV_AUTOPILOT_TYPE |
||||
{ |
||||
MAV_AUTOPILOT_GENERIC = 0, |
||||
MAV_AUTOPILOT_PIXHAWK = 1, |
||||
MAV_AUTOPILOT_SLUGS = 2, |
||||
MAV_AUTOPILOT_ARDUPILOTMEGA = 3, |
||||
MAV_AUTOPILOT_NONE = 4 |
||||
}; |
||||
|
||||
enum MAV_COMPONENT |
||||
{ |
||||
MAV_COMP_ID_GPS, |
||||
MAV_COMP_ID_WAYPOINTPLANNER, |
||||
MAV_COMP_ID_BLOBTRACKER, |
||||
MAV_COMP_ID_PATHPLANNER, |
||||
MAV_COMP_ID_AIRSLAM, |
||||
MAV_COMP_ID_MAPPER, |
||||
MAV_COMP_ID_CAMERA, |
||||
MAV_COMP_ID_IMU = 200, |
||||
MAV_COMP_ID_IMU_2 = 201, |
||||
MAV_COMP_ID_IMU_3 = 202, |
||||
MAV_COMP_ID_UDP_BRIDGE = 240, |
||||
MAV_COMP_ID_UART_BRIDGE = 241, |
||||
MAV_COMP_ID_SYSTEM_CONTROL = 250 |
||||
}; |
||||
|
||||
enum MAV_FRAME |
||||
{ |
||||
MAV_FRAME_GLOBAL = 0, |
||||
MAV_FRAME_LOCAL = 1, |
||||
MAV_FRAME_MISSION = 2, |
||||
MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, |
||||
MAV_FRAME_LOCAL_ENU = 4 |
||||
}; |
||||
|
||||
enum MAVLINK_DATA_STREAM_TYPE |
||||
{ |
||||
MAVLINK_DATA_STREAM_IMG_JPEG, |
||||
MAVLINK_DATA_STREAM_IMG_BMP, |
||||
MAVLINK_DATA_STREAM_IMG_RAW8U, |
||||
MAVLINK_DATA_STREAM_IMG_RAW32U, |
||||
MAVLINK_DATA_STREAM_IMG_PGM, |
||||
MAVLINK_DATA_STREAM_IMG_PNG |
||||
}; |
||||
|
||||
#ifndef MAVLINK_MAX_PAYLOAD_LEN |
||||
// it is possible to override this, but be careful!
|
||||
#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length
|
||||
#endif |
||||
|
||||
#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte)
|
||||
#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum
|
||||
#define MAVLINK_NUM_CHECKSUM_BYTES 2 |
||||
#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES) |
||||
|
||||
#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length
|
||||
|
||||
typedef struct param_union { |
||||
union { |
||||
float param_float; |
||||
int32_t param_int32; |
||||
uint32_t param_uint32; |
||||
}; |
||||
uint8_t type; |
||||
} mavlink_param_union_t; |
||||
|
||||
typedef struct __mavlink_system { |
||||
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 type; ///< Unused, can be used by user to store the system's type
|
||||
uint8_t state; ///< Unused, can be used by user to store the system's state
|
||||
uint8_t mode; ///< Unused, can be used by user to store the system's mode
|
||||
uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode
|
||||
} mavlink_system_t; |
||||
|
||||
typedef struct __mavlink_message { |
||||
uint16_t checksum; /// sent at end of packet
|
||||
uint8_t magic; ///< protocol magic marker
|
||||
uint8_t len; ///< Length of payload
|
||||
uint8_t seq; ///< Sequence of packet
|
||||
uint8_t sysid; ///< ID of message sender system/aircraft
|
||||
uint8_t compid; ///< ID of the message sender component
|
||||
uint8_t msgid; ///< ID of message in payload
|
||||
uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8]; |
||||
} mavlink_message_t; |
||||
|
||||
typedef enum { |
||||
MAVLINK_TYPE_CHAR = 0, |
||||
MAVLINK_TYPE_UINT8_T = 1, |
||||
MAVLINK_TYPE_INT8_T = 2, |
||||
MAVLINK_TYPE_UINT16_T = 3, |
||||
MAVLINK_TYPE_INT16_T = 4, |
||||
MAVLINK_TYPE_UINT32_T = 5, |
||||
MAVLINK_TYPE_INT32_T = 6, |
||||
MAVLINK_TYPE_UINT64_T = 7, |
||||
MAVLINK_TYPE_INT64_T = 8, |
||||
MAVLINK_TYPE_FLOAT = 9, |
||||
MAVLINK_TYPE_DOUBLE = 10 |
||||
} mavlink_message_type_t; |
||||
|
||||
#define MAVLINK_MAX_FIELDS 64 |
||||
|
||||
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
|
||||
} mavlink_field_info_t; |
||||
|
||||
// note that in this structure the order of fields is the order
|
||||
// in the XML file, not necessary the wire order
|
||||
typedef struct __mavlink_message_info { |
||||
const char *name; // name of the message
|
||||
unsigned num_fields; // how many fields in this message
|
||||
mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information
|
||||
} mavlink_message_info_t; |
||||
|
||||
#define _MAV_PAYLOAD(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)) |
||||
|
||||
typedef enum { |
||||
MAVLINK_COMM_0, |
||||
MAVLINK_COMM_1, |
||||
MAVLINK_COMM_2, |
||||
MAVLINK_COMM_3 |
||||
} mavlink_channel_t; |
||||
|
||||
/*
|
||||
* applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number |
||||
* of buffers they will use. If more are used, then the result will be |
||||
* a stack overrun |
||||
*/ |
||||
#ifndef MAVLINK_COMM_NUM_BUFFERS |
||||
#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) |
||||
# define MAVLINK_COMM_NUM_BUFFERS 16 |
||||
#else |
||||
# define MAVLINK_COMM_NUM_BUFFERS 4 |
||||
#endif |
||||
#endif |
||||
|
||||
typedef enum { |
||||
MAVLINK_PARSE_STATE_UNINIT=0, |
||||
MAVLINK_PARSE_STATE_IDLE, |
||||
MAVLINK_PARSE_STATE_GOT_STX, |
||||
MAVLINK_PARSE_STATE_GOT_SEQ, |
||||
MAVLINK_PARSE_STATE_GOT_LENGTH, |
||||
MAVLINK_PARSE_STATE_GOT_SYSID, |
||||
MAVLINK_PARSE_STATE_GOT_COMPID, |
||||
MAVLINK_PARSE_STATE_GOT_MSGID, |
||||
MAVLINK_PARSE_STATE_GOT_PAYLOAD, |
||||
MAVLINK_PARSE_STATE_GOT_CRC1 |
||||
} mavlink_parse_state_t; ///< The state machine for the comm parser
|
||||
|
||||
typedef struct __mavlink_status { |
||||
uint8_t msg_received; ///< Number of received messages
|
||||
uint8_t buffer_overrun; ///< Number of buffer overruns
|
||||
uint8_t parse_error; ///< Number of parse errors
|
||||
mavlink_parse_state_t parse_state; ///< Parsing state machine
|
||||
uint8_t packet_idx; ///< Index in current packet
|
||||
uint8_t current_rx_seq; ///< Sequence number of last packet received
|
||||
uint8_t current_tx_seq; ///< Sequence number of last packet sent
|
||||
uint16_t packet_rx_success_count; ///< Received packets
|
||||
uint16_t packet_rx_drop_count; ///< Number of packet drops
|
||||
} mavlink_status_t; |
||||
|
||||
#define MAVLINK_BIG_ENDIAN 0 |
||||
#define MAVLINK_LITTLE_ENDIAN 1 |
||||
|
||||
#endif /* MAVLINK_TYPES_H_ */ |
@ -0,0 +1,322 @@
@@ -0,0 +1,322 @@
|
||||
#ifndef _MAVLINK_PROTOCOL_H_ |
||||
#define _MAVLINK_PROTOCOL_H_ |
||||
|
||||
#include "string.h" |
||||
#include "mavlink_types.h" |
||||
|
||||
/*
|
||||
If you want MAVLink on a system that is native big-endian, |
||||
you need to define NATIVE_BIG_ENDIAN |
||||
*/ |
||||
#ifdef NATIVE_BIG_ENDIAN |
||||
# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN) |
||||
#else |
||||
# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN) |
||||
#endif |
||||
|
||||
#ifndef MAVLINK_STACK_BUFFER |
||||
#define MAVLINK_STACK_BUFFER 0 |
||||
#endif |
||||
|
||||
#ifndef MAVLINK_AVOID_GCC_STACK_BUG |
||||
# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__) |
||||
#endif |
||||
|
||||
#ifndef MAVLINK_ASSERT |
||||
#define MAVLINK_ASSERT(x) |
||||
#endif |
||||
|
||||
#ifndef MAVLINK_START_UART_SEND |
||||
#define MAVLINK_START_UART_SEND(chan, length) |
||||
#endif |
||||
|
||||
#ifndef MAVLINK_END_UART_SEND |
||||
#define MAVLINK_END_UART_SEND(chan, length) |
||||
#endif |
||||
|
||||
#ifdef MAVLINK_SEPARATE_HELPERS |
||||
#define MAVLINK_HELPER |
||||
#else |
||||
#define MAVLINK_HELPER static inline |
||||
#include "mavlink_helpers.h" |
||||
#endif // MAVLINK_SEPARATE_HELPERS
|
||||
|
||||
/* always include the prototypes to ensure we don't get out of sync */ |
||||
MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan); |
||||
#if MAVLINK_CRC_EXTRA |
||||
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
|
||||
uint8_t chan, uint8_t length, uint8_t crc_extra); |
||||
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
|
||||
uint8_t length, uint8_t crc_extra); |
||||
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
|
||||
uint8_t length, uint8_t crc_extra); |
||||
#else |
||||
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
|
||||
uint8_t chan, uint8_t length); |
||||
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
|
||||
uint8_t length); |
||||
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length); |
||||
#endif // MAVLINK_CRC_EXTRA
|
||||
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg); |
||||
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg); |
||||
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); |
||||
MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index,
|
||||
uint8_t* r_bit_index, uint8_t* buffer); |
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
||||
MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); |
||||
#endif |
||||
|
||||
/**
|
||||
* @brief Get the required buffer size for this message |
||||
*/ |
||||
static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg) |
||||
{ |
||||
return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES; |
||||
} |
||||
|
||||
#if MAVLINK_NEED_BYTE_SWAP |
||||
static inline void byte_swap_2(char *dst, const char *src) |
||||
{ |
||||
dst[0] = src[1]; |
||||
dst[1] = src[0]; |
||||
} |
||||
static inline void byte_swap_4(char *dst, const char *src) |
||||
{ |
||||
dst[0] = src[3]; |
||||
dst[1] = src[2]; |
||||
dst[2] = src[1]; |
||||
dst[3] = src[0]; |
||||
} |
||||
static inline void byte_swap_8(char *dst, const char *src) |
||||
{ |
||||
dst[0] = src[7]; |
||||
dst[1] = src[6]; |
||||
dst[2] = src[5]; |
||||
dst[3] = src[4]; |
||||
dst[4] = src[3]; |
||||
dst[5] = src[2]; |
||||
dst[6] = src[1]; |
||||
dst[7] = src[0]; |
||||
} |
||||
#elif !MAVLINK_ALIGNED_FIELDS |
||||
static inline void byte_copy_2(char *dst, const char *src) |
||||
{ |
||||
dst[0] = src[0]; |
||||
dst[1] = src[1]; |
||||
} |
||||
static inline void byte_copy_4(char *dst, const char *src) |
||||
{ |
||||
dst[0] = src[0]; |
||||
dst[1] = src[1]; |
||||
dst[2] = src[2]; |
||||
dst[3] = src[3]; |
||||
} |
||||
static inline void byte_copy_8(char *dst, const char *src) |
||||
{ |
||||
memcpy(dst, src, 8); |
||||
} |
||||
#endif |
||||
|
||||
#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b |
||||
#define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b |
||||
#define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b |
||||
|
||||
#if MAVLINK_NEED_BYTE_SWAP |
||||
#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) |
||||
#elif !MAVLINK_ALIGNED_FIELDS |
||||
#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) |
||||
#else |
||||
#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b |
||||
#define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b |
||||
#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b |
||||
#define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b |
||||
#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b |
||||
#define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b |
||||
#define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b |
||||
#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b |
||||
#endif |
||||
|
||||
|
||||
/*
|
||||
* Place a char array into a buffer |
||||
*/ |
||||
static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length) |
||||
{ |
||||
if (b == NULL) { |
||||
memset(&buf[wire_offset], 0, array_length); |
||||
} else { |
||||
memcpy(&buf[wire_offset], b, array_length); |
||||
} |
||||
} |
||||
|
||||
/*
|
||||
* Place a uint8_t array into a buffer |
||||
*/ |
||||
static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length) |
||||
{ |
||||
if (b == NULL) { |
||||
memset(&buf[wire_offset], 0, array_length); |
||||
} else { |
||||
memcpy(&buf[wire_offset], b, array_length); |
||||
} |
||||
} |
||||
|
||||
/*
|
||||
* Place a int8_t array into a buffer |
||||
*/ |
||||
static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length) |
||||
{ |
||||
if (b == NULL) { |
||||
memset(&buf[wire_offset], 0, array_length); |
||||
} else { |
||||
memcpy(&buf[wire_offset], b, array_length); |
||||
} |
||||
} |
||||
|
||||
#if MAVLINK_NEED_BYTE_SWAP |
||||
#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) \
|
||||
{ \
|
||||
if (b == NULL) { \
|
||||
memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \
|
||||
} else { \
|
||||
uint16_t i; \
|
||||
for (i=0; i<array_length; i++) { \
|
||||
_mav_put_## TYPE (buf, wire_offset+(i*sizeof(TYPE)), b[i]); \
|
||||
} \
|
||||
} \
|
||||
} |
||||
#else |
||||
#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) \
|
||||
{ \
|
||||
if (b == NULL) { \
|
||||
memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \
|
||||
} else { \
|
||||
memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \
|
||||
} \
|
||||
} |
||||
#endif |
||||
|
||||
_MAV_PUT_ARRAY(uint16_t, u16) |
||||
_MAV_PUT_ARRAY(uint32_t, u32) |
||||
_MAV_PUT_ARRAY(uint64_t, u64) |
||||
_MAV_PUT_ARRAY(int16_t, i16) |
||||
_MAV_PUT_ARRAY(int32_t, i32) |
||||
_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] |
||||
|
||||
#if MAVLINK_NEED_BYTE_SWAP |
||||
#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \ |
||||
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
|
||||
{ TYPE r; byte_swap_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; } |
||||
|
||||
_MAV_MSG_RETURN_TYPE(uint16_t, 2) |
||||
_MAV_MSG_RETURN_TYPE(int16_t, 2) |
||||
_MAV_MSG_RETURN_TYPE(uint32_t, 4) |
||||
_MAV_MSG_RETURN_TYPE(int32_t, 4) |
||||
_MAV_MSG_RETURN_TYPE(uint64_t, 8) |
||||
_MAV_MSG_RETURN_TYPE(int64_t, 8) |
||||
_MAV_MSG_RETURN_TYPE(float, 4) |
||||
_MAV_MSG_RETURN_TYPE(double, 8) |
||||
|
||||
#elif !MAVLINK_ALIGNED_FIELDS |
||||
#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \ |
||||
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
|
||||
{ TYPE r; byte_copy_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; } |
||||
|
||||
_MAV_MSG_RETURN_TYPE(uint16_t, 2) |
||||
_MAV_MSG_RETURN_TYPE(int16_t, 2) |
||||
_MAV_MSG_RETURN_TYPE(uint32_t, 4) |
||||
_MAV_MSG_RETURN_TYPE(int32_t, 4) |
||||
_MAV_MSG_RETURN_TYPE(uint64_t, 8) |
||||
_MAV_MSG_RETURN_TYPE(int64_t, 8) |
||||
_MAV_MSG_RETURN_TYPE(float, 4) |
||||
_MAV_MSG_RETURN_TYPE(double, 8) |
||||
#else // nicely aligned, no swap
|
||||
#define _MAV_MSG_RETURN_TYPE(TYPE) \ |
||||
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
|
||||
{ return *(const TYPE *)(&_MAV_PAYLOAD(msg)[ofs]);} |
||||
|
||||
_MAV_MSG_RETURN_TYPE(uint16_t) |
||||
_MAV_MSG_RETURN_TYPE(int16_t) |
||||
_MAV_MSG_RETURN_TYPE(uint32_t) |
||||
_MAV_MSG_RETURN_TYPE(int32_t) |
||||
_MAV_MSG_RETURN_TYPE(uint64_t) |
||||
_MAV_MSG_RETURN_TYPE(int64_t) |
||||
_MAV_MSG_RETURN_TYPE(float) |
||||
_MAV_MSG_RETURN_TYPE(double) |
||||
#endif // MAVLINK_NEED_BYTE_SWAP
|
||||
|
||||
static inline uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value,
|
||||
uint8_t array_length, uint8_t wire_offset) |
||||
{ |
||||
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length); |
||||
return array_length; |
||||
} |
||||
|
||||
static inline uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value,
|
||||
uint8_t array_length, uint8_t wire_offset) |
||||
{ |
||||
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length); |
||||
return array_length; |
||||
} |
||||
|
||||
static inline uint16_t _MAV_RETURN_int8_t_array(const mavlink_message_t *msg, int8_t *value,
|
||||
uint8_t array_length, uint8_t wire_offset) |
||||
{ |
||||
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length); |
||||
return array_length; |
||||
} |
||||
|
||||
#if MAVLINK_NEED_BYTE_SWAP |
||||
#define _MAV_RETURN_ARRAY(TYPE, V) \ |
||||
static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
|
||||
uint8_t array_length, uint8_t wire_offset) \
|
||||
{ \
|
||||
uint16_t i; \
|
||||
for (i=0; i<array_length; i++) { \
|
||||
value[i] = _MAV_RETURN_## TYPE (msg, wire_offset+(i*sizeof(value[0]))); \
|
||||
} \
|
||||
return array_length*sizeof(value[0]); \
|
||||
} |
||||
#else |
||||
#define _MAV_RETURN_ARRAY(TYPE, V) \ |
||||
static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
|
||||
uint8_t array_length, uint8_t wire_offset) \
|
||||
{ \
|
||||
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length*sizeof(TYPE)); \
|
||||
return array_length*sizeof(TYPE); \
|
||||
} |
||||
#endif |
||||
|
||||
_MAV_RETURN_ARRAY(uint16_t, u16) |
||||
_MAV_RETURN_ARRAY(uint32_t, u32) |
||||
_MAV_RETURN_ARRAY(uint64_t, u64) |
||||
_MAV_RETURN_ARRAY(int16_t, i16) |
||||
_MAV_RETURN_ARRAY(int32_t, i32) |
||||
_MAV_RETURN_ARRAY(int64_t, i64) |
||||
_MAV_RETURN_ARRAY(float, f) |
||||
_MAV_RETURN_ARRAY(double, d) |
||||
|
||||
#endif // _MAVLINK_PROTOCOL_H_
|
@ -0,0 +1,89 @@
@@ -0,0 +1,89 @@
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
#ifndef _CHECKSUM_H_ |
||||
#define _CHECKSUM_H_ |
||||
|
||||
|
||||
/**
|
||||
* |
||||
* CALCULATE THE CHECKSUM |
||||
* |
||||
*/ |
||||
|
||||
#define X25_INIT_CRC 0xffff |
||||
#define X25_VALIDATE_CRC 0xf0b8 |
||||
|
||||
/**
|
||||
* @brief Accumulate the X.25 CRC by adding one char at a time. |
||||
* |
||||
* The checksum function adds the hash of one char at a time to the |
||||
* 16 bit checksum (uint16_t). |
||||
* |
||||
* @param data new char to hash |
||||
* @param crcAccum the already accumulated checksum |
||||
**/ |
||||
static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum) |
||||
{ |
||||
/*Accumulate one byte of data into the CRC*/ |
||||
uint8_t tmp; |
||||
|
||||
tmp = data ^ (uint8_t)(*crcAccum &0xff); |
||||
tmp ^= (tmp<<4); |
||||
*crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Initiliaze the buffer for the X.25 CRC |
||||
* |
||||
* @param crcAccum the 16 bit X.25 CRC |
||||
*/ |
||||
static inline void crc_init(uint16_t* crcAccum) |
||||
{ |
||||
*crcAccum = X25_INIT_CRC; |
||||
} |
||||
|
||||
|
||||
/**
|
||||
* @brief Calculates the X.25 checksum on a byte buffer |
||||
* |
||||
* @param pBuffer buffer containing the byte array to hash |
||||
* @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) |
||||
{ |
||||
uint16_t crcTmp; |
||||
crc_init(&crcTmp); |
||||
while (length--) { |
||||
crc_accumulate(*pBuffer++, &crcTmp); |
||||
} |
||||
return crcTmp; |
||||
} |
||||
|
||||
/**
|
||||
* @brief Accumulate the X.25 CRC by adding an array of bytes |
||||
* |
||||
* The checksum function adds the hash of one char at a time to the |
||||
* 16 bit checksum (uint16_t). |
||||
* |
||||
* @param data new bytes to hash |
||||
* @param crcAccum the already accumulated checksum |
||||
**/ |
||||
static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint8_t length) |
||||
{ |
||||
const uint8_t *p = (const uint8_t *)pBuffer; |
||||
while (length--) { |
||||
crc_accumulate(*p++, crcAccum); |
||||
} |
||||
} |
||||
|
||||
|
||||
|
||||
|
||||
#endif /* _CHECKSUM_H_ */ |
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
@ -0,0 +1,488 @@
@@ -0,0 +1,488 @@
|
||||
#ifndef _MAVLINK_HELPERS_H_ |
||||
#define _MAVLINK_HELPERS_H_ |
||||
|
||||
#include "string.h" |
||||
#include "checksum.h" |
||||
#include "mavlink_types.h" |
||||
|
||||
#ifndef MAVLINK_HELPER |
||||
#define MAVLINK_HELPER |
||||
#endif |
||||
|
||||
/*
|
||||
internal function to give access to the channel status for each channel |
||||
*/ |
||||
MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan) |
||||
{ |
||||
static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS]; |
||||
return &m_mavlink_status[chan]; |
||||
} |
||||
|
||||
/**
|
||||
* @brief Finalize a MAVLink message with channel assignment |
||||
* |
||||
* This function calculates the checksum and sets length and aircraft id correctly. |
||||
* It assumes that the message id and the payload are already correctly set. This function |
||||
* can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack |
||||
* instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead. |
||||
* |
||||
* @param msg Message to finalize |
||||
* @param system_id Id of the sending (this) system, 1-127 |
||||
* @param length Message length |
||||
*/ |
||||
#if MAVLINK_CRC_EXTRA |
||||
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
|
||||
uint8_t chan, uint8_t length, uint8_t crc_extra) |
||||
#else |
||||
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
|
||||
uint8_t chan, uint8_t length) |
||||
#endif |
||||
{ |
||||
// This code part is the same for all messages;
|
||||
uint16_t checksum; |
||||
msg->magic = MAVLINK_STX; |
||||
msg->len = length; |
||||
msg->sysid = system_id; |
||||
msg->compid = component_id; |
||||
// One sequence number per component
|
||||
msg->seq = mavlink_get_channel_status(chan)->current_tx_seq; |
||||
mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1; |
||||
checksum = crc_calculate((uint8_t*)&msg->len, length + MAVLINK_CORE_HEADER_LEN); |
||||
#if MAVLINK_CRC_EXTRA |
||||
crc_accumulate(crc_extra, &checksum); |
||||
#endif |
||||
mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF); |
||||
mavlink_ck_b(msg) = (uint8_t)(checksum >> 8); |
||||
|
||||
return length + MAVLINK_NUM_NON_PAYLOAD_BYTES; |
||||
} |
||||
|
||||
|
||||
/**
|
||||
* @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel |
||||
*/ |
||||
#if MAVLINK_CRC_EXTRA |
||||
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
|
||||
uint8_t length, uint8_t crc_extra) |
||||
{ |
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length, crc_extra); |
||||
} |
||||
#else |
||||
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
|
||||
uint8_t length) |
||||
{ |
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length); |
||||
} |
||||
#endif |
||||
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
||||
MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); |
||||
|
||||
/**
|
||||
* @brief Finalize a MAVLink message with channel assignment and send |
||||
*/ |
||||
#if MAVLINK_CRC_EXTRA |
||||
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
|
||||
uint8_t length, uint8_t crc_extra) |
||||
#else |
||||
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length) |
||||
#endif |
||||
{ |
||||
uint16_t checksum; |
||||
uint8_t buf[MAVLINK_NUM_HEADER_BYTES]; |
||||
uint8_t ck[2]; |
||||
mavlink_status_t *status = mavlink_get_channel_status(chan); |
||||
buf[0] = MAVLINK_STX; |
||||
buf[1] = length; |
||||
buf[2] = status->current_tx_seq; |
||||
buf[3] = mavlink_system.sysid; |
||||
buf[4] = mavlink_system.compid; |
||||
buf[5] = msgid; |
||||
status->current_tx_seq++; |
||||
checksum = crc_calculate((uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN); |
||||
crc_accumulate_buffer(&checksum, packet, length); |
||||
#if MAVLINK_CRC_EXTRA |
||||
crc_accumulate(crc_extra, &checksum); |
||||
#endif |
||||
ck[0] = (uint8_t)(checksum & 0xFF); |
||||
ck[1] = (uint8_t)(checksum >> 8); |
||||
|
||||
MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); |
||||
_mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES); |
||||
_mavlink_send_uart(chan, packet, length); |
||||
_mavlink_send_uart(chan, (const char *)ck, 2); |
||||
MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); |
||||
} |
||||
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
/**
|
||||
* @brief Pack a message to send it over a serial byte stream |
||||
*/ |
||||
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); |
||||
return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len; |
||||
} |
||||
|
||||
union __mavlink_bitfield { |
||||
uint8_t uint8; |
||||
int8_t int8; |
||||
uint16_t uint16; |
||||
int16_t int16; |
||||
uint32_t uint32; |
||||
int32_t int32; |
||||
}; |
||||
|
||||
|
||||
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg) |
||||
{ |
||||
crc_init(&msg->checksum); |
||||
} |
||||
|
||||
MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) |
||||
{ |
||||
crc_accumulate(c, &msg->checksum); |
||||
} |
||||
|
||||
/**
|
||||
* This is a convenience function which handles the complete MAVLink parsing. |
||||
* the function will parse one byte at a time and return the complete packet once |
||||
* it could be successfully decoded. Checksum and other failures will be silently |
||||
* ignored. |
||||
* |
||||
* @param chan ID of the current channel. This allows to parse different channels with this function. |
||||
* a channel is not a physical message channel like a serial port, but a logic partition of |
||||
* the communication streams in this case. COMM_NB is the limit for the number of channels |
||||
* on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows |
||||
* @param c The char to barse |
||||
* |
||||
* @param returnMsg NULL if no message could be decoded, the message data else |
||||
* @return 0 if no message could be decoded, 1 else |
||||
* |
||||
* A typical use scenario of this function call is: |
||||
* |
||||
* @code |
||||
* #include <inttypes.h> // For fixed-width uint8_t type
|
||||
* |
||||
* mavlink_message_t msg; |
||||
* int chan = 0; |
||||
* |
||||
* |
||||
* while(serial.bytesAvailable > 0) |
||||
* { |
||||
* uint8_t byte = serial.getNextByte(); |
||||
* if (mavlink_parse_char(chan, byte, &msg)) |
||||
* { |
||||
* printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); |
||||
* } |
||||
* } |
||||
* |
||||
* |
||||
* @endcode |
||||
*/ |
||||
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 |
||||
*/ |
||||
#if MAVLINK_CRC_EXTRA |
||||
#ifndef MAVLINK_MESSAGE_CRC |
||||
static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS; |
||||
#define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid] |
||||
#endif |
||||
#endif |
||||
|
||||
mavlink_message_t* rxmsg = &m_mavlink_message[chan]; ///< The currently decoded message
|
||||
mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status
|
||||
int bufferIndex = 0; |
||||
|
||||
status->msg_received = 0; |
||||
|
||||
switch (status->parse_state) |
||||
{ |
||||
case MAVLINK_PARSE_STATE_UNINIT: |
||||
case MAVLINK_PARSE_STATE_IDLE: |
||||
if (c == MAVLINK_STX) |
||||
{ |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; |
||||
rxmsg->len = 0; |
||||
mavlink_start_checksum(rxmsg); |
||||
} |
||||
break; |
||||
|
||||
case MAVLINK_PARSE_STATE_GOT_STX: |
||||
if (status->msg_received
|
||||
/* Support shorter buffers than the
|
||||
default maximum packet size */ |
||||
#if (MAVLINK_MAX_PAYLOAD_LEN < 255) |
||||
|| c > MAVLINK_MAX_PAYLOAD_LEN |
||||
#endif |
||||
) |
||||
{ |
||||
status->buffer_overrun++; |
||||
status->parse_error++; |
||||
status->msg_received = 0; |
||||
status->parse_state = MAVLINK_PARSE_STATE_IDLE; |
||||
} |
||||
else |
||||
{ |
||||
// NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2
|
||||
rxmsg->len = c; |
||||
status->packet_idx = 0; |
||||
mavlink_update_checksum(rxmsg, c); |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH; |
||||
} |
||||
break; |
||||
|
||||
case MAVLINK_PARSE_STATE_GOT_LENGTH: |
||||
rxmsg->seq = c; |
||||
mavlink_update_checksum(rxmsg, c); |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ; |
||||
break; |
||||
|
||||
case MAVLINK_PARSE_STATE_GOT_SEQ: |
||||
rxmsg->sysid = c; |
||||
mavlink_update_checksum(rxmsg, c); |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID; |
||||
break; |
||||
|
||||
case MAVLINK_PARSE_STATE_GOT_SYSID: |
||||
rxmsg->compid = c; |
||||
mavlink_update_checksum(rxmsg, c); |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID; |
||||
break; |
||||
|
||||
case MAVLINK_PARSE_STATE_GOT_COMPID: |
||||
rxmsg->msgid = c; |
||||
mavlink_update_checksum(rxmsg, c); |
||||
if (rxmsg->len == 0) |
||||
{ |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; |
||||
} |
||||
else |
||||
{ |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID; |
||||
} |
||||
break; |
||||
|
||||
case MAVLINK_PARSE_STATE_GOT_MSGID: |
||||
_MAV_PAYLOAD(rxmsg)[status->packet_idx++] = (char)c; |
||||
mavlink_update_checksum(rxmsg, c); |
||||
if (status->packet_idx == rxmsg->len) |
||||
{ |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; |
||||
} |
||||
break; |
||||
|
||||
case MAVLINK_PARSE_STATE_GOT_PAYLOAD: |
||||
#if MAVLINK_CRC_EXTRA |
||||
mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid)); |
||||
#endif |
||||
if (c != (rxmsg->checksum & 0xFF)) { |
||||
// Check first checksum byte
|
||||
status->parse_error++; |
||||
status->msg_received = 0; |
||||
status->parse_state = MAVLINK_PARSE_STATE_IDLE; |
||||
if (c == MAVLINK_STX) |
||||
{ |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; |
||||
rxmsg->len = 0; |
||||
mavlink_start_checksum(rxmsg); |
||||
} |
||||
} |
||||
else |
||||
{ |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; |
||||
} |
||||
break; |
||||
|
||||
case MAVLINK_PARSE_STATE_GOT_CRC1: |
||||
if (c != (rxmsg->checksum >> 8)) { |
||||
// Check second checksum byte
|
||||
status->parse_error++; |
||||
status->msg_received = 0; |
||||
status->parse_state = MAVLINK_PARSE_STATE_IDLE; |
||||
if (c == MAVLINK_STX) |
||||
{ |
||||
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; |
||||
rxmsg->len = 0; |
||||
mavlink_start_checksum(rxmsg); |
||||
} |
||||
} |
||||
else |
||||
{ |
||||
// Successfully got message
|
||||
status->msg_received = 1; |
||||
status->parse_state = MAVLINK_PARSE_STATE_IDLE; |
||||
memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); |
||||
} |
||||
break; |
||||
} |
||||
|
||||
bufferIndex++; |
||||
// If a message has been sucessfully decoded, check index
|
||||
if (status->msg_received == 1) |
||||
{ |
||||
//while(status->current_seq != rxmsg->seq)
|
||||
//{
|
||||
// status->packet_rx_drop_count++;
|
||||
// status->current_seq++;
|
||||
//}
|
||||
status->current_rx_seq = rxmsg->seq; |
||||
// Initial condition: If no packet has been received so far, drop count is undefined
|
||||
if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0; |
||||
// Count this packet as received
|
||||
status->packet_rx_success_count++; |
||||
} |
||||
|
||||
r_mavlink_status->current_rx_seq = status->current_rx_seq+1; |
||||
r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; |
||||
r_mavlink_status->packet_rx_drop_count = status->parse_error; |
||||
status->parse_error = 0; |
||||
return status->msg_received; |
||||
} |
||||
|
||||
/**
|
||||
* @brief Put a bitfield of length 1-32 bit into the buffer |
||||
* |
||||
* @param b the value to add, will be encoded in the bitfield |
||||
* @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc. |
||||
* @param packet_index the position in the packet (the index of the first byte to use) |
||||
* @param bit_index the position in the byte (the index of the first bit to use) |
||||
* @param buffer packet buffer to write into |
||||
* @return new position of the last used byte in the buffer |
||||
*/ |
||||
MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer) |
||||
{ |
||||
uint16_t bits_remain = bits; |
||||
// Transform number into network order
|
||||
int32_t v; |
||||
uint8_t i_bit_index, i_byte_index, curr_bits_n; |
||||
#if MAVLINK_NEED_BYTE_SWAP |
||||
union { |
||||
int32_t i; |
||||
uint8_t b[4]; |
||||
} bin, bout; |
||||
bin.i = b; |
||||
bout.b[0] = bin.b[3]; |
||||
bout.b[1] = bin.b[2]; |
||||
bout.b[2] = bin.b[1]; |
||||
bout.b[3] = bin.b[0]; |
||||
v = bout.i; |
||||
#else |
||||
v = b; |
||||
#endif |
||||
|
||||
// buffer in
|
||||
// 01100000 01000000 00000000 11110001
|
||||
// buffer out
|
||||
// 11110001 00000000 01000000 01100000
|
||||
|
||||
// Existing partly filled byte (four free slots)
|
||||
// 0111xxxx
|
||||
|
||||
// Mask n free bits
|
||||
// 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1
|
||||
// = ((uint32_t)(1 << n)) - 1; // = 2^n - 1
|
||||
|
||||
// Shift n bits into the right position
|
||||
// out = in >> n;
|
||||
|
||||
// Mask and shift bytes
|
||||
i_bit_index = bit_index; |
||||
i_byte_index = packet_index; |
||||
if (bit_index > 0) |
||||
{ |
||||
// If bits were available at start, they were available
|
||||
// in the byte before the current index
|
||||
i_byte_index--; |
||||
} |
||||
|
||||
// While bits have not been packed yet
|
||||
while (bits_remain > 0) |
||||
{ |
||||
// Bits still have to be packed
|
||||
// there can be more than 8 bits, so
|
||||
// we might have to pack them into more than one byte
|
||||
|
||||
// First pack everything we can into the current 'open' byte
|
||||
//curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8
|
||||
//FIXME
|
||||
if (bits_remain <= (uint8_t)(8 - i_bit_index)) |
||||
{ |
||||
// Enough space
|
||||
curr_bits_n = (uint8_t)bits_remain; |
||||
} |
||||
else |
||||
{ |
||||
curr_bits_n = (8 - i_bit_index); |
||||
} |
||||
|
||||
// Pack these n bits into the current byte
|
||||
// Mask out whatever was at that position with ones (xxx11111)
|
||||
buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n)); |
||||
// Put content to this position, by masking out the non-used part
|
||||
buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v); |
||||
|
||||
// Increment the bit index
|
||||
i_bit_index += curr_bits_n; |
||||
|
||||
// Now proceed to the next byte, if necessary
|
||||
bits_remain -= curr_bits_n; |
||||
if (bits_remain > 0) |
||||
{ |
||||
// Offer another 8 bits / one byte
|
||||
i_byte_index++; |
||||
i_bit_index = 0; |
||||
} |
||||
} |
||||
|
||||
*r_bit_index = i_bit_index; |
||||
// If a partly filled byte is present, mark this as consumed
|
||||
if (i_bit_index != 7) i_byte_index++; |
||||
return i_byte_index - packet_index; |
||||
} |
||||
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
||||
|
||||
// To make MAVLink work on your MCU, define comm_send_ch() if you wish
|
||||
// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a
|
||||
// whole packet at a time
|
||||
|
||||
/*
|
||||
|
||||
#include "mavlink_types.h" |
||||
|
||||
void comm_send_ch(mavlink_channel_t chan, uint8_t ch) |
||||
{ |
||||
if (chan == MAVLINK_COMM_0) |
||||
{ |
||||
uart0_transmit(ch); |
||||
} |
||||
if (chan == MAVLINK_COMM_1) |
||||
{ |
||||
uart1_transmit(ch); |
||||
} |
||||
} |
||||
*/ |
||||
|
||||
MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len) |
||||
{ |
||||
#ifdef MAVLINK_SEND_UART_BYTES |
||||
/* this is the more efficient approach, if the platform
|
||||
defines it */ |
||||
MAVLINK_SEND_UART_BYTES(chan, (uint8_t *)buf, len); |
||||
#else |
||||
/* fallback to one byte at a time */ |
||||
uint16_t i; |
||||
for (i = 0; i < len; i++) { |
||||
comm_send_ch(chan, (uint8_t)buf[i]); |
||||
} |
||||
#endif |
||||
} |
||||
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
#endif /* _MAVLINK_HELPERS_H_ */ |
@ -0,0 +1,180 @@
@@ -0,0 +1,180 @@
|
||||
#ifndef MAVLINK_TYPES_H_ |
||||
#define MAVLINK_TYPES_H_ |
||||
|
||||
enum MAV_ACTION |
||||
{ |
||||
MAV_ACTION_HOLD = 0, |
||||
MAV_ACTION_MOTORS_START = 1, |
||||
MAV_ACTION_LAUNCH = 2, |
||||
MAV_ACTION_RETURN = 3, |
||||
MAV_ACTION_EMCY_LAND = 4, |
||||
MAV_ACTION_EMCY_KILL = 5, |
||||
MAV_ACTION_CONFIRM_KILL = 6, |
||||
MAV_ACTION_CONTINUE = 7, |
||||
MAV_ACTION_MOTORS_STOP = 8, |
||||
MAV_ACTION_HALT = 9, |
||||
MAV_ACTION_SHUTDOWN = 10, |
||||
MAV_ACTION_REBOOT = 11, |
||||
MAV_ACTION_SET_MANUAL = 12, |
||||
MAV_ACTION_SET_AUTO = 13, |
||||
MAV_ACTION_STORAGE_READ = 14, |
||||
MAV_ACTION_STORAGE_WRITE = 15, |
||||
MAV_ACTION_CALIBRATE_RC = 16, |
||||
MAV_ACTION_CALIBRATE_GYRO = 17, |
||||
MAV_ACTION_CALIBRATE_MAG = 18, |
||||
MAV_ACTION_CALIBRATE_ACC = 19, |
||||
MAV_ACTION_CALIBRATE_PRESSURE = 20, |
||||
MAV_ACTION_REC_START = 21, |
||||
MAV_ACTION_REC_PAUSE = 22, |
||||
MAV_ACTION_REC_STOP = 23, |
||||
MAV_ACTION_TAKEOFF = 24, |
||||
MAV_ACTION_NAVIGATE = 25, |
||||
MAV_ACTION_LAND = 26, |
||||
MAV_ACTION_LOITER = 27, |
||||
MAV_ACTION_SET_ORIGIN = 28, |
||||
MAV_ACTION_RELAY_ON = 29, |
||||
MAV_ACTION_RELAY_OFF = 30, |
||||
MAV_ACTION_GET_IMAGE = 31, |
||||
MAV_ACTION_VIDEO_START = 32, |
||||
MAV_ACTION_VIDEO_STOP = 33, |
||||
MAV_ACTION_RESET_MAP = 34, |
||||
MAV_ACTION_RESET_PLAN = 35, |
||||
MAV_ACTION_DELAY_BEFORE_COMMAND = 36, |
||||
MAV_ACTION_ASCEND_AT_RATE = 37, |
||||
MAV_ACTION_CHANGE_MODE = 38, |
||||
MAV_ACTION_LOITER_MAX_TURNS = 39, |
||||
MAV_ACTION_LOITER_MAX_TIME = 40, |
||||
MAV_ACTION_START_HILSIM = 41, |
||||
MAV_ACTION_STOP_HILSIM = 42,
|
||||
MAV_ACTION_NB ///< Number of MAV actions
|
||||
}; |
||||
|
||||
#ifndef MAVLINK_MAX_PAYLOAD_LEN |
||||
// it is possible to override this, but be careful!
|
||||
#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length
|
||||
#endif |
||||
|
||||
#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte)
|
||||
#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum
|
||||
#define MAVLINK_NUM_CHECKSUM_BYTES 2 |
||||
#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES) |
||||
|
||||
#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length
|
||||
|
||||
typedef struct param_union { |
||||
union { |
||||
float param_float; |
||||
int32_t param_int32; |
||||
uint32_t param_uint32; |
||||
}; |
||||
uint8_t type; |
||||
} mavlink_param_union_t; |
||||
|
||||
typedef struct __mavlink_system { |
||||
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 type; ///< Unused, can be used by user to store the system's type
|
||||
uint8_t state; ///< Unused, can be used by user to store the system's state
|
||||
uint8_t mode; ///< Unused, can be used by user to store the system's mode
|
||||
uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode
|
||||
} mavlink_system_t; |
||||
|
||||
typedef struct __mavlink_message { |
||||
uint16_t checksum; /// sent at end of packet
|
||||
uint8_t magic; ///< protocol magic marker
|
||||
uint8_t len; ///< Length of payload
|
||||
uint8_t seq; ///< Sequence of packet
|
||||
uint8_t sysid; ///< ID of message sender system/aircraft
|
||||
uint8_t compid; ///< ID of the message sender component
|
||||
uint8_t msgid; ///< ID of message in payload
|
||||
uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8]; |
||||
} mavlink_message_t; |
||||
|
||||
typedef enum { |
||||
MAVLINK_TYPE_CHAR = 0, |
||||
MAVLINK_TYPE_UINT8_T = 1, |
||||
MAVLINK_TYPE_INT8_T = 2, |
||||
MAVLINK_TYPE_UINT16_T = 3, |
||||
MAVLINK_TYPE_INT16_T = 4, |
||||
MAVLINK_TYPE_UINT32_T = 5, |
||||
MAVLINK_TYPE_INT32_T = 6, |
||||
MAVLINK_TYPE_UINT64_T = 7, |
||||
MAVLINK_TYPE_INT64_T = 8, |
||||
MAVLINK_TYPE_FLOAT = 9, |
||||
MAVLINK_TYPE_DOUBLE = 10 |
||||
} mavlink_message_type_t; |
||||
|
||||
#define MAVLINK_MAX_FIELDS 64 |
||||
|
||||
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
|
||||
} mavlink_field_info_t; |
||||
|
||||
// note that in this structure the order of fields is the order
|
||||
// in the XML file, not necessary the wire order
|
||||
typedef struct __mavlink_message_info { |
||||
const char *name; // name of the message
|
||||
unsigned num_fields; // how many fields in this message
|
||||
mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information
|
||||
} mavlink_message_info_t; |
||||
|
||||
#define _MAV_PAYLOAD(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)) |
||||
|
||||
typedef enum { |
||||
MAVLINK_COMM_0, |
||||
MAVLINK_COMM_1, |
||||
MAVLINK_COMM_2, |
||||
MAVLINK_COMM_3 |
||||
} mavlink_channel_t; |
||||
|
||||
/*
|
||||
* applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number |
||||
* of buffers they will use. If more are used, then the result will be |
||||
* a stack overrun |
||||
*/ |
||||
#ifndef MAVLINK_COMM_NUM_BUFFERS |
||||
#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) |
||||
# define MAVLINK_COMM_NUM_BUFFERS 16 |
||||
#else |
||||
# define MAVLINK_COMM_NUM_BUFFERS 4 |
||||
#endif |
||||
#endif |
||||
|
||||
typedef enum { |
||||
MAVLINK_PARSE_STATE_UNINIT=0, |
||||
MAVLINK_PARSE_STATE_IDLE, |
||||
MAVLINK_PARSE_STATE_GOT_STX, |
||||
MAVLINK_PARSE_STATE_GOT_SEQ, |
||||
MAVLINK_PARSE_STATE_GOT_LENGTH, |
||||
MAVLINK_PARSE_STATE_GOT_SYSID, |
||||
MAVLINK_PARSE_STATE_GOT_COMPID, |
||||
MAVLINK_PARSE_STATE_GOT_MSGID, |
||||
MAVLINK_PARSE_STATE_GOT_PAYLOAD, |
||||
MAVLINK_PARSE_STATE_GOT_CRC1 |
||||
} mavlink_parse_state_t; ///< The state machine for the comm parser
|
||||
|
||||
typedef struct __mavlink_status { |
||||
uint8_t msg_received; ///< Number of received messages
|
||||
uint8_t buffer_overrun; ///< Number of buffer overruns
|
||||
uint8_t parse_error; ///< Number of parse errors
|
||||
mavlink_parse_state_t parse_state; ///< Parsing state machine
|
||||
uint8_t packet_idx; ///< Index in current packet
|
||||
uint8_t current_rx_seq; ///< Sequence number of last packet received
|
||||
uint8_t current_tx_seq; ///< Sequence number of last packet sent
|
||||
uint16_t packet_rx_success_count; ///< Received packets
|
||||
uint16_t packet_rx_drop_count; ///< Number of packet drops
|
||||
} mavlink_status_t; |
||||
|
||||
#define MAVLINK_BIG_ENDIAN 0 |
||||
#define MAVLINK_LITTLE_ENDIAN 1 |
||||
|
||||
#endif /* MAVLINK_TYPES_H_ */ |
@ -0,0 +1,324 @@
@@ -0,0 +1,324 @@
|
||||
#ifndef _MAVLINK_PROTOCOL_H_ |
||||
#define _MAVLINK_PROTOCOL_H_ |
||||
|
||||
#include "string.h" |
||||
#include "mavlink_types.h" |
||||
|
||||
/*
|
||||
If you want MAVLink on a system that is native big-endian, |
||||
you need to define NATIVE_BIG_ENDIAN |
||||
*/ |
||||
#ifdef NATIVE_BIG_ENDIAN |
||||
# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN) |
||||
#else |
||||
# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN) |
||||
#endif |
||||
|
||||
#ifndef MAVLINK_STACK_BUFFER |
||||
#define MAVLINK_STACK_BUFFER 0 |
||||
#endif |
||||
|
||||
#ifndef MAVLINK_AVOID_GCC_STACK_BUG |
||||
# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__) |
||||
#endif |
||||
|
||||
#ifndef MAVLINK_ASSERT |
||||
#define MAVLINK_ASSERT(x) |
||||
#endif |
||||
|
||||
#ifndef MAVLINK_START_UART_SEND |
||||
#define MAVLINK_START_UART_SEND(chan, length) |
||||
#endif |
||||
|
||||
#ifndef MAVLINK_END_UART_SEND |
||||
#define MAVLINK_END_UART_SEND(chan, length) |
||||
#endif |
||||
|
||||
#ifdef MAVLINK_SEPARATE_HELPERS |
||||
#define MAVLINK_HELPER |
||||
#else |
||||
#define MAVLINK_HELPER static inline |
||||
#include "mavlink_helpers.h" |
||||
#endif // MAVLINK_SEPARATE_HELPERS
|
||||
|
||||
/* always include the prototypes to ensure we don't get out of sync */ |
||||
MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan); |
||||
#if MAVLINK_CRC_EXTRA |
||||
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
|
||||
uint8_t chan, uint8_t length, uint8_t crc_extra); |
||||
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
|
||||
uint8_t length, uint8_t crc_extra); |
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
||||
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
|
||||
uint8_t length, uint8_t crc_extra); |
||||
#endif |
||||
#else |
||||
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
|
||||
uint8_t chan, uint8_t length); |
||||
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
|
||||
uint8_t length); |
||||
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length); |
||||
#endif // MAVLINK_CRC_EXTRA
|
||||
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg); |
||||
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg); |
||||
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); |
||||
MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index,
|
||||
uint8_t* r_bit_index, uint8_t* buffer); |
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
||||
MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); |
||||
#endif |
||||
|
||||
/**
|
||||
* @brief Get the required buffer size for this message |
||||
*/ |
||||
static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg) |
||||
{ |
||||
return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES; |
||||
} |
||||
|
||||
#if MAVLINK_NEED_BYTE_SWAP |
||||
static inline void byte_swap_2(char *dst, const char *src) |
||||
{ |
||||
dst[0] = src[1]; |
||||
dst[1] = src[0]; |
||||
} |
||||
static inline void byte_swap_4(char *dst, const char *src) |
||||
{ |
||||
dst[0] = src[3]; |
||||
dst[1] = src[2]; |
||||
dst[2] = src[1]; |
||||
dst[3] = src[0]; |
||||
} |
||||
static inline void byte_swap_8(char *dst, const char *src) |
||||
{ |
||||
dst[0] = src[7]; |
||||
dst[1] = src[6]; |
||||
dst[2] = src[5]; |
||||
dst[3] = src[4]; |
||||
dst[4] = src[3]; |
||||
dst[5] = src[2]; |
||||
dst[6] = src[1]; |
||||
dst[7] = src[0]; |
||||
} |
||||
#elif !MAVLINK_ALIGNED_FIELDS |
||||
static inline void byte_copy_2(char *dst, const char *src) |
||||
{ |
||||
dst[0] = src[0]; |
||||
dst[1] = src[1]; |
||||
} |
||||
static inline void byte_copy_4(char *dst, const char *src) |
||||
{ |
||||
dst[0] = src[0]; |
||||
dst[1] = src[1]; |
||||
dst[2] = src[2]; |
||||
dst[3] = src[3]; |
||||
} |
||||
static inline void byte_copy_8(char *dst, const char *src) |
||||
{ |
||||
memcpy(dst, src, 8); |
||||
} |
||||
#endif |
||||
|
||||
#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b |
||||
#define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b |
||||
#define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b |
||||
|
||||
#if MAVLINK_NEED_BYTE_SWAP |
||||
#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) |
||||
#elif !MAVLINK_ALIGNED_FIELDS |
||||
#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) |
||||
#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) |
||||
#else |
||||
#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b |
||||
#define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b |
||||
#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b |
||||
#define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b |
||||
#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b |
||||
#define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b |
||||
#define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b |
||||
#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b |
||||
#endif |
||||
|
||||
|
||||
/*
|
||||
* Place a char array into a buffer |
||||
*/ |
||||
static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length) |
||||
{ |
||||
if (b == NULL) { |
||||
memset(&buf[wire_offset], 0, array_length); |
||||
} else { |
||||
memcpy(&buf[wire_offset], b, array_length); |
||||
} |
||||
} |
||||
|
||||
/*
|
||||
* Place a uint8_t array into a buffer |
||||
*/ |
||||
static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length) |
||||
{ |
||||
if (b == NULL) { |
||||
memset(&buf[wire_offset], 0, array_length); |
||||
} else { |
||||
memcpy(&buf[wire_offset], b, array_length); |
||||
} |
||||
} |
||||
|
||||
/*
|
||||
* Place a int8_t array into a buffer |
||||
*/ |
||||
static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length) |
||||
{ |
||||
if (b == NULL) { |
||||
memset(&buf[wire_offset], 0, array_length); |
||||
} else { |
||||
memcpy(&buf[wire_offset], b, array_length); |
||||
} |
||||
} |
||||
|
||||
#if MAVLINK_NEED_BYTE_SWAP |
||||
#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) \
|
||||
{ \
|
||||
if (b == NULL) { \
|
||||
memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \
|
||||
} else { \
|
||||
uint16_t i; \
|
||||
for (i=0; i<array_length; i++) { \
|
||||
_mav_put_## TYPE (buf, wire_offset+(i*sizeof(TYPE)), b[i]); \
|
||||
} \
|
||||
} \
|
||||
} |
||||
#else |
||||
#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) \
|
||||
{ \
|
||||
if (b == NULL) { \
|
||||
memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \
|
||||
} else { \
|
||||
memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \
|
||||
} \
|
||||
} |
||||
#endif |
||||
|
||||
_MAV_PUT_ARRAY(uint16_t, u16) |
||||
_MAV_PUT_ARRAY(uint32_t, u32) |
||||
_MAV_PUT_ARRAY(uint64_t, u64) |
||||
_MAV_PUT_ARRAY(int16_t, i16) |
||||
_MAV_PUT_ARRAY(int32_t, i32) |
||||
_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] |
||||
|
||||
#if MAVLINK_NEED_BYTE_SWAP |
||||
#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \ |
||||
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
|
||||
{ TYPE r; byte_swap_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; } |
||||
|
||||
_MAV_MSG_RETURN_TYPE(uint16_t, 2) |
||||
_MAV_MSG_RETURN_TYPE(int16_t, 2) |
||||
_MAV_MSG_RETURN_TYPE(uint32_t, 4) |
||||
_MAV_MSG_RETURN_TYPE(int32_t, 4) |
||||
_MAV_MSG_RETURN_TYPE(uint64_t, 8) |
||||
_MAV_MSG_RETURN_TYPE(int64_t, 8) |
||||
_MAV_MSG_RETURN_TYPE(float, 4) |
||||
_MAV_MSG_RETURN_TYPE(double, 8) |
||||
|
||||
#elif !MAVLINK_ALIGNED_FIELDS |
||||
#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \ |
||||
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
|
||||
{ TYPE r; byte_copy_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; } |
||||
|
||||
_MAV_MSG_RETURN_TYPE(uint16_t, 2) |
||||
_MAV_MSG_RETURN_TYPE(int16_t, 2) |
||||
_MAV_MSG_RETURN_TYPE(uint32_t, 4) |
||||
_MAV_MSG_RETURN_TYPE(int32_t, 4) |
||||
_MAV_MSG_RETURN_TYPE(uint64_t, 8) |
||||
_MAV_MSG_RETURN_TYPE(int64_t, 8) |
||||
_MAV_MSG_RETURN_TYPE(float, 4) |
||||
_MAV_MSG_RETURN_TYPE(double, 8) |
||||
#else // nicely aligned, no swap
|
||||
#define _MAV_MSG_RETURN_TYPE(TYPE) \ |
||||
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
|
||||
{ return *(const TYPE *)(&_MAV_PAYLOAD(msg)[ofs]);} |
||||
|
||||
_MAV_MSG_RETURN_TYPE(uint16_t) |
||||
_MAV_MSG_RETURN_TYPE(int16_t) |
||||
_MAV_MSG_RETURN_TYPE(uint32_t) |
||||
_MAV_MSG_RETURN_TYPE(int32_t) |
||||
_MAV_MSG_RETURN_TYPE(uint64_t) |
||||
_MAV_MSG_RETURN_TYPE(int64_t) |
||||
_MAV_MSG_RETURN_TYPE(float) |
||||
_MAV_MSG_RETURN_TYPE(double) |
||||
#endif // MAVLINK_NEED_BYTE_SWAP
|
||||
|
||||
static inline uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value,
|
||||
uint8_t array_length, uint8_t wire_offset) |
||||
{ |
||||
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length); |
||||
return array_length; |
||||
} |
||||
|
||||
static inline uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value,
|
||||
uint8_t array_length, uint8_t wire_offset) |
||||
{ |
||||
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length); |
||||
return array_length; |
||||
} |
||||
|
||||
static inline uint16_t _MAV_RETURN_int8_t_array(const mavlink_message_t *msg, int8_t *value,
|
||||
uint8_t array_length, uint8_t wire_offset) |
||||
{ |
||||
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length); |
||||
return array_length; |
||||
} |
||||
|
||||
#if MAVLINK_NEED_BYTE_SWAP |
||||
#define _MAV_RETURN_ARRAY(TYPE, V) \ |
||||
static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
|
||||
uint8_t array_length, uint8_t wire_offset) \
|
||||
{ \
|
||||
uint16_t i; \
|
||||
for (i=0; i<array_length; i++) { \
|
||||
value[i] = _MAV_RETURN_## TYPE (msg, wire_offset+(i*sizeof(value[0]))); \
|
||||
} \
|
||||
return array_length*sizeof(value[0]); \
|
||||
} |
||||
#else |
||||
#define _MAV_RETURN_ARRAY(TYPE, V) \ |
||||
static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
|
||||
uint8_t array_length, uint8_t wire_offset) \
|
||||
{ \
|
||||
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length*sizeof(TYPE)); \
|
||||
return array_length*sizeof(TYPE); \
|
||||
} |
||||
#endif |
||||
|
||||
_MAV_RETURN_ARRAY(uint16_t, u16) |
||||
_MAV_RETURN_ARRAY(uint32_t, u32) |
||||
_MAV_RETURN_ARRAY(uint64_t, u64) |
||||
_MAV_RETURN_ARRAY(int16_t, i16) |
||||
_MAV_RETURN_ARRAY(int32_t, i32) |
||||
_MAV_RETURN_ARRAY(int64_t, i64) |
||||
_MAV_RETURN_ARRAY(float, f) |
||||
_MAV_RETURN_ARRAY(double, d) |
||||
|
||||
#endif // _MAVLINK_PROTOCOL_H_
|
@ -0,0 +1 @@
@@ -0,0 +1 @@
|
||||
*.pyc |
@ -0,0 +1,69 @@
@@ -0,0 +1,69 @@
|
||||
#!/usr/bin/env python |
||||
''' |
||||
parse a MAVLink protocol XML file and generate a python implementation |
||||
|
||||
Copyright Andrew Tridgell 2011 |
||||
Released under GNU GPL version 3 or later |
||||
''' |
||||
|
||||
import sys, textwrap, os |
||||
from optparse import OptionParser |
||||
|
||||
# allow import from the parent directory, where mavutil.py is |
||||
sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) |
||||
|
||||
import mavparse |
||||
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") |
||||
(opts, args) = parser.parse_args() |
||||
|
||||
if len(args) < 1: |
||||
parser.error("You must supply at least one MAVLink XML protocol definition") |
||||
|
||||
|
||||
xml = [] |
||||
|
||||
for fname in args: |
||||
print("Parsing %s" % fname) |
||||
xml.append(mavparse.MAVXML(fname, opts.wire_protocol)) |
||||
|
||||
# expand includes |
||||
for x in xml[:]: |
||||
for i in x.include: |
||||
fname = os.path.join(os.path.dirname(x.filename), i) |
||||
print("Parsing %s" % fname) |
||||
xml.append(mavparse.MAVXML(fname, opts.wire_protocol)) |
||||
|
||||
# include message lengths and CRCs too |
||||
for idx in range(0, 256): |
||||
if x.message_lengths[idx] == 0: |
||||
x.message_lengths[idx] = xml[-1].message_lengths[idx] |
||||
x.message_crcs[idx] = xml[-1].message_crcs[idx] |
||||
x.message_names[idx] = xml[-1].message_names[idx] |
||||
|
||||
# work out max payload size across all includes |
||||
largest_payload = 0 |
||||
for x in xml: |
||||
if x.largest_payload > largest_payload: |
||||
largest_payload = x.largest_payload |
||||
for x in xml: |
||||
x.largest_payload = largest_payload |
||||
|
||||
if mavparse.check_duplicates(xml): |
||||
sys.exit(1) |
||||
|
||||
print("Found %u MAVLink message types in %u XML files" % ( |
||||
mavparse.total_msgs(xml), len(xml))) |
||||
|
||||
if opts.language == 'python': |
||||
mavgen_python.generate(opts.output, xml) |
||||
elif opts.language == 'C': |
||||
mavgen_c.generate(opts.output, xml) |
||||
else: |
||||
print("Unsupported language %s" % opts.language) |
||||
|
@ -0,0 +1,139 @@
@@ -0,0 +1,139 @@
|
||||
#!/usr/bin/env python |
||||
''' |
||||
generate a MAVLink test suite |
||||
|
||||
Copyright Andrew Tridgell 2011 |
||||
Released under GNU GPL version 3 or later |
||||
''' |
||||
|
||||
import sys, textwrap |
||||
from optparse import OptionParser |
||||
import mavparse |
||||
|
||||
def gen_value(f, i, language): |
||||
'''generate a test value for the ith field of a message''' |
||||
type = f.type |
||||
|
||||
# could be an array |
||||
if type.find("[") != -1: |
||||
aidx = type.find("[") |
||||
basetype = type[0:aidx] |
||||
if basetype == "array": |
||||
basetype = "int8_t" |
||||
if language == 'C': |
||||
return '(const %s *)"%s%u"' % (basetype, f.name, i) |
||||
return '"%s%u"' % (f.name, i) |
||||
|
||||
if type == 'float': |
||||
return 17.0 + i*7 |
||||
if type == 'char': |
||||
return 'A' + i |
||||
if type == 'int8_t': |
||||
return 5 + i |
||||
if type in ['int8_t', 'uint8_t']: |
||||
return 5 + i |
||||
if type in ['uint8_t_mavlink_version']: |
||||
return 2 |
||||
if type in ['int16_t', 'uint16_t']: |
||||
return 17235 + i*52 |
||||
if type in ['int32_t', 'uint32_t']: |
||||
v = 963497464 + i*52 |
||||
if language == 'C': |
||||
return "%sL" % v |
||||
return v |
||||
if type in ['int64_t', 'uint64_t']: |
||||
v = 9223372036854775807 + i*63 |
||||
if language == 'C': |
||||
return "%sLL" % v |
||||
return v |
||||
|
||||
|
||||
|
||||
def generate_methods_python(outf, msgs): |
||||
outf.write(""" |
||||
''' |
||||
MAVLink protocol test implementation (auto-generated by mavtestgen.py) |
||||
|
||||
Generated from: %s |
||||
|
||||
Note: this file has been auto-generated. DO NOT EDIT |
||||
''' |
||||
|
||||
import mavlink |
||||
|
||||
def generate_outputs(mav): |
||||
'''generate all message types as outputs''' |
||||
""") |
||||
for m in msgs: |
||||
if m.name == "HEARTBEAT": continue |
||||
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'))) |
||||
if i != len(m.fields)-1: |
||||
outf.write(",") |
||||
outf.write(")\n") |
||||
|
||||
|
||||
def generate_methods_C(outf, msgs): |
||||
outf.write(""" |
||||
/* |
||||
MAVLink protocol test implementation (auto-generated by mavtestgen.py) |
||||
|
||||
Generated from: %s |
||||
|
||||
Note: this file has been auto-generated. DO NOT EDIT |
||||
*/ |
||||
|
||||
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()) |
||||
for i in range(0, len(m.fields)): |
||||
f = m.fields[i] |
||||
outf.write("%s" % gen_value(f, i, 'C')) |
||||
if i != len(m.fields)-1: |
||||
outf.write(",") |
||||
outf.write(");\n") |
||||
outf.write("}\n") |
||||
|
||||
|
||||
|
||||
###################################################################### |
||||
'''main program''' |
||||
|
||||
parser = OptionParser("mavtestgen.py [options] <XML files>") |
||||
parser.add_option("-o", "--output", dest="output", default="mavtest", help="output file base name") |
||||
(opts, args) = parser.parse_args() |
||||
|
||||
if len(args) < 1: |
||||
parser.error("You must supply at least one MAVLink XML protocol definition") |
||||
|
||||
|
||||
msgs = [] |
||||
enums = [] |
||||
|
||||
for fname in args: |
||||
(m, e) = mavparse.parse_mavlink_xml(fname) |
||||
msgs.extend(m) |
||||
enums.extend(e) |
||||
|
||||
|
||||
if mavparse.check_duplicates(msgs): |
||||
sys.exit(1) |
||||
|
||||
print("Found %u MAVLink message types" % len(msgs)) |
||||
|
||||
print("Generating python %s" % (opts.output+'.py')) |
||||
outf = open(opts.output + '.py', "w") |
||||
generate_methods_python(outf, msgs) |
||||
outf.close() |
||||
|
||||
print("Generating C %s" % (opts.output+'.h')) |
||||
outf = open(opts.output + '.h', "w") |
||||
generate_methods_C(outf, msgs) |
||||
outf.close() |
||||
|
||||
print("Generated %s OK" % opts.output) |
Loading…
Reference in new issue