Skip to content

Commit

Permalink
ArduPlane: 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 Mar 6, 2024
1 parent c1d2891 commit ead7871
Show file tree
Hide file tree
Showing 10 changed files with 38 additions and 2 deletions.
6 changes: 6 additions & 0 deletions ArduPlane/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,6 +110,7 @@ bool Plane::stick_mixing_enabled(void)
*/
void Plane::stabilize_roll()
{
#if AP_INVERTED_FLIGHT_ENABLED
if (fly_inverted()) {
// we want to fly upside down. We need to cope with wrap of
// the roll_sensor interfering with wrap of nav_roll, which
Expand All @@ -119,6 +120,7 @@ void Plane::stabilize_roll()
nav_roll_cd += 18000;
if (ahrs.roll_sensor < 0) nav_roll_cd -= 36000;
}
#endif

const float roll_out = stabilize_roll_get_roll_out();
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, roll_out);
Expand Down Expand Up @@ -306,9 +308,11 @@ void Plane::stabilize_stick_mixing_fbw()
} else if (pitch_input < -0.5f) {
pitch_input = (3*pitch_input + 1);
}
#if AP_INVERTED_FLIGHT_ENABLED
if (fly_inverted()) {
pitch_input = -pitch_input;
}
#endif
if (pitch_input > 0) {
nav_pitch_cd += pitch_input * aparm.pitch_limit_max*100;
} else {
Expand Down Expand Up @@ -641,10 +645,12 @@ void Plane::update_load_factor(void)
// stall prevention is disabled
return;
}
#if AP_INVERTED_FLIGHT_ENABLED
if (fly_inverted()) {
// no roll limits when inverted
return;
}
#endif
#if HAL_QUADPLANE_ENABLED
if (quadplane.tailsitter.active()) {
// no limits while hovering
Expand Down
4 changes: 4 additions & 0 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -314,8 +314,10 @@ class Plane : public AP_Vehicle {
// This is set to 254 when we need to re-read the switch
uint8_t oldSwitchPosition = 254;

#if AP_INVERTED_FLIGHT_ENABLED
// This is used to enable the inverted flight feature
bool inverted_flight;
#endif

// last time we ran roll/pitch stabilization
uint32_t last_stabilize_ms;
Expand Down Expand Up @@ -489,8 +491,10 @@ class Plane : public AP_Vehicle {
// are we headed to the land approach waypoint? Works for any nav type
bool wp_is_land_approach;

#if AP_INVERTED_FLIGHT_ENABLED
// should we fly inverted?
bool inverted_flight;
#endif

// should we enable cross-tracking for the next waypoint?
bool next_wp_crosstrack;
Expand Down
4 changes: 4 additions & 0 deletions ArduPlane/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -152,7 +152,9 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option,
case AUX_FUNC::TRAINING:
case AUX_FUNC::FLAP:
case AUX_FUNC::GUIDED:
#if AP_INVERTED_FLIGHT_ENABLED
case AUX_FUNC::INVERTED:
#endif
case AUX_FUNC::LOITER:
case AUX_FUNC::MANUAL:
case AUX_FUNC::RTL:
Expand Down Expand Up @@ -215,9 +217,11 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option,
bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag)
{
switch(ch_option) {
#if AP_INVERTED_FLIGHT_ENABLED
case AUX_FUNC::INVERTED:
plane.inverted_flight = (ch_flag == AuxSwitchPos::HIGH);
break;
#endif

case AUX_FUNC::REVERSE_THROTTLE:
plane.reversed_throttle = (ch_flag == AuxSwitchPos::HIGH);
Expand Down
4 changes: 4 additions & 0 deletions ArduPlane/commands_logic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -134,12 +134,14 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
do_set_home(cmd);
break;

#if AP_INVERTED_FLIGHT_ENABLED
case MAV_CMD_DO_INVERTED_FLIGHT:
if (cmd.p1 == 0 || cmd.p1 == 1) {
auto_state.inverted_flight = (bool)cmd.p1;
gcs().send_text(MAV_SEVERITY_INFO, "Set inverted %u", cmd.p1);
}
break;
#endif

case MAV_CMD_DO_LAND_START:
break;
Expand Down Expand Up @@ -319,7 +321,9 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret
// do commands (always return true)
case MAV_CMD_DO_CHANGE_SPEED:
case MAV_CMD_DO_SET_HOME:
#if AP_INVERTED_FLIGHT_ENABLED
case MAV_CMD_DO_INVERTED_FLIGHT:
#endif
case MAV_CMD_DO_LAND_START:
case MAV_CMD_DO_FENCE_ENABLE:
case MAV_CMD_DO_AUTOTUNE_ENABLE:
Expand Down
2 changes: 2 additions & 0 deletions ArduPlane/control_modes.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -169,6 +169,7 @@ void Plane::autotune_enable(bool enable)
}
}

#if AP_INVERTED_FLIGHT_ENABLED
/*
are we flying inverted?
*/
Expand All @@ -186,3 +187,4 @@ bool Plane::fly_inverted(void)
}
return false;
}
#endif
4 changes: 3 additions & 1 deletion ArduPlane/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,11 @@ bool Mode::enter()
plane.nav_scripting.enabled = false;
#endif

#if AP_INVERTED_FLIGHT_ENABLED
// cancel inverted flight
plane.auto_state.inverted_flight = false;

#endif

// cancel waiting for rudder neutral
plane.takeoff_state.waiting_for_rudder_neutral = false;

Expand Down
2 changes: 2 additions & 0 deletions ArduPlane/mode_fbwa.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,11 @@ void ModeFBWA::update()
}
plane.adjust_nav_pitch_throttle();
plane.nav_pitch_cd = constrain_int32(plane.nav_pitch_cd, plane.pitch_limit_min*100, plane.aparm.pitch_limit_max.get()*100);
#if AP_INVERTED_FLIGHT_ENABLED
if (plane.fly_inverted()) {
plane.nav_pitch_cd = -plane.nav_pitch_cd;
}
#endif
if (plane.failsafe.rc_failsafe && plane.g.fs_action_short == FS_ACTION_SHORT_FBWA) {
// FBWA failsafe glide
plane.nav_roll_cd = 0;
Expand Down
2 changes: 2 additions & 0 deletions ArduPlane/mode_training.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,11 @@ void ModeTraining::update()
plane.training_manual_pitch = true;
plane.nav_pitch_cd = 0;
}
#if AP_INVERTED_FLIGHT_ENABLED
if (plane.fly_inverted()) {
plane.nav_pitch_cd = -plane.nav_pitch_cd;
}
#endif
}

/*
Expand Down
6 changes: 6 additions & 0 deletions ArduPlane/tailsitter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -557,9 +557,11 @@ bool Tailsitter::transition_vtol_complete(void) const
return true;
}
int32_t roll_cd = labs(plane.ahrs.roll_sensor);
#if AP_INVERTED_FLIGHT_ENABLED
if (plane.fly_inverted()) {
roll_cd = 18000 - roll_cd;
}
#endif
if (roll_cd > MAX(4500, plane.roll_limit_cd + 500)) {
gcs().send_text(MAV_SEVERITY_WARNING, "Transition VTOL done, roll error");
return true;
Expand Down Expand Up @@ -845,7 +847,11 @@ void Tailsitter_Transition::update()
quadplane.assisted_flight = true;
uint32_t dt = now - fw_transition_start_ms;
// multiply by 0.1 to convert (degrees/second * milliseconds) to centi degrees
#if AP_INVERTED_FLIGHT_ENABLED
plane.nav_pitch_cd = constrain_float(fw_transition_initial_pitch - (quadplane.tailsitter.transition_rate_fw * dt) * 0.1f * (plane.fly_inverted()?-1.0f:1.0f), -8500, 8500);
#else
plane.nav_pitch_cd = constrain_float(fw_transition_initial_pitch - (quadplane.tailsitter.transition_rate_fw * dt) * 0.1f, -8500, 8500);
#endif
plane.nav_roll_cd = 0;
quadplane.disable_yaw_rate_time_constant();
quadplane.attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd,
Expand Down
6 changes: 5 additions & 1 deletion ArduPlane/takeoff.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,11 @@ bool Plane::auto_takeoff_check(void)
if (do_takeoff_attitude_check) {
// Check aircraft attitude for bad launch
if (ahrs.pitch_sensor <= -3000 || ahrs.pitch_sensor >= 4500 ||
(!fly_inverted() && labs(ahrs.roll_sensor) > 3000)) {
(
#if AP_INVERTED_FLIGHT_ENABLED
!fly_inverted() &&
#endif
labs(ahrs.roll_sensor) > 3000)) {
gcs().send_text(MAV_SEVERITY_WARNING, "Bad launch AUTO");
takeoff_state.accel_event_counter = 0;
goto no_launch;
Expand Down

0 comments on commit ead7871

Please sign in to comment.