mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: Remove unused fence floor enable function
This commit is contained in:
parent
b2346ef6df
commit
2a9affe517
|
@ -115,8 +115,6 @@ protected:
|
|||
// return expected input throttle setting to hover:
|
||||
virtual float throttle_hover() const;
|
||||
|
||||
void autoenable_floor_fence(void);
|
||||
|
||||
// Alt_Hold based flight mode states used in Alt_Hold, Loiter, and Sport
|
||||
enum AltHoldModeState {
|
||||
AltHold_MotorStopped,
|
||||
|
|
|
@ -225,19 +225,3 @@ bool Mode::is_taking_off() const
|
|||
}
|
||||
return takeoff.running();
|
||||
}
|
||||
|
||||
// called when takeoff is complete
|
||||
void Mode::autoenable_floor_fence(void)
|
||||
{
|
||||
#if AC_FENCE == ENABLED
|
||||
switch(copter.fence.auto_enabled()) {
|
||||
case AC_Fence::AutoEnable::ALWAYS_ENABLED:
|
||||
case AC_Fence::AutoEnable::ENABLE_DISABLE_FLOOR_ONLY:
|
||||
copter.fence.enable(true);
|
||||
break;
|
||||
default:
|
||||
// fence does not auto-enable in other takeoff conditions
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue