ArduCopter: remove pointless init_optflow wrapper

Hiding a one-line call in a wrapper just adds size to the build
This commit is contained in:
Peter Barker 2021-05-28 13:24:18 +10:00 committed by Randy Mackay
parent eed6753331
commit b9c1633358
3 changed files with 4 additions and 12 deletions

View File

@ -856,7 +856,6 @@ private:
bool rangefinder_alt_ok() const;
bool rangefinder_up_ok() const;
void rpm_update();
void init_optflow();
void update_optical_flow(void);
void compass_cal_update(void);
void accel_cal_update(void);

View File

@ -162,15 +162,6 @@ void Copter::rpm_update(void)
#endif
}
// initialise optical flow sensor
void Copter::init_optflow()
{
#if OPTFLOW == ENABLED
// initialise optical flow sensor
optflow.init(MASK_LOG_OPTFLOW);
#endif // OPTFLOW == ENABLED
}
void Copter::compass_cal_update()
{
compass.cal_update();

View File

@ -123,8 +123,10 @@ void Copter::init_ardupilot()
attitude_control->parameter_sanity_check();
// init the optical flow sensor
init_optflow();
#if OPTFLOW == ENABLED
// initialise optical flow sensor
optflow.init(MASK_LOG_OPTFLOW);
#endif // OPTFLOW == ENABLED
#if HAL_MOUNT_ENABLED
// initialise camera mount