mirror of https://github.com/ArduPilot/ardupilot
AP_Baro: MS5611: reduce OSR to 1024
This is the same change as done in PX4: This reduces self-heating of the sensor which reduces the amount of altitude change when warming up. Apparently some individual sensors are severely affected by this. Unfortunately it raises the noise level, but Paul is confident it won't be a significant issue.
This commit is contained in:
parent
ea5cd99651
commit
94d01934f7
|
@ -34,8 +34,26 @@ extern const AP_HAL::HAL& hal;
|
||||||
#define CMD_MS5611_PROM_C5 0xAA
|
#define CMD_MS5611_PROM_C5 0xAA
|
||||||
#define CMD_MS5611_PROM_C6 0xAC
|
#define CMD_MS5611_PROM_C6 0xAC
|
||||||
#define CMD_MS5611_PROM_CRC 0xAE
|
#define CMD_MS5611_PROM_CRC 0xAE
|
||||||
#define CMD_CONVERT_D1_OSR4096 0x48 // Maximum resolution (oversampling)
|
|
||||||
#define CMD_CONVERT_D2_OSR4096 0x58 // Maximum resolution (oversampling)
|
#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_OSR1024 0x44 /* write to this address to start pressure conversion */
|
||||||
|
#define ADDR_CMD_CONVERT_D1_OSR2048 0x46 /* write to this address to start pressure conversion */
|
||||||
|
#define ADDR_CMD_CONVERT_D1_OSR4096 0x48 /* write to this address to start pressure conversion */
|
||||||
|
#define ADDR_CMD_CONVERT_D2_OSR256 0x50 /* write to this address to start temperature conversion */
|
||||||
|
#define ADDR_CMD_CONVERT_D2_OSR512 0x52 /* write to this address to start temperature conversion */
|
||||||
|
#define ADDR_CMD_CONVERT_D2_OSR1024 0x54 /* write to this address to start temperature conversion */
|
||||||
|
#define ADDR_CMD_CONVERT_D2_OSR2048 0x56 /* write to this address to start temperature conversion */
|
||||||
|
#define ADDR_CMD_CONVERT_D2_OSR4096 0x58 /* write to this address to start temperature conversion */
|
||||||
|
|
||||||
|
/*
|
||||||
|
use an OSR of 1024 to reduce the self-heating effect of the
|
||||||
|
sensor. Information from MS tells us that some individual sensors
|
||||||
|
are quite sensitive to this effect and that reducing the OSR can
|
||||||
|
make a big difference
|
||||||
|
*/
|
||||||
|
#define ADDR_CMD_CONVERT_D1 ADDR_CMD_CONVERT_D1_OSR1024
|
||||||
|
#define ADDR_CMD_CONVERT_D2 ADDR_CMD_CONVERT_D2_OSR1024
|
||||||
|
|
||||||
// SPI Device //////////////////////////////////////////////////////////////////
|
// SPI Device //////////////////////////////////////////////////////////////////
|
||||||
|
|
||||||
|
@ -194,7 +212,7 @@ AP_Baro_MS56XX::AP_Baro_MS56XX(AP_Baro &baro, AP_SerialBus *serial, bool use_tim
|
||||||
}
|
}
|
||||||
|
|
||||||
// Send a command to read Temp first
|
// Send a command to read Temp first
|
||||||
_serial->write(CMD_CONVERT_D2_OSR4096);
|
_serial->write(ADDR_CMD_CONVERT_D2);
|
||||||
_last_timer = hal.scheduler->micros();
|
_last_timer = hal.scheduler->micros();
|
||||||
_state = 0;
|
_state = 0;
|
||||||
|
|
||||||
|
@ -290,13 +308,13 @@ void AP_Baro_MS56XX::_timer(void)
|
||||||
_d2_count = 16;
|
_d2_count = 16;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (_serial->write(CMD_CONVERT_D1_OSR4096)) { // Command to read pressure
|
if (_serial->write(ADDR_CMD_CONVERT_D1)) { // Command to read pressure
|
||||||
_state++;
|
_state++;
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
/* if read fails, re-initiate a temperature read command or we are
|
/* if read fails, re-initiate a temperature read command or we are
|
||||||
* stuck */
|
* stuck */
|
||||||
_serial->write(CMD_CONVERT_D2_OSR4096);
|
_serial->write(ADDR_CMD_CONVERT_D2);
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
uint32_t d1 = _serial->read_24bits(0);;
|
uint32_t d1 = _serial->read_24bits(0);;
|
||||||
|
@ -316,18 +334,18 @@ void AP_Baro_MS56XX::_timer(void)
|
||||||
_updated = true;
|
_updated = true;
|
||||||
|
|
||||||
if (_state == 4) {
|
if (_state == 4) {
|
||||||
if (_serial->write(CMD_CONVERT_D2_OSR4096)) { // Command to read temperature
|
if (_serial->write(ADDR_CMD_CONVERT_D2)) { // Command to read temperature
|
||||||
_state = 0;
|
_state = 0;
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
if (_serial->write(CMD_CONVERT_D1_OSR4096)) { // Command to read pressure
|
if (_serial->write(ADDR_CMD_CONVERT_D1)) { // Command to read pressure
|
||||||
_state++;
|
_state++;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
/* if read fails, re-initiate a pressure read command or we are
|
/* if read fails, re-initiate a pressure read command or we are
|
||||||
* stuck */
|
* stuck */
|
||||||
_serial->write(CMD_CONVERT_D1_OSR4096);
|
_serial->write(ADDR_CMD_CONVERT_D1);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue