mirror of https://github.com/ArduPilot/ardupilot
AP_Math: stop using Progmem.h
This commit is contained in:
parent
520b0384fd
commit
502077d763
|
@ -9,10 +9,9 @@
|
||||||
* EITHER EXPRESSED OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE IMPLIED
|
* EITHER EXPRESSED OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE IMPLIED
|
||||||
* WARRANTIES OF MERCHANTABILITY AND/OR FITNESS FOR A PARTICULAR PURPOSE.
|
* WARRANTIES OF MERCHANTABILITY AND/OR FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "edc.h"
|
#include "edc.h"
|
||||||
|
|
||||||
#include <AP_Progmem/AP_Progmem.h>
|
#include <inttypes.h>
|
||||||
|
|
||||||
/* CRC16 implementation acording to CCITT standards */
|
/* CRC16 implementation acording to CCITT standards */
|
||||||
static const uint16_t crc16tab[256] = {
|
static const uint16_t crc16tab[256] = {
|
||||||
|
@ -52,7 +51,7 @@ static const uint16_t crc16tab[256] = {
|
||||||
|
|
||||||
uint16_t crc16_ccitt(const uint8_t *buf, uint32_t len, uint16_t crc)
|
uint16_t crc16_ccitt(const uint8_t *buf, uint32_t len, uint16_t crc)
|
||||||
{
|
{
|
||||||
for (uint32_t i = 0; i < len; i++)
|
for (uint32_t i = 0; i < len; i++)
|
||||||
crc = (crc << 8) ^ (uint16_t) pgm_read_word(&crc16tab[((crc >> 8) ^ *buf++) & 0x00FF]);
|
crc = (crc << 8) ^ crc16tab[((crc >> 8) ^ *buf++) & 0x00FF];
|
||||||
return crc;
|
return crc;
|
||||||
}
|
}
|
||||||
|
|
|
@ -16,13 +16,8 @@
|
||||||
|
|
||||||
// Copyright (C) 2010 Swift Navigation Inc.
|
// Copyright (C) 2010 Swift Navigation Inc.
|
||||||
// Contact: Fergus Noble <fergus@swift-nav.com>
|
// Contact: Fergus Noble <fergus@swift-nav.com>
|
||||||
|
#pragma once
|
||||||
#ifndef __EDC_H_
|
|
||||||
#define __EDC_H_
|
|
||||||
|
|
||||||
|
#include <inttypes.h>
|
||||||
#include <stdint.h>
|
|
||||||
|
|
||||||
uint16_t crc16_ccitt(const uint8_t *buf, uint32_t len, uint16_t crc);
|
uint16_t crc16_ccitt(const uint8_t *buf, uint32_t len, uint16_t crc);
|
||||||
|
|
||||||
#endif /* __EDC_H_ */
|
|
||||||
|
|
Loading…
Reference in New Issue