Skip to content

Commit

Permalink
ArduCopter: add compile-time option to remove inverted-flight capability
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Apr 3, 2024
1 parent 3d4466c commit 93f8a23
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 2 deletions.
6 changes: 5 additions & 1 deletion ArduCopter/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,9 @@ void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwi
case AUX_FUNC::ACRO_TRAINER:
case AUX_FUNC::ATTCON_ACCEL_LIM:
case AUX_FUNC::ATTCON_FEEDFWD:
#if AP_INVERTED_FLIGHT_ENABLED
case AUX_FUNC::INVERTED:
#endif
case AUX_FUNC::MOTOR_INTERLOCK:
case AUX_FUNC::PARACHUTE_3POS: // we trust the vehicle will be disarmed so even if switch is in release position the chute will not release
case AUX_FUNC::PARACHUTE_ENABLE:
Expand Down Expand Up @@ -417,6 +419,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
#endif
break;

#if AP_INVERTED_FLIGHT_ENABLED
case AUX_FUNC::INVERTED:
#if FRAME_CONFIG == HELI_FRAME
switch (ch_flag) {
Expand All @@ -434,8 +437,9 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
copter.attitude_control->set_inverted_flight(false);
break;
}
#endif
#endif // FRAME_CONFIG == HELI_FRAME
break;
#endif // AP_INVERTED_FLIGHT_ENABLED

case AUX_FUNC::WINCH_ENABLE:
#if AP_WINCH_ENABLED
Expand Down
2 changes: 2 additions & 0 deletions ArduCopter/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -458,10 +458,12 @@ void Copter::exit_mode(Mode *&old_flightmode,
}
}

#if AP_INVERTED_FLIGHT_ENABLED
// 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
#endif //HELI_FRAME
}

Expand Down
4 changes: 3 additions & 1 deletion ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,7 @@ class Mode {
virtual bool allows_autotune() const { return false; }
virtual bool allows_flip() const { return false; }

#if FRAME_CONFIG == HELI_FRAME
#if FRAME_CONFIG == HELI_FRAME && AP_INVERTED_FLIGHT_ENABLED
virtual bool allows_inverted() const { return false; };
#endif

Expand Down Expand Up @@ -1581,7 +1581,9 @@ class ModeStabilize_Heli : public ModeStabilize {
bool init(bool ignore_checks) override;
void run() override;

#if AP_INVERTED_FLIGHT_ENABLED
bool allows_inverted() const override { return true; };
#endif

protected:

Expand Down

0 comments on commit 93f8a23

Please sign in to comment.