mirror of https://github.com/ArduPilot/ardupilot
Plane: add Mode::is_vtol_man_mode
and make use of is_vtol_mode in in_vtol_mode
This commit is contained in:
parent
b9830f657a
commit
4630e9af30
|
@ -69,6 +69,7 @@ public:
|
|||
// true for all q modes
|
||||
virtual bool is_vtol_mode() const { return false; }
|
||||
virtual bool is_vtol_man_throttle() const { return false; }
|
||||
virtual bool is_vtol_man_mode() const { return false; }
|
||||
|
||||
// true if mode can have terrain following disabled by switch
|
||||
virtual bool allows_terrain_disable() const { return false; }
|
||||
|
@ -346,6 +347,7 @@ public:
|
|||
|
||||
bool is_vtol_mode() const override { return true; }
|
||||
bool is_vtol_man_throttle() const override { return true; }
|
||||
virtual bool is_vtol_man_mode() const override { return true; }
|
||||
|
||||
// methods that affect movement of the vehicle in this mode
|
||||
void update() override;
|
||||
|
@ -366,6 +368,7 @@ public:
|
|||
const char *name4() const override { return "QHOV"; }
|
||||
|
||||
bool is_vtol_mode() const override { return true; }
|
||||
virtual bool is_vtol_man_mode() const override { return true; }
|
||||
|
||||
// methods that affect movement of the vehicle in this mode
|
||||
void update() override;
|
||||
|
@ -384,6 +387,7 @@ public:
|
|||
const char *name4() const override { return "QLOT"; }
|
||||
|
||||
bool is_vtol_mode() const override { return true; }
|
||||
virtual bool is_vtol_man_mode() const override { return true; }
|
||||
|
||||
// methods that affect movement of the vehicle in this mode
|
||||
void update() override;
|
||||
|
@ -457,6 +461,7 @@ public:
|
|||
const char *name4() const override { return "QATN"; }
|
||||
|
||||
bool is_vtol_mode() const override { return true; }
|
||||
virtual bool is_vtol_man_mode() const override { return true; }
|
||||
|
||||
// methods that affect movement of the vehicle in this mode
|
||||
void update() override;
|
||||
|
|
|
@ -1227,7 +1227,7 @@ bool QuadPlane::is_flying_vtol(void) const
|
|||
if (plane.control_mode == &plane.mode_guided && guided_takeoff) {
|
||||
return true;
|
||||
}
|
||||
if (plane.control_mode == &plane.mode_qstabilize || plane.control_mode == &plane.mode_qhover || plane.control_mode == &plane.mode_qloiter || plane.control_mode == &plane.mode_qautotune) {
|
||||
if (plane.control_mode->is_vtol_man_mode()) {
|
||||
// in manual flight modes only consider aircraft landed when pilot demanded throttle is zero
|
||||
return plane.get_throttle_input() > 0;
|
||||
}
|
||||
|
@ -2227,13 +2227,7 @@ bool QuadPlane::in_vtol_mode(void) const
|
|||
if (!available()) {
|
||||
return false;
|
||||
}
|
||||
return (plane.control_mode == &plane.mode_qstabilize ||
|
||||
plane.control_mode == &plane.mode_qhover ||
|
||||
plane.control_mode == &plane.mode_qloiter ||
|
||||
plane.control_mode == &plane.mode_qland ||
|
||||
plane.control_mode == &plane.mode_qrtl ||
|
||||
plane.control_mode == &plane.mode_qacro ||
|
||||
plane.control_mode == &plane.mode_qautotune ||
|
||||
return (plane.control_mode->is_vtol_mode() ||
|
||||
((plane.control_mode == &plane.mode_guided || plane.control_mode == &plane.mode_avoidADSB) && plane.auto_state.vtol_loiter) ||
|
||||
in_vtol_auto());
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue