mirror of https://github.com/ArduPilot/ardupilot
autotest: add test for AUTO_LAND_TO_BRAKE
Having some terrain-based issues with BRAKE mode
This commit is contained in:
parent
7647e38f3f
commit
72734d38de
|
@ -0,0 +1,19 @@
|
|||
QGC WPL 110
|
||||
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -20.558323 -47.415722 931.809998 1
|
||||
1 0 3 22 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 35.000000 1
|
||||
2 0 3 16 1.000000 0.000000 0.000000 0.000000 -20.558323 -47.415722 35.000000 1
|
||||
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -20.558152 -47.415520 35.000000 1
|
||||
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -20.558317 -47.415059 35.000000 1
|
||||
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -20.558746 -47.414832 35.000000 1
|
||||
6 0 3 16 1.000000 0.000000 0.000000 0.000000 -20.558941 -47.415046 35.000000 1
|
||||
7 0 3 21 0.000000 0.000000 0.000000 1.000000 -20.558941 -47.415046 0.000000 1
|
||||
8 0 0 211 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||
9 0 0 93 5.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||
10 0 3 22 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 35.000000 1
|
||||
11 0 0 178 0.000000 8.888889 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||
12 0 3 16 1.000000 0.000000 0.000000 0.000000 -20.558941 -47.415046 35.000000 1
|
||||
13 0 3 16 0.000000 0.000000 0.000000 0.000000 -20.558746 -47.414832 35.000000 1
|
||||
14 0 3 16 0.000000 0.000000 0.000000 0.000000 -20.558317 -47.415059 35.000000 1
|
||||
15 0 3 16 0.000000 0.000000 0.000000 0.000000 -20.558152 -47.415520 35.000000 1
|
||||
16 0 3 16 1.000000 0.000000 0.000000 0.000000 -20.558323 -47.415722 35.000000 1
|
||||
17 0 3 21 0.000000 0.000000 0.000000 1.000000 -20.558323 -47.415722 0.000000 1
|
|
@ -8431,6 +8431,65 @@ class AutoTestCopter(AutoTest):
|
|||
|
||||
self.wait_disarmed()
|
||||
|
||||
def AUTO_LAND_TO_BRAKE(self):
|
||||
'''ensure terrain altitude is taken into account when braking'''
|
||||
self.load_mission('mission.txt')
|
||||
home_loc = self.get_home_tuple_from_mission("mission.txt")
|
||||
|
||||
self.set_parameters({
|
||||
"PLND_ACC_P_NSE": 2.500000,
|
||||
"PLND_ALT_MAX": 8.000000,
|
||||
"PLND_ALT_MIN": 0.750000,
|
||||
"PLND_BUS": -1,
|
||||
"PLND_CAM_POS_X": 0.000000,
|
||||
"PLND_CAM_POS_Y": 0.000000,
|
||||
"PLND_CAM_POS_Z": 0.000000,
|
||||
"PLND_ENABLED": 1,
|
||||
"PLND_EST_TYPE": 1,
|
||||
"PLND_LAG": 0.020000,
|
||||
"PLND_LAND_OFS_X": 0.000000,
|
||||
"PLND_LAND_OFS_Y": 0.000000,
|
||||
"PLND_OPTIONS": 0,
|
||||
"PLND_RET_BEHAVE": 0,
|
||||
"PLND_RET_MAX": 4,
|
||||
"PLND_STRICT": 1,
|
||||
"PLND_TIMEOUT": 4.000000,
|
||||
"PLND_TYPE": 4,
|
||||
"PLND_XY_DIST_MAX": 2.500000,
|
||||
"PLND_YAW_ALIGN": 0.000000,
|
||||
|
||||
"SIM_PLD_ALT_LMT": 15.000000,
|
||||
"SIM_PLD_DIST_LMT": 10.000000,
|
||||
"SIM_PLD_ENABLE": 1,
|
||||
"SIM_PLD_HEIGHT": 942.0000000,
|
||||
"SIM_PLD_LAT": -20.558929,
|
||||
"SIM_PLD_LON": -47.415035,
|
||||
"SIM_PLD_RATE": 100,
|
||||
"SIM_PLD_TYPE": 1,
|
||||
"SIM_PLD_YAW": 87,
|
||||
|
||||
"SIM_SONAR_SCALE": 12,
|
||||
})
|
||||
|
||||
self.set_analog_rangefinder_parameters()
|
||||
|
||||
self.customise_SITL_commandline([
|
||||
"--home", "%s,%s,%s,%s" % home_loc
|
||||
])
|
||||
|
||||
self.set_parameter('AUTO_OPTIONS', 3)
|
||||
self.change_mode('AUTO')
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
|
||||
self.wait_current_waypoint(7)
|
||||
self.wait_altitude(10, 15, relative=True, timeout=60)
|
||||
self.change_mode('BRAKE')
|
||||
# monitor altitude here
|
||||
self.wait_altitude(10, 15, relative=True, minimum_duration=20)
|
||||
self.change_mode('AUTO')
|
||||
self.wait_disarmed()
|
||||
|
||||
# a wrapper around all the 1A,1B,1C..etc tests for travis
|
||||
def tests1(self):
|
||||
ret = ([])
|
||||
|
@ -9156,6 +9215,10 @@ class AutoTestCopter(AutoTest):
|
|||
"Change speed during misison using waypoint items",
|
||||
self.DO_CHANGE_SPEED),
|
||||
|
||||
Test("AUTO_LAND_TO_BRAKE",
|
||||
"Change to LAND while descending in AUTO land phase",
|
||||
self.AUTO_LAND_TO_BRAKE),
|
||||
|
||||
Test("WPNAV_SPEED",
|
||||
"Change speed during misison",
|
||||
self.WPNAV_SPEED),
|
||||
|
|
Loading…
Reference in New Issue