Copter: Heli: remove duplicate inverted flight state

This commit is contained in:
Iampete1 2024-02-29 23:29:00 +00:00 committed by Randy Mackay
parent 1bf7792fe5
commit 73760ea393
2 changed files with 2 additions and 7 deletions

View File

@ -580,9 +580,8 @@ private:
// Tradheli flags
typedef struct {
uint8_t dynamic_flight : 1; // 0 // true if we are moving at a significant speed (used to turn on/off leaky I terms)
uint8_t inverted_flight : 1; // 1 // true for inverted flight mode
uint8_t in_autorotation : 1; // 2 // true when heli is in autorotation
bool coll_stk_low ; // 3 // true when collective stick is on lower limit
uint8_t in_autorotation : 1; // 1 // true when heli is in autorotation
bool coll_stk_low ; // 2 // true when collective stick is on lower limit
} heli_flags_t;
heli_flags_t heli_flags;

View File

@ -421,17 +421,13 @@ 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.motors->set_inverted_flight(true);
copter.attitude_control->set_inverted_flight(true);
copter.heli_flags.inverted_flight = true;
break;
case AuxSwitchPos::MIDDLE:
// nothing
break;
case AuxSwitchPos::LOW:
copter.motors->set_inverted_flight(false);
copter.attitude_control->set_inverted_flight(false);
copter.heli_flags.inverted_flight = false;
break;
}
#endif