mirror of https://github.com/ArduPilot/ardupilot
AP_Baro: remove Baro accumulate API
no backend actually needs to be prodded, everything is done on timers
This commit is contained in:
parent
3b51278481
commit
c5f4fe9a8a
|
@ -1043,16 +1043,6 @@ void AP_Baro::update_field_elevation(void)
|
|||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
call accumulate on all drivers
|
||||
*/
|
||||
void AP_Baro::accumulate(void)
|
||||
{
|
||||
for (uint8_t i=0; i<_num_drivers; i++) {
|
||||
drivers[i]->accumulate();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/* register a new sensor, claiming a sensor slot. If we are out of
|
||||
slots it will panic
|
||||
|
|
|
@ -88,10 +88,6 @@ public:
|
|||
float get_pressure_correction(void) const { return get_pressure_correction(_primary); }
|
||||
float get_pressure_correction(uint8_t instance) const { return sensors[instance].p_correction; }
|
||||
|
||||
// accumulate a reading on sensors. Some backends without their
|
||||
// own thread or a timer may need this.
|
||||
void accumulate(void);
|
||||
|
||||
// calibrate the barometer. This must be called on startup if the
|
||||
// altitude/climb_rate/acceleration interfaces are ever used
|
||||
void calibrate(bool save=true);
|
||||
|
|
|
@ -12,11 +12,6 @@ public:
|
|||
// data to the frontend
|
||||
virtual void update() = 0;
|
||||
|
||||
// accumulate function. This is used for backends that don't use a
|
||||
// timer, and need to be called regularly by the main code to
|
||||
// trigger them to read the sensor
|
||||
virtual void accumulate(void) {}
|
||||
|
||||
void backend_update(uint8_t instance);
|
||||
|
||||
// Check that the baro valid by using a mean filter.
|
||||
|
|
|
@ -33,7 +33,6 @@ static AP_Baro barometer;
|
|||
#endif // HAL_EXTERNAL_AHRS_ENABLED
|
||||
|
||||
static uint32_t timer;
|
||||
static uint8_t counter;
|
||||
static AP_BoardConfig board_config;
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
|
@ -69,14 +68,9 @@ void loop()
|
|||
return;
|
||||
}
|
||||
|
||||
// run accumulate() at 50Hz and update() at 10Hz
|
||||
if ((AP_HAL::micros() - timer) > 20 * 1000UL) {
|
||||
// run update() at 10Hz
|
||||
if ((AP_HAL::micros() - timer) > 100 * 1000UL) {
|
||||
timer = AP_HAL::micros();
|
||||
barometer.accumulate();
|
||||
if (counter++ < 5) {
|
||||
return;
|
||||
}
|
||||
counter = 0;
|
||||
barometer.update();
|
||||
|
||||
//calculate time taken for barometer readings to update
|
||||
|
|
Loading…
Reference in New Issue