mirror of https://github.com/ArduPilot/ardupilot
autotest: add test for Plane's RTL_CLIMB_MIN parameter
This commit is contained in:
parent
e4d5a92721
commit
ca49f62b6d
|
@ -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
|
|
@ -1431,6 +1431,49 @@ class AutoTestPlane(AutoTest):
|
|||
self.deadreckoning_main()
|
||||
self.deadreckoning_main(disable_airspeed_sensor=True)
|
||||
|
||||
def rtl_climb_min(self):
|
||||
self.wait_ready_to_arm()
|
||||
rtl_climb_min = 100
|
||||
self.set_parameter("RTL_CLIMB_MIN", rtl_climb_min)
|
||||
takeoff_alt = 50
|
||||
self.takeoff(alt=takeoff_alt)
|
||||
self.change_mode('CRUISE')
|
||||
self.wait_distance_to_home(1000, 1500, timeout=60)
|
||||
post_cruise_alt = self.get_altitude(relative=True)
|
||||
self.change_mode('RTL')
|
||||
expected_alt = self.get_parameter("ALT_HOLD_RTL")/100.0
|
||||
if expected_alt == -1:
|
||||
expected_alt = self.get_altitude(relative=True)
|
||||
|
||||
# ensure we're about half-way-down at the half-way-home stage:
|
||||
self.wait_distance_to_nav_target(
|
||||
0,
|
||||
500,
|
||||
timeout=120,
|
||||
)
|
||||
alt = self.get_altitude(relative=True)
|
||||
expected_halfway_alt = expected_alt + (post_cruise_alt + rtl_climb_min - expected_alt)/2.0
|
||||
if abs(alt - expected_halfway_alt) > 30:
|
||||
raise NotAchievedException("Not half-way-down and half-way-home (want=%f got=%f" %
|
||||
(expected_halfway_alt, alt))
|
||||
self.progress("Half-way-down at half-way-home (want=%f vs got=%f)" %
|
||||
(expected_halfway_alt, alt))
|
||||
|
||||
rtl_radius = self.get_parameter("RTL_RADIUS")
|
||||
if rtl_radius == 0:
|
||||
rtl_radius = self.get_parameter("WP_LOITER_RAD")
|
||||
self.wait_distance_to_nav_target(
|
||||
0,
|
||||
rtl_radius,
|
||||
timeout=120,
|
||||
)
|
||||
alt = self.get_altitude(relative=True)
|
||||
if abs(alt - expected_alt) > 10:
|
||||
raise NotAchievedException(
|
||||
"Expected to have %fm altitude at end of RTL (got %f)" %
|
||||
(expected_alt, alt))
|
||||
self.fly_home_land_and_disarm()
|
||||
|
||||
def sample_enable_parameter(self):
|
||||
return "Q_ENABLE"
|
||||
|
||||
|
@ -2376,6 +2419,10 @@ class AutoTestPlane(AutoTest):
|
|||
"Test AirSpeed drivers",
|
||||
self.test_airspeed_drivers),
|
||||
|
||||
("RTL_CLIMB_MIN",
|
||||
"Test RTL_CLIMB_MIN",
|
||||
self.rtl_climb_min),
|
||||
|
||||
("IMUTempCal",
|
||||
"Test IMU temperature calibration",
|
||||
self.test_imu_tempcal),
|
||||
|
|
Loading…
Reference in New Issue