mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: stop using Progmem.h
This commit is contained in:
parent
5d07e5bdbf
commit
5f26c951d8
|
@ -20,15 +20,14 @@
|
|||
This provides some support code and variables for MAVLink enabled sketches
|
||||
|
||||
*/
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_GPS/AP_GPS.h>
|
||||
#include <AP_Progmem/AP_Progmem.h>
|
||||
|
||||
#include "GCS.h"
|
||||
#include "GCS_MAVLink.h"
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_GPS/AP_GPS.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
|
||||
#ifdef MAVLINK_SEPARATE_HELPERS
|
||||
#include "include/mavlink/v1.0/mavlink_helpers.h"
|
||||
#endif
|
||||
|
@ -146,12 +145,12 @@ void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len)
|
|||
mavlink_comm_port[chan]->write(buf, len);
|
||||
}
|
||||
|
||||
static const uint8_t mavlink_message_crc_progmem[256] = MAVLINK_MESSAGE_CRCS;
|
||||
static const uint8_t mavlink_message_crc_table[256] = MAVLINK_MESSAGE_CRCS;
|
||||
|
||||
// return CRC byte for a mavlink message ID
|
||||
uint8_t mavlink_get_message_crc(uint8_t msgid)
|
||||
{
|
||||
return pgm_read_byte(&mavlink_message_crc_progmem[msgid]);
|
||||
return mavlink_message_crc_table[msgid];
|
||||
}
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
|
Loading…
Reference in New Issue