mirror of https://github.com/ArduPilot/ardupilot
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:
parent
eed6753331
commit
b9c1633358
|
@ -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);
|
||||
|
|
|
@ -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();
|
||||
|
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue