mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
MAVLink: updates to mavlink headers to fix mavlink 1.0 issues
This commit is contained in:
parent
13ae16e0c5
commit
1ad17bc78c
@ -5,7 +5,7 @@
|
||||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Fri May 25 17:56:06 2012"
|
||||
#define MAVLINK_BUILD_DATE "Mon Jun 4 13:31:56 2012"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
|
||||
|
||||
|
@ -5,7 +5,7 @@
|
||||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Fri May 25 17:56:06 2012"
|
||||
#define MAVLINK_BUILD_DATE "Mon Jun 4 13:31:56 2012"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
|
||||
|
||||
|
@ -23,7 +23,7 @@ MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
|
||||
*/
|
||||
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
|
||||
@ -133,6 +133,25 @@ MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint
|
||||
}
|
||||
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
/**
|
||||
* @brief re-send a message over a uart channel
|
||||
* this is more stack efficient than re-marshalling the message
|
||||
*/
|
||||
MAVLINK_HELPER void mavlink_uart_resend(mavlink_channel_t chan, const mavlink_message_t *msg)
|
||||
{
|
||||
uint8_t ck[2];
|
||||
|
||||
ck[0] = (uint8_t)(msg->checksum & 0xFF);
|
||||
ck[1] = (uint8_t)(msg->checksum >> 8);
|
||||
|
||||
MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len);
|
||||
_mavlink_send_uart(chan, (const char *)&msg->magic, MAVLINK_NUM_HEADER_BYTES);
|
||||
_mavlink_send_uart(chan, _MAV_PAYLOAD(msg), msg->len);
|
||||
_mavlink_send_uart(chan, (const char *)ck, 2);
|
||||
MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a message to send it over a serial byte stream
|
||||
*/
|
||||
|
@ -60,6 +60,7 @@ MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t
|
||||
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_uart_resend(mavlink_channel_t chan, 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);
|
||||
|
@ -5,7 +5,7 @@
|
||||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Fri May 25 17:56:06 2012"
|
||||
#define MAVLINK_BUILD_DATE "Mon Jun 4 13:31:56 2012"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
|
||||
|
||||
|
@ -5,7 +5,7 @@
|
||||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Fri May 25 17:56:06 2012"
|
||||
#define MAVLINK_BUILD_DATE "Mon Jun 4 13:31:56 2012"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
|
||||
|
||||
|
@ -133,6 +133,25 @@ MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint
|
||||
}
|
||||
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
/**
|
||||
* @brief re-send a message over a uart channel
|
||||
* this is more stack efficient than re-marshalling the message
|
||||
*/
|
||||
MAVLINK_HELPER void mav_uart_resend(mavlink_channel_t chan, const mavlink_message_t *msg)
|
||||
{
|
||||
uint8_t ck[2];
|
||||
|
||||
ck[0] = (uint8_t)(msg->checksum & 0xFF);
|
||||
ck[1] = (uint8_t)(msg->checksum >> 8);
|
||||
|
||||
MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len);
|
||||
_mavlink_send_uart(chan, (const char *)&msg->magic, MAVLINK_NUM_HEADER_BYTES);
|
||||
_mavlink_send_uart(chan, _MAV_PAYLOAD(msg), msg->len);
|
||||
_mavlink_send_uart(chan, ck, 2);
|
||||
MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a message to send it over a serial byte stream
|
||||
*/
|
||||
|
Loading…
Reference in New Issue
Block a user