Copter: move barometer_accumulate to sensors.cpp

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

View File

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

View File

@ -660,7 +660,6 @@ private:
void compass_accumulate(void);
void compass_cal_update(void);
void barometer_accumulate(void);
void perf_update(void);
void fast_loop();
void rc_loop();
@ -1052,6 +1051,7 @@ private:
void radio_passthrough_to_motors();
void init_barometer(bool full_calibration);
void read_barometer(void);
void barometer_accumulate(void);
void init_rangefinder(void);
void read_rangefinder(void);
bool rangefinder_alt_ok();

View File

@ -24,6 +24,12 @@ void Copter::read_barometer(void)
motors->set_air_density_ratio(barometer.get_air_density_ratio());
}
// try to accumulate a baro reading
void Copter::barometer_accumulate(void)
{
barometer.accumulate();
}
void Copter::init_rangefinder(void)
{
#if RANGEFINDER_ENABLED == ENABLED