ArduSub: 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:19 +10:00 committed by Randy Mackay
parent b9c1633358
commit 26d1e34c19
3 changed files with 2 additions and 14 deletions

View File

@ -550,9 +550,6 @@ private:
void init_rangefinder(void);
void read_rangefinder(void);
bool rangefinder_alt_ok(void) const;
#if OPTFLOW == ENABLED
void init_optflow();
#endif
void terrain_update();
void terrain_logging();
void init_ardupilot() override;

View File

@ -86,15 +86,6 @@ void Sub::rpm_update(void)
}
#endif
// initialise optical flow sensor
#if OPTFLOW == ENABLED
void Sub::init_optflow()
{
// initialise optical flow sensor
optflow.init(MASK_LOG_OPTFLOW);
}
#endif // OPTFLOW == ENABLED
void Sub::accel_cal_update()
{
if (hal.util->get_soft_armed()) {

View File

@ -94,9 +94,9 @@ void Sub::init_ardupilot()
wp_nav.set_terrain(&terrain);
#endif
// init the optical flow sensor
#if OPTFLOW == ENABLED
init_optflow();
// initialise optical flow sensor
optflow.init(MASK_LOG_OPTFLOW);
#endif
#if HAL_MOUNT_ENABLED