Sub: move barometer_accumulate to sensors.cpp

non-functional change
This commit is contained in:
Randy Mackay 2017-11-22 17:13:05 +09:00
parent 9a03ba1bfb
commit f01b483657
3 changed files with 7 additions and 9 deletions

View File

@ -94,14 +94,6 @@ void Sub::setup()
fast_loopTimer = AP_HAL::micros();
}
/*
try to accumulate a baro reading
*/
void Sub::barometer_accumulate(void)
{
barometer.accumulate();
}
void Sub::perf_update(void)
{
if (should_log(MASK_LOG_PM)) {

View File

@ -460,7 +460,6 @@ private:
void compass_accumulate(void);
void compass_cal_update(void);
void barometer_accumulate(void);
void perf_update(void);
void fast_loop();
void fifty_hz_loop();
@ -642,6 +641,7 @@ private:
void clear_input_hold();
void init_barometer(bool save);
void read_barometer(void);
void barometer_accumulate(void);
void init_rangefinder(void);
void read_rangefinder(void);
bool rangefinder_alt_ok(void);

View File

@ -20,6 +20,12 @@ void Sub::read_barometer(void)
}
}
// try to accumulate a baro reading
void Sub::barometer_accumulate(void)
{
barometer.accumulate();
}
void Sub::init_rangefinder(void)
{
#if RANGEFINDER_ENABLED == ENABLED