Browse Source

mavlink: fixed build with uart resend

mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
012fc35314
  1. 4
      libraries/GCS_MAVLink/include/mavlink/v1.0/mavlink_helpers.h
  2. 1
      libraries/GCS_MAVLink/include/mavlink/v1.0/protocol.h

4
libraries/GCS_MAVLink/include/mavlink/v1.0/mavlink_helpers.h

@ -137,7 +137,7 @@ MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint @@ -137,7 +137,7 @@ MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint
* @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)
MAVLINK_HELPER void mavlink_uart_resend(mavlink_channel_t chan, const mavlink_message_t *msg)
{
uint8_t ck[2];
@ -147,7 +147,7 @@ MAVLINK_HELPER void mav_uart_resend(mavlink_channel_t chan, const mavlink_messag @@ -147,7 +147,7 @@ MAVLINK_HELPER void mav_uart_resend(mavlink_channel_t chan, const mavlink_messag
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_send_uart(chan, (const char *)ck, 2);
MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len);
}

1
libraries/GCS_MAVLink/include/mavlink/v1.0/protocol.h

@ -60,6 +60,7 @@ MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t @@ -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);

Loading…
Cancel
Save