mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 23:18:29 -04:00
ArduPlane: Only run is_flying landing checks when in landing stage
This commit is contained in:
parent
4c5b1e1fc5
commit
8e53fb2a78
@ -70,10 +70,6 @@ void Plane::update_is_flying_5Hz(void)
|
|||||||
crash_state.impact_detected = false;
|
crash_state.impact_detected = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (landing.is_on_approach() && fabsf(auto_state.sink_rate) > 0.2f) {
|
|
||||||
is_flying_bool = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
switch (flight_stage)
|
switch (flight_stage)
|
||||||
{
|
{
|
||||||
case AP_Vehicle::FixedWing::FLIGHT_TAKEOFF:
|
case AP_Vehicle::FixedWing::FLIGHT_TAKEOFF:
|
||||||
@ -93,6 +89,12 @@ void Plane::update_is_flying_5Hz(void)
|
|||||||
// TODO: detect ground impacts
|
// TODO: detect ground impacts
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case AP_Vehicle::FixedWing::FLIGHT_LAND:
|
||||||
|
if (landing.is_on_approach() && fabsf(auto_state.sink_rate) > 0.2f) {
|
||||||
|
is_flying_bool = true;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
case AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND:
|
case AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND:
|
||||||
if (auto_state.sink_rate < -0.5f) {
|
if (auto_state.sink_rate < -0.5f) {
|
||||||
// steep climb
|
// steep climb
|
||||||
|
Loading…
Reference in New Issue
Block a user