mirror of https://github.com/ArduPilot/ardupilot
Copter: Heli: ensure inverted flight only in supported modes
This commit is contained in:
parent
576ee75669
commit
52bffc4b4d
|
@ -421,7 +421,11 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
|
|||
#if FRAME_CONFIG == HELI_FRAME
|
||||
switch (ch_flag) {
|
||||
case AuxSwitchPos::HIGH:
|
||||
copter.attitude_control->set_inverted_flight(true);
|
||||
if (copter.flightmode->allows_inverted()) {
|
||||
copter.attitude_control->set_inverted_flight(true);
|
||||
} else {
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "Inverted flight not available in %s mode", copter.flightmode->name());
|
||||
}
|
||||
break;
|
||||
case AuxSwitchPos::MIDDLE:
|
||||
// nothing
|
||||
|
|
|
@ -457,6 +457,11 @@ void Copter::exit_mode(Mode *&old_flightmode,
|
|||
input_manager.set_stab_col_ramp(0.0);
|
||||
}
|
||||
}
|
||||
|
||||
// Make sure inverted flight is disabled if not supported in the new mode
|
||||
if (!new_flightmode->allows_inverted()) {
|
||||
attitude_control->set_inverted_flight(false);
|
||||
}
|
||||
#endif //HELI_FRAME
|
||||
}
|
||||
|
||||
|
|
|
@ -128,6 +128,10 @@ public:
|
|||
virtual bool allows_autotune() const { return false; }
|
||||
virtual bool allows_flip() const { return false; }
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
virtual bool allows_inverted() const { return false; };
|
||||
#endif
|
||||
|
||||
// return a string for this flightmode
|
||||
virtual const char *name() const = 0;
|
||||
virtual const char *name4() const = 0;
|
||||
|
@ -1574,6 +1578,8 @@ public:
|
|||
bool init(bool ignore_checks) override;
|
||||
void run() override;
|
||||
|
||||
bool allows_inverted() const override { return true; };
|
||||
|
||||
protected:
|
||||
|
||||
private:
|
||||
|
|
Loading…
Reference in New Issue