AP_Baro: MS5637: fix CRC check
The configuration of MS5637 is different from MS5611 in 2 ways: - The PROM is of 112 bytes rather than 128 - The CRC is located in the first MSB of the first word, not the last one For CRC calculation we also need to zero out the last (missing) word. This renames _check_crc() to _read_prom(), which returns false when the PROM doesn't contain valid data. It also makes it virtual so MS5637 can override it. This also moves the PROM read to be all in the same place rather than split between the CRC field and coefficient fields. Finally calculate_crc() is renamed to crc4() to be shorter and add info on what it does.
This commit is contained in:
parent
7457588d7c
commit
30f631de8f
@ -26,14 +26,7 @@
|
|||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
#define CMD_MS5611_RESET 0x1E
|
#define CMD_MS5611_RESET 0x1E
|
||||||
#define CMD_MS5611_PROM_Setup 0xA0
|
#define CMD_MS56XX_PROM 0xA0
|
||||||
#define CMD_MS5611_PROM_C1 0xA2
|
|
||||||
#define CMD_MS5611_PROM_C2 0xA4
|
|
||||||
#define CMD_MS5611_PROM_C3 0xA6
|
|
||||||
#define CMD_MS5611_PROM_C4 0xA8
|
|
||||||
#define CMD_MS5611_PROM_C5 0xAA
|
|
||||||
#define CMD_MS5611_PROM_C6 0xAC
|
|
||||||
#define CMD_MS5611_PROM_CRC 0xAE
|
|
||||||
|
|
||||||
#define ADDR_CMD_CONVERT_D1_OSR256 0x40 /* write to this address to start pressure conversion */
|
#define ADDR_CMD_CONVERT_D1_OSR256 0x40 /* write to this address to start pressure conversion */
|
||||||
#define ADDR_CMD_CONVERT_D1_OSR512 0x42 /* write to this address to start pressure conversion */
|
#define ADDR_CMD_CONVERT_D1_OSR512 0x42 /* write to this address to start pressure conversion */
|
||||||
@ -202,19 +195,19 @@ void AP_Baro_MS56XX::_init()
|
|||||||
_serial->write(CMD_MS5611_RESET);
|
_serial->write(CMD_MS5611_RESET);
|
||||||
hal.scheduler->delay(4);
|
hal.scheduler->delay(4);
|
||||||
|
|
||||||
// We read the factory calibration
|
uint16_t prom[8];
|
||||||
// The on-chip CRC is not used
|
if (!_read_prom(prom)) {
|
||||||
_C1 = _serial->read_16bits(CMD_MS5611_PROM_C1);
|
AP_HAL::panic("Can't read PROM");
|
||||||
_C2 = _serial->read_16bits(CMD_MS5611_PROM_C2);
|
|
||||||
_C3 = _serial->read_16bits(CMD_MS5611_PROM_C3);
|
|
||||||
_C4 = _serial->read_16bits(CMD_MS5611_PROM_C4);
|
|
||||||
_C5 = _serial->read_16bits(CMD_MS5611_PROM_C5);
|
|
||||||
_C6 = _serial->read_16bits(CMD_MS5611_PROM_C6);
|
|
||||||
|
|
||||||
if (!_check_crc()) {
|
|
||||||
AP_HAL::panic("Bad CRC on MS5611");
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Save factory calibration coefficients
|
||||||
|
_C1 = prom[1];
|
||||||
|
_C2 = prom[2];
|
||||||
|
_C3 = prom[3];
|
||||||
|
_C4 = prom[4];
|
||||||
|
_C5 = prom[5];
|
||||||
|
_C6 = prom[6];
|
||||||
|
|
||||||
// Send a command to read Temp first
|
// Send a command to read Temp first
|
||||||
_serial->write(ADDR_CMD_CONVERT_D2);
|
_serial->write(ADDR_CMD_CONVERT_D2);
|
||||||
_last_timer = AP_HAL::micros();
|
_last_timer = AP_HAL::micros();
|
||||||
@ -235,9 +228,9 @@ void AP_Baro_MS56XX::_init()
|
|||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* MS5611 crc4 method based on PX4Firmware code
|
* MS56XX crc4 method from datasheet for 16 bytes (8 short values)
|
||||||
*/
|
*/
|
||||||
static uint16_t calculate_crc(uint16_t *data)
|
static uint16_t crc4(uint16_t *data)
|
||||||
{
|
{
|
||||||
uint16_t n_rem = 0;
|
uint16_t n_rem = 0;
|
||||||
uint8_t n_bit;
|
uint8_t n_bit;
|
||||||
@ -259,24 +252,54 @@ static uint16_t calculate_crc(uint16_t *data)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/* final 4 bit remainder is CRC value */
|
|
||||||
return (n_rem >> 12) & 0xF;
|
return (n_rem >> 12) & 0xF;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_Baro_MS56XX::_check_crc(void)
|
bool AP_Baro_MS56XX::_read_prom(uint16_t prom[8])
|
||||||
{
|
{
|
||||||
uint16_t n_prom[8] = { _serial->read_16bits(CMD_MS5611_PROM_Setup),
|
/*
|
||||||
_C1, _C2, _C3, _C4, _C5, _C6,
|
* MS5611-01BA datasheet, CYCLIC REDUNDANCY CHECK (CRC): "MS5611-01BA
|
||||||
_serial->read_16bits(CMD_MS5611_PROM_CRC) };
|
* contains a PROM memory with 128-Bit. A 4-bit CRC has been implemented
|
||||||
|
* to check the data validity in memory."
|
||||||
|
*
|
||||||
|
* CRC field must me removed for CRC-4 calculation.
|
||||||
|
*/
|
||||||
|
for (uint8_t i = 0; i < 8; i++) {
|
||||||
|
prom[i] = _serial->read_16bits(CMD_MS56XX_PROM + (i << 1));
|
||||||
|
}
|
||||||
|
|
||||||
/* save the read crc */
|
/* save the read crc */
|
||||||
const uint16_t crc_read = n_prom[7] & 0xF;
|
const uint16_t crc_read = prom[7] & 0xf;
|
||||||
|
|
||||||
/* remove CRC byte */
|
/* remove CRC byte */
|
||||||
n_prom[7] &= ~0xF;
|
prom[7] &= 0xff00;
|
||||||
|
|
||||||
/* return true if CRCs match */
|
return crc_read == crc4(prom);
|
||||||
return crc_read == calculate_crc(n_prom);
|
}
|
||||||
|
|
||||||
|
bool AP_Baro_MS5637::_read_prom(uint16_t prom[8])
|
||||||
|
{
|
||||||
|
/*
|
||||||
|
* MS5637-02BA03 datasheet, CYCLIC REDUNDANCY CHECK (CRC): "MS5637
|
||||||
|
* contains a PROM memory with 112-Bit. A 4-bit CRC has been implemented
|
||||||
|
* to check the data validity in memory."
|
||||||
|
*
|
||||||
|
* 8th PROM word must be zeroed and CRC field removed for CRC-4
|
||||||
|
* calculation.
|
||||||
|
*/
|
||||||
|
for (uint8_t i = 0; i < 7; i++) {
|
||||||
|
prom[i] = _serial->read_16bits(CMD_MS56XX_PROM + (i << 1));
|
||||||
|
}
|
||||||
|
|
||||||
|
prom[7] = 0;
|
||||||
|
|
||||||
|
/* save the read crc */
|
||||||
|
const uint16_t crc_read = (prom[0] & 0xf000) >> 12;
|
||||||
|
|
||||||
|
/* remove CRC byte */
|
||||||
|
prom[0] &= ~0xf000;
|
||||||
|
|
||||||
|
return crc_read == crc4(prom);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -78,15 +78,16 @@ public:
|
|||||||
void update();
|
void update();
|
||||||
void accumulate();
|
void accumulate();
|
||||||
|
|
||||||
private:
|
protected:
|
||||||
|
AP_Baro_MS56XX(AP_Baro &baro, AP_SerialBus *serial, bool use_timer);
|
||||||
|
void _init();
|
||||||
|
|
||||||
virtual void _calculate() = 0;
|
virtual void _calculate() = 0;
|
||||||
|
virtual bool _read_prom(uint16_t prom[8]);
|
||||||
|
void _timer();
|
||||||
|
|
||||||
AP_SerialBus *_serial;
|
AP_SerialBus *_serial;
|
||||||
|
|
||||||
bool _check_crc();
|
|
||||||
|
|
||||||
void _timer();
|
|
||||||
|
|
||||||
/* Asynchronous state: */
|
/* Asynchronous state: */
|
||||||
volatile bool _updated;
|
volatile bool _updated;
|
||||||
volatile uint8_t _d1_count;
|
volatile uint8_t _d1_count;
|
||||||
@ -97,10 +98,6 @@ private:
|
|||||||
|
|
||||||
bool _use_timer;
|
bool _use_timer;
|
||||||
|
|
||||||
protected:
|
|
||||||
AP_Baro_MS56XX(AP_Baro &baro, AP_SerialBus *serial, bool use_timer);
|
|
||||||
void _init();
|
|
||||||
|
|
||||||
// Internal calibration registers
|
// Internal calibration registers
|
||||||
uint16_t _C1,_C2,_C3,_C4,_C5,_C6;
|
uint16_t _C1,_C2,_C3,_C4,_C5,_C6;
|
||||||
float _D1,_D2;
|
float _D1,_D2;
|
||||||
@ -129,5 +126,6 @@ public:
|
|||||||
AP_Baro_MS5637(AP_Baro &baro, AP_SerialBus *serial, bool use_timer);
|
AP_Baro_MS5637(AP_Baro &baro, AP_SerialBus *serial, bool use_timer);
|
||||||
private:
|
private:
|
||||||
void _calculate();
|
void _calculate();
|
||||||
|
bool _read_prom(uint16_t prom[8]) override;
|
||||||
};
|
};
|
||||||
#endif // __AP_BARO_MS5611_H__
|
#endif // __AP_BARO_MS5611_H__
|
||||||
|
Loading…
Reference in New Issue
Block a user