Copter: add allows_save_trim function to Mode class

This commit is contained in:
Tatsuya Yamaguchi 2021-02-07 13:58:50 +09:00 committed by Peter Barker
parent 0cce5699b2
commit 2b89ac625f
2 changed files with 4 additions and 1 deletions

View File

@ -201,7 +201,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi
case AUX_FUNC::SAVE_TRIM:
if ((ch_flag == AuxSwitchPos::HIGH) &&
(copter.flightmode->mode_number() <= Mode::Number::ACRO) &&
(copter.flightmode->allows_save_trim()) &&
(copter.channel_throttle->get_control_in() == 0)) {
copter.save_trim();
}

View File

@ -60,6 +60,7 @@ public:
virtual bool has_user_takeoff(bool must_navigate) const { return false; }
virtual bool in_guided_mode() const { return false; }
virtual bool logs_attitude() const { return false; }
virtual bool allows_save_trim() const { return false; }
// return a string for this flightmode
virtual const char *name() const = 0;
@ -275,6 +276,7 @@ public:
void exit();
// whether an air-mode aux switch has been toggled
void air_mode_aux_changed();
bool allows_save_trim() const override { return true; }
protected:
@ -1236,6 +1238,7 @@ public:
bool has_manual_throttle() const override { return true; }
bool allows_arming(bool from_gcs) const override { return true; };
bool is_autopilot() const override { return false; }
bool allows_save_trim() const override { return true; }
protected: