mirror of https://github.com/ArduPilot/ardupilot
Copter: remove pointless wrapper around proximity init
This commit is contained in:
parent
f44335371f
commit
6bfcf2fb53
|
@ -864,7 +864,6 @@ private:
|
||||||
void rpm_update();
|
void rpm_update();
|
||||||
void update_optical_flow(void);
|
void update_optical_flow(void);
|
||||||
void compass_cal_update(void);
|
void compass_cal_update(void);
|
||||||
void init_proximity();
|
|
||||||
|
|
||||||
// RC_Channel.cpp
|
// RC_Channel.cpp
|
||||||
void save_trim();
|
void save_trim();
|
||||||
|
|
|
@ -159,12 +159,3 @@ void Copter::rpm_update(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// initialise proximity sensor
|
|
||||||
void Copter::init_proximity(void)
|
|
||||||
{
|
|
||||||
#if HAL_PROXIMITY_ENABLED
|
|
||||||
g2.proximity.init();
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
|
@ -149,8 +149,10 @@ void Copter::init_ardupilot()
|
||||||
// initialise rangefinder
|
// initialise rangefinder
|
||||||
init_rangefinder();
|
init_rangefinder();
|
||||||
|
|
||||||
|
#if HAL_PROXIMITY_ENABLED
|
||||||
// init proximity sensor
|
// init proximity sensor
|
||||||
init_proximity();
|
g2.proximity.init();
|
||||||
|
#endif
|
||||||
|
|
||||||
#if BEACON_ENABLED == ENABLED
|
#if BEACON_ENABLED == ENABLED
|
||||||
// init beacons used for non-gps position estimation
|
// init beacons used for non-gps position estimation
|
||||||
|
|
Loading…
Reference in New Issue