Plane: use pure-virtual method for allows_throttle_nudging

In place of a state variable which could become stale
This commit is contained in:
Peter Barker 2020-12-23 11:47:58 +11:00 committed by Peter Barker
parent 882d9c4e23
commit a1ea1306a1
21 changed files with 18 additions and 22 deletions

View File

@ -579,9 +579,6 @@ private:
// true if we are in an auto-navigation mode, which controls whether control input is ignored
// with STICK_MIXING=0
bool auto_navigation_mode:1;
// this allows certain flight modes to mix RC input with throttle depending on airspeed_nudge_cm
bool throttle_allows_nudging:1;
// this controls throttle suppression in auto modes
bool throttle_suppressed;

View File

@ -83,6 +83,10 @@ public:
// subclasses override this if they require navigation.
virtual void navigate() { return; }
// this allows certain flight modes to mix RC input with throttle
// depending on airspeed_nudge_cm
virtual bool allows_throttle_nudging() const { return false; }
protected:
// subclasses override this to perform checks before entering the mode
@ -122,6 +126,8 @@ public:
void navigate() override;
bool allows_throttle_nudging() const override { return true; }
protected:
bool _enter() override;
@ -161,6 +167,8 @@ public:
virtual bool is_guided_mode() const override { return true; }
bool allows_throttle_nudging() const override { return true; }
protected:
bool _enter() override;
@ -234,6 +242,8 @@ public:
void navigate() override;
bool allows_throttle_nudging() const override { return true; }
protected:
bool _enter() override;
@ -282,6 +292,8 @@ public:
// methods that affect movement of the vehicle in this mode
void update() override { }
bool allows_throttle_nudging() const override { return true; }
protected:
bool _enter() override;
@ -381,6 +393,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; }
bool allows_throttle_nudging() const override { return true; }
// methods that affect movement of the vehicle in this mode
void update() override;
@ -521,6 +534,8 @@ public:
void navigate() override;
bool allows_throttle_nudging() const override { return true; }
// var_info for holding parameter information
static const struct AP_Param::GroupInfo var_info[];
@ -554,6 +569,8 @@ public:
void navigate() override;
bool allows_throttle_nudging() const override { return true; }
protected:
bool exit_heading_aligned() const;

View File

@ -3,7 +3,6 @@
bool ModeAcro::_enter()
{
plane.throttle_allows_nudging = false;
plane.auto_throttle_mode = false;
plane.auto_navigation_mode = false;
plane.acro_state.locked_roll = false;

View File

@ -3,7 +3,6 @@
bool ModeAuto::_enter()
{
plane.throttle_allows_nudging = true;
plane.auto_throttle_mode = true;
plane.auto_navigation_mode = true;
if (plane.quadplane.available() && plane.quadplane.enable == 2) {

View File

@ -3,7 +3,6 @@
bool ModeAutoTune::_enter()
{
plane.throttle_allows_nudging = false;
plane.auto_throttle_mode = false;
plane.auto_navigation_mode = false;
plane.autotune_start();

View File

@ -4,7 +4,6 @@
bool ModeCircle::_enter()
{
// the altitude to circle at is taken from the current altitude
plane.throttle_allows_nudging = false;
plane.auto_throttle_mode = true;
plane.auto_navigation_mode = true;
plane.next_WP_loc.alt = plane.current_loc.alt;

View File

@ -3,7 +3,6 @@
bool ModeCruise::_enter()
{
plane.throttle_allows_nudging = false;
plane.auto_throttle_mode = true;
plane.auto_navigation_mode = false;
locked_heading = false;

View File

@ -3,7 +3,6 @@
bool ModeFBWA::_enter()
{
plane.throttle_allows_nudging = false;
plane.auto_throttle_mode = false;
plane.auto_navigation_mode = false;

View File

@ -3,7 +3,6 @@
bool ModeFBWB::_enter()
{
plane.throttle_allows_nudging = false;
plane.auto_throttle_mode = true;
plane.auto_navigation_mode = false;

View File

@ -3,7 +3,6 @@
bool ModeGuided::_enter()
{
plane.throttle_allows_nudging = true;
plane.auto_throttle_mode = true;
plane.auto_navigation_mode = true;
plane.guided_throttle_passthru = false;

View File

@ -3,7 +3,6 @@
bool ModeInitializing::_enter()
{
plane.throttle_allows_nudging = true;
plane.auto_throttle_mode = true;
plane.auto_navigation_mode = false;

View File

@ -3,7 +3,6 @@
bool ModeLoiter::_enter()
{
plane.throttle_allows_nudging = true;
plane.auto_throttle_mode = true;
plane.auto_navigation_mode = true;
plane.do_loiter_at_location();

View File

@ -3,7 +3,6 @@
bool ModeManual::_enter()
{
plane.throttle_allows_nudging = false;
plane.auto_throttle_mode = false;
plane.auto_navigation_mode = false;

View File

@ -3,7 +3,6 @@
bool ModeQAcro::_enter()
{
plane.throttle_allows_nudging = false;
plane.auto_navigation_mode = false;
if (!plane.quadplane.init_mode() && plane.previous_mode != nullptr) {
plane.control_mode = plane.previous_mode;

View File

@ -3,7 +3,6 @@
bool ModeQStabilize::_enter()
{
plane.throttle_allows_nudging = true;
plane.auto_navigation_mode = false;
if (!plane.quadplane.init_mode() && plane.previous_mode != nullptr) {
plane.control_mode = plane.previous_mode;

View File

@ -3,7 +3,6 @@
bool ModeRTL::_enter()
{
plane.throttle_allows_nudging = true;
plane.auto_throttle_mode = true;
plane.auto_navigation_mode = true;
plane.prev_WP_loc = plane.current_loc;

View File

@ -3,7 +3,6 @@
bool ModeStabilize::_enter()
{
plane.throttle_allows_nudging = false;
plane.auto_throttle_mode = false;
plane.auto_navigation_mode = false;

View File

@ -52,7 +52,6 @@ ModeTakeoff::ModeTakeoff()
bool ModeTakeoff::_enter()
{
// the altitude to circle at is taken from the current altitude
plane.throttle_allows_nudging = true;
plane.auto_throttle_mode = true;
plane.auto_navigation_mode = true;

View File

@ -9,7 +9,6 @@ bool ModeThermal::_enter()
return false;
}
plane.throttle_allows_nudging = true;
plane.auto_throttle_mode = true;
plane.auto_navigation_mode = true;
plane.do_loiter_at_location();

View File

@ -3,7 +3,6 @@
bool ModeTraining::_enter()
{
plane.throttle_allows_nudging = false;
plane.auto_throttle_mode = false;
plane.auto_navigation_mode = false;

View File

@ -221,7 +221,7 @@ void Plane::calc_airspeed_errors()
#endif
// Bump up the target airspeed based on throttle nudging
if (throttle_allows_nudging && airspeed_nudge_cm > 0) {
if (control_mode->allows_throttle_nudging() && airspeed_nudge_cm > 0) {
target_airspeed_cm += airspeed_nudge_cm;
}