Skip to content

Commit 50ec24b

Browse files
committed
ArduPlane: add compile-time option to remove inverted-flight capability
1 parent 807bbfe commit 50ec24b

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 {
@@ -652,10 +656,12 @@ void Plane::update_load_factor(void)
652656
// stall prevention is disabled
653657
return;
654658
}
659+
#if AP_INVERTED_FLIGHT_ENABLED
655660
if (fly_inverted()) {
656661
// no roll limits when inverted
657662
return;
658663
}
664+
#endif
659665
#if HAL_QUADPLANE_ENABLED
660666
if (quadplane.tailsitter.active()) {
661667
// no limits while hovering

ArduPlane/Plane.h

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -351,8 +351,10 @@ class Plane : public AP_Vehicle {
351351
// time of last mode change
352352
uint32_t last_mode_change_ms;
353353

354+
#if AP_INVERTED_FLIGHT_ENABLED
354355
// This is used to enable the inverted flight feature
355356
bool inverted_flight;
357+
#endif
356358

357359
// last time we ran roll/pitch stabilization
358360
uint32_t last_stabilize_ms;
@@ -528,8 +530,10 @@ class Plane : public AP_Vehicle {
528530
// are we headed to the land approach waypoint? Works for any nav type
529531
bool wp_is_land_approach;
530532

533+
#if AP_INVERTED_FLIGHT_ENABLED
531534
// should we fly inverted?
532535
bool inverted_flight;
536+
#endif
533537

534538
// should we enable cross-tracking for the next waypoint?
535539
bool next_wp_crosstrack;

ArduPlane/RC_Channel_Plane.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -144,7 +144,9 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option,
144144
case AUX_FUNC::TRAINING:
145145
case AUX_FUNC::FLAP:
146146
case AUX_FUNC::GUIDED:
147+
#if AP_INVERTED_FLIGHT_ENABLED
147148
case AUX_FUNC::INVERTED:
149+
#endif
148150
case AUX_FUNC::LOITER:
149151
case AUX_FUNC::MANUAL:
150152
case AUX_FUNC::RTL:
@@ -227,9 +229,11 @@ bool RC_Channel_Plane::do_aux_function(const AuxFuncTrigger &trigger)
227229
const AuxSwitchPos &ch_flag = trigger.pos;
228230

229231
switch(ch_option) {
232+
#if AP_INVERTED_FLIGHT_ENABLED
230233
case AUX_FUNC::INVERTED:
231234
plane.inverted_flight = (ch_flag == AuxSwitchPos::HIGH);
232235
break;
236+
#endif
233237

234238
case AUX_FUNC::REVERSE_THROTTLE:
235239
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_RETURN_PATH_START:
145147
case MAV_CMD_DO_LAND_START:
@@ -308,7 +310,9 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret
308310
// do commands (always return true)
309311
case MAV_CMD_DO_CHANGE_SPEED:
310312
case MAV_CMD_DO_SET_HOME:
313+
#if AP_INVERTED_FLIGHT_ENABLED
311314
case MAV_CMD_DO_INVERTED_FLIGHT:
315+
#endif
312316
case MAV_CMD_DO_RETURN_PATH_START:
313317
case MAV_CMD_DO_LAND_START:
314318
case MAV_CMD_DO_FENCE_ENABLE:

ArduPlane/control_modes.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -174,6 +174,7 @@ void Plane::autotune_enable(bool enable)
174174
}
175175
}
176176

177+
#if AP_INVERTED_FLIGHT_ENABLED
177178
/*
178179
are we flying inverted?
179180
*/
@@ -191,3 +192,4 @@ bool Plane::fly_inverted(void)
191192
}
192193
return false;
193194
}
195+
#endif

ArduPlane/mode.cpp

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

34+
#if AP_INVERTED_FLIGHT_ENABLED
3435
// cancel inverted flight
3536
plane.auto_state.inverted_flight = false;
36-
37+
#endif
38+
3739
// cancel waiting for rudder neutral
3840
plane.takeoff_state.waiting_for_rudder_neutral = false;
3941

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
@@ -571,9 +571,11 @@ bool Tailsitter::transition_vtol_complete(void) const
571571
return true;
572572
}
573573
int32_t roll_cd = labs(plane.ahrs.roll_sensor);
574+
#if AP_INVERTED_FLIGHT_ENABLED
574575
if (plane.fly_inverted()) {
575576
roll_cd = 18000 - roll_cd;
576577
}
578+
#endif
577579
if (roll_cd > MAX(4500, plane.roll_limit_cd + 500)) {
578580
gcs().send_text(MAV_SEVERITY_WARNING, "Transition VTOL done, roll error");
579581
return true;
@@ -859,7 +861,11 @@ void Tailsitter_Transition::update()
859861
quadplane.assisted_flight = true;
860862
uint32_t dt = now - fw_transition_start_ms;
861863
// multiply by 0.1 to convert (degrees/second * milliseconds) to centi degrees
864+
#if AP_INVERTED_FLIGHT_ENABLED
862865
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);
866+
#else
867+
plane.nav_pitch_cd = constrain_float(fw_transition_initial_pitch - (quadplane.tailsitter.transition_rate_fw * dt) * 0.1f, -8500, 8500);
868+
#endif
863869
plane.nav_roll_cd = 0;
864870
quadplane.disable_yaw_rate_time_constant();
865871
quadplane.attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_cd(plane.nav_roll_cd,

ArduPlane/takeoff.cpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -114,7 +114,11 @@ bool Plane::auto_takeoff_check(void)
114114
if (do_takeoff_attitude_check) {
115115
// Check aircraft attitude for bad launch
116116
if (ahrs.pitch_sensor <= -3000 || ahrs.pitch_sensor >= 4500 ||
117-
(!fly_inverted() && labs(ahrs.roll_sensor) > 3000)) {
117+
(
118+
#if AP_INVERTED_FLIGHT_ENABLED
119+
!fly_inverted() &&
120+
#endif
121+
labs(ahrs.roll_sensor) > 3000)) {
118122
gcs().send_text(MAV_SEVERITY_WARNING, "Bad launch AUTO");
119123
takeoff_state.accel_event_counter = 0;
120124
goto no_launch;

0 commit comments

Comments
 (0)