Copter: automatically enable and disable floor fence on automated takeoff and landing

This commit is contained in:
Dr.-Ing. Amilcar do Carmo Lucas 2021-01-06 16:19:23 +01:00 committed by Peter Barker
parent 2e422f249a
commit 92122e5133
5 changed files with 45 additions and 2 deletions

View File

@ -383,7 +383,7 @@ private:
RCMapper rcmap;
// intertial nav alt when we armed
// inertial nav alt when we armed
float arming_altitude_m;
// Failsafe
@ -744,7 +744,10 @@ private:
#endif
// fence.cpp
#if AC_FENCE == ENABLED
void fence_check();
void disable_fence_for_landing(void);
#endif
// heli.cpp
void heli_init();

View File

@ -83,4 +83,21 @@ void Copter::fence_check()
}
}
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

@ -21,7 +21,7 @@ public:
RTL = 6, // automatic return to launching point
CIRCLE = 7, // automatic circular flight with automatic throttle
LAND = 9, // automatic landing with horizontal position control
DRIFT = 11, // semi-automous position, yaw and throttle control
DRIFT = 11, // semi-autonomous position, yaw and throttle control
SPORT = 13, // manual earth-frame angular rate control with manual throttle
FLIP = 14, // automatically flip the vehicle on the roll axis
AUTOTUNE = 15, // automatically tune the vehicle's roll and pitch gains
@ -115,6 +115,8 @@ 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,

View File

@ -250,6 +250,10 @@ void ModeAuto::land_start(const Vector3f& destination)
// optionally deploy landing gear
copter.landinggear.deploy_for_landing();
#if AC_FENCE == ENABLED
copter.disable_fence_for_landing();
#endif
}
// auto_circle_movetoedge_start - initialise waypoint controller to move to edge of a circle with it's center at the specified location

View File

@ -76,6 +76,7 @@ void Mode::_TakeOff::stop()
{
_running = false;
start_ms = 0;
copter.flightmode->autoenable_floor_fence();
}
// returns pilot and takeoff climb rates
@ -225,3 +226,19 @@ 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
}