Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: add climb-before-turn on RTL #16823

Merged
merged 1 commit into from
Mar 16, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -503,7 +503,7 @@ void Plane::update_alt()

float target_alt = relative_target_altitude_cm();

if (control_mode == &mode_rtl && !rtl.done_climb && g2.rtl_climb_min > 0) {
if (control_mode == &mode_rtl && !rtl.done_climb && (g2.rtl_climb_min > 0 || (plane.g2.flight_options & FlightOptions::CLIMB_BEFORE_TURN))) {
// ensure we do the initial climb in RTL. We add an extra
// 10m in the demanded height to push TECS to climb
// quickly
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1143,7 +1143,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Param: FLIGHT_OPTIONS
// @DisplayName: Flight mode options
// @Description: Flight mode specific options
// @Bitmask: 0:Rudder mixing in direct flight modes only (Manual / Stabilize / Acro),1:Use centered throttle in Cruise or FBWB to indicate trim airspeed, 2:Disable attitude check for takeoff arming, 3:Force target airspeed to trim airspeed in Cruise or FBWB
// @Bitmask: 0:Rudder mixing in direct flight modes only (Manual / Stabilize / Acro),1:Use centered throttle in Cruise or FBWB to indicate trim airspeed, 2:Disable attitude check for takeoff arming, 3:Force target airspeed to trim airspeed in Cruise or FBWB, 4: Climb to ALT_HOLD_RTL before turning for RTL.
// @User: Advanced
AP_GROUPINFO("FLIGHT_OPTIONS", 13, ParametersG2, flight_options, 0),

Expand Down
1 change: 1 addition & 0 deletions ArduPlane/defines.h
Original file line number Diff line number Diff line change
Expand Up @@ -152,6 +152,7 @@ enum FlightOptions {
CRUISE_TRIM_THROTTLE = (1 << 1),
DISABLE_TOFF_ATTITUDE_CHK = (1 << 2),
CRUISE_TRIM_AIRSPEED = (1 << 3),
CLIMB_BEFORE_TURN = (1 << 4),
};

enum CrowFlapOptions {
Expand Down
37 changes: 24 additions & 13 deletions ArduPlane/mode_rtl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,20 +19,31 @@ void ModeRTL::update()
plane.calc_nav_pitch();
plane.calc_throttle();

if (plane.g2.rtl_climb_min > 0) {
bool alt_threshold_reached = false;
if (plane.g2.flight_options & FlightOptions::CLIMB_BEFORE_TURN) {
magicrub marked this conversation as resolved.
Show resolved Hide resolved
// Climb to ALT_HOLD_RTL before turning. This overrides RTL_CLIMB_MIN.
alt_threshold_reached = plane.current_loc.alt > plane.next_WP_loc.alt;
} else if (plane.g2.rtl_climb_min > 0) {
/*
when RTL first starts limit bank angle to LEVEL_ROLL_LIMIT
until we have climbed by RTL_CLIMB_MIN meters
*/
if (!plane.rtl.done_climb && (plane.current_loc.alt - plane.prev_WP_loc.alt)*0.01 > plane.g2.rtl_climb_min) {
plane.prev_WP_loc = plane.current_loc;
plane.setup_glide_slope();
plane.rtl.done_climb = true;
}
if (!plane.rtl.done_climb) {
plane.roll_limit_cd = MIN(plane.roll_limit_cd, plane.g.level_roll_limit*100);
plane.nav_roll_cd = constrain_int32(plane.nav_roll_cd, -plane.roll_limit_cd, plane.roll_limit_cd);
}
when RTL first starts limit bank angle to LEVEL_ROLL_LIMIT
until we have climbed by RTL_CLIMB_MIN meters
*/
alt_threshold_reached = (plane.current_loc.alt - plane.prev_WP_loc.alt)*0.01 > plane.g2.rtl_climb_min;
} else {
return;
}

if (!plane.rtl.done_climb && alt_threshold_reached) {
plane.prev_WP_loc = plane.current_loc;
plane.setup_glide_slope();
plane.rtl.done_climb = true;
}
if (!plane.rtl.done_climb) {
// Constrain the roll limit as a failsafe, that way if something goes wrong the plane will
// eventually turn back and go to RTL instead of going perfectly straight. This also leaves
// some leeway for fighting wind.
plane.roll_limit_cd = MIN(plane.roll_limit_cd, plane.g.level_roll_limit*100);
plane.nav_roll_cd = constrain_int32(plane.nav_roll_cd, -plane.roll_limit_cd, plane.roll_limit_cd);
}
}

Expand Down
13 changes: 13 additions & 0 deletions Tools/autotest/ArduPlane_Tests/ClimbBeforeTurn/flaps.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
QGC WPL 110
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 584.390015 1
1 0 3 22 15.000000 0.000000 0.000000 0.000000 -35.361279 149.164230 30.000000 1
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361229 149.163025 80.000000 1
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364563 149.163773 80.000000 1
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364384 149.164795 80.000000 1
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361027 149.164093 80.000000 1
6 0 0 177 2.000000 3.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
7 0 3 189 0.000000 0.000000 0.000000 0.000000 -35.362915 149.162613 60.000000 1
8 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363136 149.162750 60.000000 1
9 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365467 149.164215 55.000000 1
10 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365009 149.165482 39.889999 1
11 0 3 21 0.000000 0.000000 0.000000 1.000000 -35.363041 149.165222 0.000000 1
55 changes: 55 additions & 0 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -1594,6 +1594,57 @@ def deadreckoning(self):
def deadreckoning_no_airspeed_sensor(self):
self.deadreckoning_main(disable_airspeed_sensor=True)

def climb_before_turn(self):
self.wait_ready_to_arm()
self.set_parameter("FLIGHT_OPTIONS", 0)
self.set_parameter("ALT_HOLD_RTL", 8000)
takeoff_alt = 40
self.takeoff(alt=takeoff_alt)
self.change_mode("CRUISE")
self.wait_distance_to_home(500, 1000, timeout=60)
self.change_mode("RTL")
expected_alt = self.get_parameter("ALT_HOLD_RTL") / 100.0

home = self.home_position_as_mav_location()
distance = self.get_distance(home, self.mav.location())

self.wait_altitude(expected_alt - 10, expected_alt + 10, relative=True)

new_distance = self.get_distance(home, self.mav.location())
# We should be closer to home.
if new_distance > distance:
raise NotAchievedException(
"Expected to be closer to home (was %fm, now %fm)."
% (distance, new_distance)
)

self.fly_home_land_and_disarm()
self.change_mode("MANUAL")
self.set_rc(3, 1000)

self.wait_ready_to_arm()
self.set_parameter("FLIGHT_OPTIONS", 16)
self.set_parameter("ALT_HOLD_RTL", 10000)
self.takeoff(alt=takeoff_alt)
self.change_mode("CRUISE")
self.wait_distance_to_home(500, 1000, timeout=60)
self.change_mode("RTL")

home = self.home_position_as_mav_location()
distance = self.get_distance(home, self.mav.location())

self.wait_altitude(expected_alt - 10, expected_alt + 10, relative=True)

new_distance = self.get_distance(home, self.mav.location())
# We should be farther from to home.
if new_distance < distance:
raise NotAchievedException(
"Expected to be farther from home (was %fm, now %fm)."
% (distance, new_distance)
)

self.fly_home_land_and_disarm()

def rtl_climb_min(self):
self.wait_ready_to_arm()
rtl_climb_min = 100
Expand Down Expand Up @@ -2805,6 +2856,10 @@ def tests(self):
"Test RTL_CLIMB_MIN",
self.rtl_climb_min),

("ClimbBeforeTurn",
"Test climb-before-turn",
self.climb_before_turn),

("IMUTempCal",
"Test IMU temperature calibration",
self.test_imu_tempcal),
Expand Down