mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_Baro: remove checks for HAL_BOARD_APM2 and HAL_BOARD_APM1
This commit is contained in:
parent
221d822573
commit
4bd8b2ae35
@ -28,20 +28,16 @@
|
|||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
#define BMP085_ADDRESS 0x77 //(0xEE >> 1)
|
#define BMP085_ADDRESS 0x77 //(0xEE >> 1)
|
||||||
#define BMP085_EOC 30 // End of conversion pin PC7 on APM1
|
|
||||||
|
|
||||||
// the apm2 hardware needs to check the state of the
|
#ifndef BMP085_EOC
|
||||||
// chip using a direct IO port
|
|
||||||
// On APM2 prerelease hw, the data ready port is hooked up to PE7, which
|
|
||||||
// is not available to the arduino digitalRead function.
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
|
||||||
#define BMP_DATA_READY() hal.gpio->read(BMP085_EOC)
|
|
||||||
#else
|
|
||||||
// No EOC connection from Baro
|
// No EOC connection from Baro
|
||||||
// Use times instead.
|
// Use times instead.
|
||||||
// Temp conversion time is 4.5ms
|
// Temp conversion time is 4.5ms
|
||||||
// Pressure conversion time is 25.5ms (for OVERSAMPLING=3)
|
// Pressure conversion time is 25.5ms (for OVERSAMPLING=3)
|
||||||
|
#define BMP085_EOC -1
|
||||||
#define BMP_DATA_READY() (BMP085_State == 0 ? hal.scheduler->millis() > (_last_temp_read_command_time + 5) : hal.scheduler->millis() > (_last_press_read_command_time + 26))
|
#define BMP_DATA_READY() (BMP085_State == 0 ? hal.scheduler->millis() > (_last_temp_read_command_time + 5) : hal.scheduler->millis() > (_last_press_read_command_time + 26))
|
||||||
|
#else
|
||||||
|
#define BMP_DATA_READY() hal.gpio->read(BMP085_EOC)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// oversampling 3 gives 26ms conversion time. We then average
|
// oversampling 3 gives 26ms conversion time. We then average
|
||||||
@ -72,7 +68,9 @@ AP_Baro_BMP085::AP_Baro_BMP085(AP_Baro &baro) :
|
|||||||
}
|
}
|
||||||
|
|
||||||
// End Of Conversion (PC7) input
|
// End Of Conversion (PC7) input
|
||||||
|
if (BMP085_EOC >= 0) {
|
||||||
hal.gpio->pinMode(BMP085_EOC, HAL_GPIO_INPUT);
|
hal.gpio->pinMode(BMP085_EOC, HAL_GPIO_INPUT);
|
||||||
|
}
|
||||||
|
|
||||||
// We read the calibration data registers
|
// We read the calibration data registers
|
||||||
if (hal.i2c->readRegisters(BMP085_ADDRESS, 0xAA, 22, buff) != 0) {
|
if (hal.i2c->readRegisters(BMP085_ADDRESS, 0xAA, 22, buff) != 0) {
|
||||||
|
@ -384,10 +384,9 @@ void AP_Baro_MS5611::_calculate()
|
|||||||
// Formulas from manufacturer datasheet
|
// Formulas from manufacturer datasheet
|
||||||
// sub -15c temperature compensation is not included
|
// sub -15c temperature compensation is not included
|
||||||
|
|
||||||
// we do the calculations using floating point
|
// we do the calculations using floating point allows us to take advantage
|
||||||
// as this is much faster on an AVR2560, and also allows
|
// of the averaging of D1 and D1 over multiple samples, giving us more
|
||||||
// us to take advantage of the averaging of D1 and D1 over
|
// precision
|
||||||
// multiple samples, giving us more precision
|
|
||||||
dT = _D2-(((uint32_t)_C5)<<8);
|
dT = _D2-(((uint32_t)_C5)<<8);
|
||||||
TEMP = (dT * _C6)/8388608;
|
TEMP = (dT * _C6)/8388608;
|
||||||
OFF = _C2 * 65536.0f + (_C4 * dT) / 128;
|
OFF = _C2 * 65536.0f + (_C4 * dT) / 128;
|
||||||
@ -424,10 +423,9 @@ void AP_Baro_MS5607::_calculate()
|
|||||||
// Formulas from manufacturer datasheet
|
// Formulas from manufacturer datasheet
|
||||||
// sub -15c temperature compensation is not included
|
// sub -15c temperature compensation is not included
|
||||||
|
|
||||||
// we do the calculations using floating point
|
// we do the calculations using floating point allows us to take advantage
|
||||||
// as this is much faster on an AVR2560, and also allows
|
// of the averaging of D1 and D1 over multiple samples, giving us more
|
||||||
// us to take advantage of the averaging of D1 and D1 over
|
// precision
|
||||||
// multiple samples, giving us more precision
|
|
||||||
dT = _D2-(((uint32_t)_C5)<<8);
|
dT = _D2-(((uint32_t)_C5)<<8);
|
||||||
TEMP = (dT * _C6)/8388608;
|
TEMP = (dT * _C6)/8388608;
|
||||||
OFF = _C2 * 131072.0f + (_C4 * dT) / 64;
|
OFF = _C2 * 131072.0f + (_C4 * dT) / 64;
|
||||||
|
@ -18,12 +18,6 @@ void setup()
|
|||||||
|
|
||||||
hal.scheduler->delay(1000);
|
hal.scheduler->delay(1000);
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
|
||||||
// disable CS on MPU6000
|
|
||||||
hal.gpio->pinMode(63, HAL_GPIO_OUTPUT);
|
|
||||||
hal.gpio->write(63, 1);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
barometer.init();
|
barometer.init();
|
||||||
barometer.calibrate();
|
barometer.calibrate();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user