From 9a03ba1bfba16feba71aeef86804b7ebf861b208 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 22 Nov 2017 17:12:46 +0900 Subject: [PATCH] Copter: move barometer_accumulate to sensors.cpp non-functional change --- ArduCopter/ArduCopter.cpp | 8 -------- ArduCopter/Copter.h | 2 +- ArduCopter/sensors.cpp | 6 ++++++ 3 files changed, 7 insertions(+), 9 deletions(-) diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index f4d8702ad9..95c1732afa 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -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)) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 64e8180bfe..46d8dee1cf 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -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(); diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index 5cf2a96128..59b09e142c 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -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