mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: Cleanup - removes autoenabling of fence with AC_Fence parameter
This commit is contained in:
parent
8ef68c8fb0
commit
d055d7a581
|
@ -1522,11 +1522,6 @@ bool ModeAuto::verify_takeoff()
|
|||
if (reached_wp_dest) {
|
||||
// retract the landing gear
|
||||
copter.landinggear.retract_after_takeoff();
|
||||
|
||||
#if AC_FENCE == ENABLED
|
||||
// auto-enable the fence after takeoff
|
||||
copter.fence.auto_enable_fence_after_takeoff();
|
||||
#endif
|
||||
}
|
||||
|
||||
return reached_wp_dest;
|
||||
|
|
|
@ -398,11 +398,6 @@ void ModeGuided::takeoff_run()
|
|||
// optionally retract landing gear
|
||||
copter.landinggear.retract_after_takeoff();
|
||||
|
||||
#if AC_FENCE == ENABLED
|
||||
// takeoff complete, enable fence
|
||||
copter.fence.auto_enable_fence_after_takeoff();
|
||||
#endif
|
||||
|
||||
// switch to position control mode but maintain current target
|
||||
const Vector3f target = wp_nav->get_wp_destination();
|
||||
set_destination(target, false, 0, false, 0, false, wp_nav->origin_and_destination_are_terrain_alt());
|
||||
|
|
Loading…
Reference in New Issue