ArduCopter: Use auto enable and auto disable from AC_Fence

This commit is contained in:
James O'Shannessy 2021-01-14 10:37:25 +11:00 committed by Peter Barker
parent 8a99d9dd00
commit a88f2721a8
5 changed files with 10 additions and 41 deletions

View File

@ -746,8 +746,6 @@ private:
// fence.cpp
#if AC_FENCE == ENABLED
void fence_check();
void autoenable_fence_after_takeoff(void);
void disable_fence_for_landing(void);
#endif
// heli.cpp

View File

@ -83,39 +83,4 @@ void Copter::fence_check()
}
}
/*
called when an auto-takeoff is complete
*/
void Copter::autoenable_fence_after_takeoff(void)
{
#if AC_FENCE == ENABLED
switch(fence.auto_enabled()) {
case AC_Fence::AutoEnable::ALWAYS_ENABLED:
case AC_Fence::AutoEnable::ENABLE_DISABLE_FLOOR_ONLY:
fence.enable(true);
break;
default:
// fence does not auto-enable in other takeoff conditions
break;
}
#endif
}
void Copter::disable_fence_for_landing(void)
{
switch (fence.auto_enabled()) {
case AC_Fence::AutoEnable::ALWAYS_ENABLED:
fence.enable(false);
gcs().send_text(MAV_SEVERITY_NOTICE, "Fence disabled (auto disable)");
break;
case AC_Fence::AutoEnable::ENABLE_DISABLE_FLOOR_ONLY:
fence.disable_floor();
gcs().send_text(MAV_SEVERITY_NOTICE, "Fence floor disabled (auto disable)");
break;
default:
// fence does not auto-disable in other landing conditions
break;
}
}
#endif

View File

@ -252,7 +252,7 @@ void ModeAuto::land_start(const Vector3f& destination)
copter.landinggear.deploy_for_landing();
#if AC_FENCE == ENABLED
copter.disable_fence_for_landing();
copter.fence.auto_disable_fence_for_landing();
#endif
}
@ -1522,8 +1522,10 @@ bool ModeAuto::verify_takeoff()
// retract the landing gear
copter.landinggear.retract_after_takeoff();
#if AC_FENCE == ENABLED
// auto-enable the fence after takeoff
copter.autoenable_fence_after_takeoff();
copter.fence.auto_enable_fence_after_takeoff();
#endif
}
return reached_wp_dest;

View File

@ -398,8 +398,10 @@ void ModeGuided::takeoff_run()
// optionally retract landing gear
copter.landinggear.retract_after_takeoff();
#if AC_FENCE == ENABLED
// takeoff complete, enable fence
copter.autoenable_fence_after_takeoff();
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();

View File

@ -40,8 +40,10 @@ bool ModeLand::init(bool ignore_checks)
// optionally deploy landing gear
copter.landinggear.deploy_for_landing();
#if AC_FENCE == ENABLED
// disable the fence on landing
copter.disable_fence_for_landing();
copter.fence.auto_disable_fence_for_landing();
#endif
return true;
}