autotest: use set_parameters in rover; fixup tests to use context

This commit is contained in:
Peter Barker 2022-06-29 18:32:59 +10:00 committed by Peter Barker
parent 1c9c1d7207
commit 043764fbf9
1 changed files with 92 additions and 61 deletions

View File

@ -90,8 +90,10 @@ class AutoTestRover(AutoTest):
ex = None
try:
self.progress("TEST SQUARE")
self.set_parameter("RC7_OPTION", 7)
self.set_parameter("RC9_OPTION", 58)
self.set_parameters({
"RC7_OPTION": 7,
"RC9_OPTION": 58,
})
self.change_mode('MANUAL')
@ -442,15 +444,17 @@ class AutoTestRover(AutoTest):
raise MsgRcvTimeoutException("banner not received")
def drive_brake_get_stopping_distance(self, speed):
# measure our stopping distance:
old_cruise_speed = self.get_parameter('CRUISE_SPEED')
old_accel_max = self.get_parameter('ATC_ACCEL_MAX')
'''measure our stopping distance'''
self.context_push()
# controller tends not to meet cruise speed (max of ~14 when 15
# set), thus *1.2
self.set_parameter('CRUISE_SPEED', speed*1.2)
# at time of writing, the vehicle is only capable of 10m/s/s accel
self.set_parameter('ATC_ACCEL_MAX', 15)
self.set_parameters({
'CRUISE_SPEED': speed*1.2,
'ATC_ACCEL_MAX': 15,
})
self.change_mode("STEERING")
self.set_rc(3, 2000)
self.wait_groundspeed(15, 100)
@ -472,17 +476,15 @@ class AutoTestRover(AutoTest):
break
delta = self.get_distance(start, stop)
self.set_parameter('CRUISE_SPEED', old_cruise_speed)
self.set_parameter('ATC_ACCEL_MAX', old_accel_max)
self.context_pop()
return delta
def drive_brake(self):
old_using_brake = self.get_parameter('ATC_BRAKE')
old_cruise_speed = self.get_parameter('CRUISE_SPEED')
self.set_parameter('CRUISE_SPEED', 15)
self.set_parameter('ATC_BRAKE', 0)
self.set_parameters({
'CRUISE_SPEED': 15,
'ATC_BRAKE': 0,
})
self.arm_vehicle()
@ -491,13 +493,12 @@ class AutoTestRover(AutoTest):
# brakes on:
self.set_parameter('ATC_BRAKE', 1)
distance_with_brakes = self.drive_brake_get_stopping_distance(15)
# revert state:
self.set_parameter('ATC_BRAKE', old_using_brake)
self.set_parameter('CRUISE_SPEED', old_cruise_speed)
delta = distance_without_brakes - distance_with_brakes
self.disarm_vehicle()
if delta < distance_without_brakes * 0.05: # 5% isn't asking for much
self.disarm_vehicle()
raise NotAchievedException("""
Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
""" %
@ -505,8 +506,6 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
distance_without_brakes,
delta))
self.disarm_vehicle()
self.progress(
"Brakes work (with=%0.2fm without=%0.2fm delta=%0.2fm)" %
(distance_with_brakes, distance_without_brakes, delta))
@ -570,9 +569,11 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
ex = None
try:
self.load_fence("rover-fence-ac-avoid.txt")
self.set_parameter("FENCE_ENABLE", 0)
self.set_parameter("PRX_TYPE", 10)
self.set_parameter("RC10_OPTION", 40) # proximity-enable
self.set_parameters({
"FENCE_ENABLE": 0,
"PRX_TYPE": 10,
"RC10_OPTION": 40, # proximity-enable
})
self.reboot_sitl()
# start = self.mav.location()
self.wait_ready_to_arm()
@ -699,8 +700,10 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.set_rc(9, 1000)
self.set_rc(10, 1000)
self.set_parameter("RC9_OPTION", 53) # steering
self.set_parameter("RC10_OPTION", 54) # hold
self.set_parameters({
"RC9_OPTION": 53, # steering
"RC10_OPTION": 54, # hold
})
self.set_rc(9, 1900)
self.wait_mode("STEERING")
self.set_rc(10, 1900)
@ -4357,8 +4360,10 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.wait_ready_to_arm()
here = self.mav.location()
self.progress("here: %f %f" % (here.lat, here.lng))
self.set_parameter("FENCE_ENABLE", 1)
self.set_parameter("AVOID_ENABLE", 0)
self.set_parameters({
"FENCE_ENABLE": 1,
"AVOID_ENABLE": 0,
})
# self.set_parameter("SIM_SPEEDUP", 1)
@ -4606,9 +4611,11 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.context_push()
ex = None
try:
self.set_parameter("AVOID_ENABLE", 3)
self.set_parameter("OA_TYPE", 2)
self.set_parameter("FENCE_MARGIN", 0) # FIXME: https://github.com/ArduPilot/ardupilot/issues/11601
self.set_parameters({
"AVOID_ENABLE": 3,
"OA_TYPE": 2,
"FENCE_MARGIN": 0, # FIXME: https://github.com/ArduPilot/ardupilot/issues/11601
})
self.reboot_sitl()
self.change_mode('AUTO')
self.wait_ready_to_arm()
@ -4653,9 +4660,11 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.context_push()
ex = None
try:
self.set_parameter("AVOID_ENABLE", 3)
self.set_parameter("OA_TYPE", 2)
self.set_parameter("FENCE_MARGIN", 0) # FIXME: https://github.com/ArduPilot/ardupilot/issues/11601
self.set_parameters({
"AVOID_ENABLE": 3,
"OA_TYPE": 2,
"FENCE_MARGIN": 0, # FIXME: https://github.com/ArduPilot/ardupilot/issues/11601
})
self.reboot_sitl()
self.change_mode('GUIDED')
self.wait_ready_to_arm()
@ -4682,9 +4691,11 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
'''make sure wheel encoders are generally working'''
ex = None
try:
self.set_parameter("WENC_TYPE", 10)
self.set_parameter("EK3_ENABLE", 1)
self.set_parameter("AHRS_EKF_TYPE", 3)
self.set_parameters({
"WENC_TYPE": 10,
"EK3_ENABLE": 1,
"AHRS_EKF_TYPE": 3,
})
self.reboot_sitl()
self.change_mode("LOITER")
self.wait_ready_to_arm()
@ -4738,8 +4749,10 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.context_push()
ex = None
try:
self.set_parameter("AVOID_ENABLE", 3)
self.set_parameter("OA_TYPE", 2)
self.set_parameters({
"AVOID_ENABLE": 3,
"OA_TYPE": 2,
})
self.reboot_sitl()
self.change_mode('GUIDED')
self.wait_ready_to_arm()
@ -4787,8 +4800,10 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
])
if self.mavproxy is not None:
self.mavproxy.send("fence list\n")
self.set_parameter("FENCE_ENABLE", 1)
self.set_parameter("AVOID_ENABLE", 3)
self.set_parameters({
"FENCE_ENABLE": 1,
"AVOID_ENABLE": 3,
})
fence_middle = self.offset_location_ne(here, 0, 30)
# FIXME: this might be nowhere near "here"!
expected_stopping_point = mavutil.location(40.0713376, -105.2295738, 0, 0)
@ -4824,15 +4839,19 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.context_push()
ex = None
try:
self.set_parameter("AVOID_ENABLE", 3)
self.set_parameter("OA_TYPE", 1)
self.set_parameter("OA_LOOKAHEAD", 50)
self.set_parameters({
"AVOID_ENABLE": 3,
"OA_TYPE": 1,
"OA_LOOKAHEAD": 50,
})
self.reboot_sitl()
self.change_mode('GUIDED')
self.wait_ready_to_arm()
self.arm_vehicle()
self.set_parameter("FENCE_ENABLE", 1)
self.set_parameter("WP_RADIUS", 5)
self.set_parameters({
"FENCE_ENABLE": 1,
"WP_RADIUS": 5,
})
if self.mavproxy is not None:
self.mavproxy.send("fence list\n")
target_loc = mavutil.location(40.071060, -105.227734, 0, 0)
@ -4871,15 +4890,19 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.context_push()
ex = None
try:
self.set_parameter("AVOID_ENABLE", 3)
self.set_parameter("OA_TYPE", 1)
self.set_parameter("OA_LOOKAHEAD", 50)
self.set_parameters({
"AVOID_ENABLE": 3,
"OA_TYPE": 1,
"OA_LOOKAHEAD": 50,
})
self.reboot_sitl()
self.change_mode('GUIDED')
self.wait_ready_to_arm()
self.arm_vehicle()
self.set_parameter("FENCE_ENABLE", 1)
self.set_parameter("WP_RADIUS", 5)
self.set_parameters({
"FENCE_ENABLE": 1,
"WP_RADIUS": 5,
})
if self.mavproxy is not None:
self.mavproxy.send("fence list\n")
target_loc = mavutil.location(40.071260, -105.227000, 0, 0)
@ -4912,15 +4935,19 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.context_push()
ex = None
try:
self.set_parameter("AVOID_ENABLE", 3)
self.set_parameter("OA_TYPE", 1)
self.set_parameter("OA_LOOKAHEAD", 50)
self.set_parameters({
"AVOID_ENABLE": 3,
"OA_TYPE": 1,
"OA_LOOKAHEAD": 50,
})
self.reboot_sitl()
self.change_mode('AUTO')
self.wait_ready_to_arm()
self.arm_vehicle()
self.set_parameter("FENCE_ENABLE", 1)
self.set_parameter("WP_RADIUS", 5)
self.set_parameters({
"FENCE_ENABLE": 1,
"WP_RADIUS": 5,
})
if self.mavproxy is not None:
self.mavproxy.send("fence list\n")
target_loc = mavutil.location(40.071260, -105.227000, 0, 0)
@ -5009,9 +5036,11 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
messages.append(message)
self.install_message_hook(my_message_hook)
try:
self.set_parameter("SCR_ENABLE", 1)
self.set_parameter("SCR_HEAP_SIZE", 1024000)
self.set_parameter("SCR_VM_I_COUNT", 1000000)
self.set_parameters({
"SCR_ENABLE": 1,
"SCR_HEAP_SIZE": 1024000,
"SCR_VM_I_COUNT": 1000000,
})
for script in test_scripts:
self.install_test_script(script)
@ -5315,9 +5344,11 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.context_push()
ex = None
try:
self.set_parameter("PRX_TYPE", 2) # AP_Proximity_MAV
self.set_parameter("OA_TYPE", 2) # dijkstra
self.set_parameter("OA_DB_OUTPUT", 3) # send all items
self.set_parameters({
"PRX_TYPE": 2, # AP_Proximity_MAV
"OA_TYPE": 2, # dijkstra
"OA_DB_OUTPUT": 3, # send all items
})
self.reboot_sitl()
# 1 laser pointing straight forward: