Skip to content

Commit a33c31c

Browse files
committed
ArduPlane: add compile-time option to remove inverted-flight capability
1 parent 91ea452 commit a33c31c

10 files changed

+38
-2
lines changed

ArduPlane/Attitude.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -110,6 +110,7 @@ bool Plane::stick_mixing_enabled(void)
110110
*/
111111
void Plane::stabilize_roll()
112112
{
113+
#if AP_INVERTED_FLIGHT_ENABLED
113114
if (fly_inverted()) {
114115
// we want to fly upside down. We need to cope with wrap of
115116
// the roll_sensor interfering with wrap of nav_roll, which
@@ -119,6 +120,7 @@ void Plane::stabilize_roll()
119120
nav_roll_cd += 18000;
120121
if (ahrs.roll_sensor < 0) nav_roll_cd -= 36000;
121122
}
123+
#endif
122124

123125
const float roll_out = stabilize_roll_get_roll_out();
124126
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, roll_out);
@@ -306,9 +308,11 @@ void Plane::stabilize_stick_mixing_fbw()
306308
} else if (pitch_input < -0.5f) {
307309
pitch_input = (3*pitch_input + 1);
308310
}
311+
#if AP_INVERTED_FLIGHT_ENABLED
309312
if (fly_inverted()) {
310313
pitch_input = -pitch_input;
311314
}
315+
#endif
312316
if (pitch_input > 0) {
313317
nav_pitch_cd += pitch_input * aparm.pitch_limit_max*100;
314318
} else {
@@ -641,10 +645,12 @@ void Plane::update_load_factor(void)
641645
// stall prevention is disabled
642646
return;
643647
}
648+
#if AP_INVERTED_FLIGHT_ENABLED
644649
if (fly_inverted()) {
645650
// no roll limits when inverted
646651
return;
647652
}
653+
#endif
648654
#if HAL_QUADPLANE_ENABLED
649655
if (quadplane.tailsitter.active()) {
650656
// no limits while hovering

ArduPlane/Plane.h

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -314,8 +314,10 @@ class Plane : public AP_Vehicle {
314314
// This is set to 254 when we need to re-read the switch
315315
uint8_t oldSwitchPosition = 254;
316316

317+
#if AP_INVERTED_FLIGHT_ENABLED
317318
// This is used to enable the inverted flight feature
318319
bool inverted_flight;
320+
#endif
319321

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

494+
#if AP_INVERTED_FLIGHT_ENABLED
492495
// should we fly inverted?
493496
bool inverted_flight;
497+
#endif
494498

495499
// should we enable cross-tracking for the next waypoint?
496500
bool next_wp_crosstrack;

ArduPlane/RC_Channel.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -152,7 +152,9 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option,
152152
case AUX_FUNC::TRAINING:
153153
case AUX_FUNC::FLAP:
154154
case AUX_FUNC::GUIDED:
155+
#if AP_INVERTED_FLIGHT_ENABLED
155156
case AUX_FUNC::INVERTED:
157+
#endif
156158
case AUX_FUNC::LOITER:
157159
case AUX_FUNC::MANUAL:
158160
case AUX_FUNC::RTL:
@@ -216,9 +218,11 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option,
216218
bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag)
217219
{
218220
switch(ch_option) {
221+
#if AP_INVERTED_FLIGHT_ENABLED
219222
case AUX_FUNC::INVERTED:
220223
plane.inverted_flight = (ch_flag == AuxSwitchPos::HIGH);
221224
break;
225+
#endif
222226

223227
case AUX_FUNC::REVERSE_THROTTLE:
224228
plane.reversed_throttle = (ch_flag == AuxSwitchPos::HIGH);

ArduPlane/commands_logic.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -134,12 +134,14 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
134134
do_set_home(cmd);
135135
break;
136136

137+
#if AP_INVERTED_FLIGHT_ENABLED
137138
case MAV_CMD_DO_INVERTED_FLIGHT:
138139
if (cmd.p1 == 0 || cmd.p1 == 1) {
139140
auto_state.inverted_flight = (bool)cmd.p1;
140141
gcs().send_text(MAV_SEVERITY_INFO, "Set inverted %u", cmd.p1);
141142
}
142143
break;
144+
#endif
143145

144146
case MAV_CMD_DO_LAND_START:
145147
break;
@@ -319,7 +321,9 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret
319321
// do commands (always return true)
320322
case MAV_CMD_DO_CHANGE_SPEED:
321323
case MAV_CMD_DO_SET_HOME:
324+
#if AP_INVERTED_FLIGHT_ENABLED
322325
case MAV_CMD_DO_INVERTED_FLIGHT:
326+
#endif
323327
case MAV_CMD_DO_LAND_START:
324328
case MAV_CMD_DO_FENCE_ENABLE:
325329
case MAV_CMD_DO_AUTOTUNE_ENABLE:

ArduPlane/control_modes.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -169,6 +169,7 @@ void Plane::autotune_enable(bool enable)
169169
}
170170
}
171171

172+
#if AP_INVERTED_FLIGHT_ENABLED
172173
/*
173174
are we flying inverted?
174175
*/
@@ -186,3 +187,4 @@ bool Plane::fly_inverted(void)
186187
}
187188
return false;
188189
}
190+
#endif

ArduPlane/mode.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,9 +30,11 @@ bool Mode::enter()
3030
plane.nav_scripting.enabled = false;
3131
#endif
3232

33+
#if AP_INVERTED_FLIGHT_ENABLED
3334
// cancel inverted flight
3435
plane.auto_state.inverted_flight = false;
35-
36+
#endif
37+
3638
// cancel waiting for rudder neutral
3739
plane.takeoff_state.waiting_for_rudder_neutral = false;
3840

ArduPlane/mode_fbwa.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,9 +14,11 @@ void ModeFBWA::update()
1414
}
1515
plane.adjust_nav_pitch_throttle();
1616
plane.nav_pitch_cd = constrain_int32(plane.nav_pitch_cd, plane.pitch_limit_min*100, plane.aparm.pitch_limit_max.get()*100);
17+
#if AP_INVERTED_FLIGHT_ENABLED
1718
if (plane.fly_inverted()) {
1819
plane.nav_pitch_cd = -plane.nav_pitch_cd;
1920
}
21+
#endif
2022
if (plane.failsafe.rc_failsafe && plane.g.fs_action_short == FS_ACTION_SHORT_FBWA) {
2123
// FBWA failsafe glide
2224
plane.nav_roll_cd = 0;

ArduPlane/mode_training.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,9 +28,11 @@ void ModeTraining::update()
2828
plane.training_manual_pitch = true;
2929
plane.nav_pitch_cd = 0;
3030
}
31+
#if AP_INVERTED_FLIGHT_ENABLED
3132
if (plane.fly_inverted()) {
3233
plane.nav_pitch_cd = -plane.nav_pitch_cd;
3334
}
35+
#endif
3436
}
3537

3638
/*

ArduPlane/tailsitter.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -557,9 +557,11 @@ bool Tailsitter::transition_vtol_complete(void) const
557557
return true;
558558
}
559559
int32_t roll_cd = labs(plane.ahrs.roll_sensor);
560+
#if AP_INVERTED_FLIGHT_ENABLED
560561
if (plane.fly_inverted()) {
561562
roll_cd = 18000 - roll_cd;
562563
}
564+
#endif
563565
if (roll_cd > MAX(4500, plane.roll_limit_cd + 500)) {
564566
gcs().send_text(MAV_SEVERITY_WARNING, "Transition VTOL done, roll error");
565567
return true;
@@ -845,7 +847,11 @@ void Tailsitter_Transition::update()
845847
quadplane.assisted_flight = true;
846848
uint32_t dt = now - fw_transition_start_ms;
847849
// multiply by 0.1 to convert (degrees/second * milliseconds) to centi degrees
850+
#if AP_INVERTED_FLIGHT_ENABLED
848851
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);
852+
#else
853+
plane.nav_pitch_cd = constrain_float(fw_transition_initial_pitch - (quadplane.tailsitter.transition_rate_fw * dt) * 0.1f, -8500, 8500);
854+
#endif
849855
plane.nav_roll_cd = 0;
850856
quadplane.disable_yaw_rate_time_constant();
851857
quadplane.attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd,

ArduPlane/takeoff.cpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -107,7 +107,11 @@ bool Plane::auto_takeoff_check(void)
107107
if (do_takeoff_attitude_check) {
108108
// Check aircraft attitude for bad launch
109109
if (ahrs.pitch_sensor <= -3000 || ahrs.pitch_sensor >= 4500 ||
110-
(!fly_inverted() && labs(ahrs.roll_sensor) > 3000)) {
110+
(
111+
#if AP_INVERTED_FLIGHT_ENABLED
112+
!fly_inverted() &&
113+
#endif
114+
labs(ahrs.roll_sensor) > 3000)) {
111115
gcs().send_text(MAV_SEVERITY_WARNING, "Bad launch AUTO");
112116
takeoff_state.accel_event_counter = 0;
113117
goto no_launch;

0 commit comments

Comments
 (0)