mirror of https://github.com/ArduPilot/ardupilot
Plane: update based on PR feedback
This commit is contained in:
parent
6177cbbfe2
commit
b35b94f553
|
@ -38,11 +38,11 @@ AP_Vehicle& vehicle = plane;
|
||||||
// returns true if vehicle is landing. Only used by Lua scripts
|
// returns true if vehicle is landing. Only used by Lua scripts
|
||||||
bool Plane::is_landing() const
|
bool Plane::is_landing() const
|
||||||
{
|
{
|
||||||
#if HAL_QUADPLANE_ENABLED
|
#if HAL_QUADPLANE_ENABLED
|
||||||
|
if (plane.quadplane.in_vtol_land_descent()) {
|
||||||
return plane.quadplane.in_vtol_land_descent();
|
return true;
|
||||||
|
}
|
||||||
#endif // HAL_QUADPLANE_ENABLED
|
#endif
|
||||||
|
|
||||||
return control_mode->is_landing();
|
return control_mode->is_landing();
|
||||||
}
|
}
|
||||||
|
@ -50,13 +50,7 @@ bool Plane::is_landing() const
|
||||||
// returns true if vehicle is taking off. Only used by Lua scripts
|
// returns true if vehicle is taking off. Only used by Lua scripts
|
||||||
bool Plane::is_taking_off() const
|
bool Plane::is_taking_off() const
|
||||||
{
|
{
|
||||||
#if HAL_QUADPLANE_ENABLED
|
return control_mode->is_taking_off() || (started_flying_ms > 0 && millis() - started_flying_ms < 30000);
|
||||||
|
|
||||||
return plane.quadplane.in_vtol_takeoff();
|
|
||||||
|
|
||||||
#endif // HAL_QUADPLANE_ENABLED
|
|
||||||
|
|
||||||
return control_mode->is_taking_off();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // AP_SCRIPTING_ENABLED
|
#endif // AP_SCRIPTING_ENABLED
|
||||||
|
|
|
@ -168,7 +168,7 @@ bool ModeAuto::is_landing() const
|
||||||
case MAV_CMD_DO_VTOL_TRANSITION:
|
case MAV_CMD_DO_VTOL_TRANSITION:
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
return false;
|
return plane.mission.get_in_landing_sequence_flag();
|
||||||
}
|
}
|
||||||
|
|
||||||
bool ModeAuto::is_taking_off() const
|
bool ModeAuto::is_taking_off() const
|
||||||
|
|
Loading…
Reference in New Issue