Skip to content
Snippets Groups Projects
Commit a6250ee0 authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

GCS_MAVLink: fixed const in buffer based send call

parent e8ef484e
No related branches found
No related tags found
No related merge requests found
...@@ -117,6 +117,7 @@ MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint ...@@ -117,6 +117,7 @@ MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint
buf[4] = mavlink_system.compid; buf[4] = mavlink_system.compid;
buf[5] = msgid; buf[5] = msgid;
status->current_tx_seq++; status->current_tx_seq++;
checksum = crc_calculate((uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN); checksum = crc_calculate((uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN);
crc_accumulate_buffer(&checksum, packet, length); crc_accumulate_buffer(&checksum, packet, length);
#if MAVLINK_CRC_EXTRA #if MAVLINK_CRC_EXTRA
...@@ -511,7 +512,7 @@ MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, ...@@ -511,7 +512,7 @@ MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf,
#ifdef MAVLINK_SEND_UART_BYTES #ifdef MAVLINK_SEND_UART_BYTES
/* this is the more efficient approach, if the platform /* this is the more efficient approach, if the platform
defines it */ defines it */
MAVLINK_SEND_UART_BYTES(chan, (uint8_t *)buf, len); MAVLINK_SEND_UART_BYTES(chan, (const uint8_t *)buf, len);
#else #else
/* fallback to one byte at a time */ /* fallback to one byte at a time */
uint16_t i; uint16_t i;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment