autotest: stop using start_test for things that aren't actually tests

start_test should only be used for top-level tests, not parts of
top-level tests
This commit is contained in:
Peter Barker 2021-04-28 12:24:49 +10:00 committed by Peter Barker
parent a3ceb6d95b
commit fc426e01c2
1 changed files with 10 additions and 10 deletions

View File

@ -7897,7 +7897,7 @@ Also, ignores heartbeats not from our target system'''
for frame in MAV_FRAMES_TO_TEST: for frame in MAV_FRAMES_TO_TEST:
frame_name = mavutil.mavlink.enums["MAV_FRAME"][frame].name frame_name = mavutil.mavlink.enums["MAV_FRAME"][frame].name
self.start_test("Testing Set Position in %s" % frame_name) self.start_subtest("Testing Set Position in %s" % frame_name)
self.start_subtest("Changing Latitude") self.start_subtest("Changing Latitude")
targetpos.lat += 0.0001 targetpos.lat += 0.0001
if test_alt: if test_alt:
@ -7935,8 +7935,8 @@ Also, ignores heartbeats not from our target system'''
height_accuracy=2, minimum_duration=2) height_accuracy=2, minimum_duration=2)
if test_heading: if test_heading:
self.start_test("Testing Yaw targetting in %s" % frame_name) self.start_subtest("Testing Yaw targetting in %s" % frame_name)
self.start_subtest("Changing Latitude and Heading") self.progress("Changing Latitude and Heading")
targetpos.lat += 0.0001 targetpos.lat += 0.0001
if test_alt: if test_alt:
targetpos.alt += 5 targetpos.alt += 5
@ -7997,7 +7997,7 @@ Also, ignores heartbeats not from our target system'''
self.wait_heading(0, minimum_duration=5, timeout=timeout) self.wait_heading(0, minimum_duration=5, timeout=timeout)
if test_yaw_rate: if test_yaw_rate:
self.start_test("Testing Yaw Rate targetting in %s" % frame_name) self.start_subtest("Testing Yaw Rate targetting in %s" % frame_name)
def send_yaw_rate(rate, target=None): def send_yaw_rate(rate, target=None):
self.mav.mav.set_position_target_global_int_send( self.mav.mav.set_position_target_global_int_send(
@ -8053,7 +8053,7 @@ Also, ignores heartbeats not from our target system'''
self.stop_mavproxy(mavproxy) self.stop_mavproxy(mavproxy)
self.start_test("Getting back to home and disarm") self.progress("Getting back to home and disarm")
self.do_RTL(distance_min=0, distance_max=wp_accuracy) self.do_RTL(distance_min=0, distance_max=wp_accuracy)
self.disarm_vehicle() self.disarm_vehicle()
@ -8119,8 +8119,8 @@ Also, ignores heartbeats not from our target system'''
for frame in MAV_FRAMES_TO_TEST: for frame in MAV_FRAMES_TO_TEST:
frame_name = mavutil.mavlink.enums["MAV_FRAME"][frame].name frame_name = mavutil.mavlink.enums["MAV_FRAME"][frame].name
self.start_test("Testing Set Velocity in %s" % frame_name) self.start_subtest("Testing Set Velocity in %s" % frame_name)
self.start_subtest("Changing Vx speed") self.progress("Changing Vx speed")
self.wait_speed_vector( self.wait_speed_vector(
target_speed, target_speed,
timeout=timeout, timeout=timeout,
@ -8189,7 +8189,7 @@ Also, ignores heartbeats not from our target system'''
) )
if test_heading: if test_heading:
self.start_test("Testing Yaw targetting in %s" % frame_name) self.start_subtest("Testing Yaw targetting in %s" % frame_name)
def send_yaw_target(yaw, mav_frame): def send_yaw_target(yaw, mav_frame):
self.mav.mav.set_position_target_global_int_send( self.mav.mav.set_position_target_global_int_send(
@ -8288,7 +8288,7 @@ Also, ignores heartbeats not from our target system'''
) )
if test_yaw_rate: if test_yaw_rate:
self.start_test("Testing Yaw Rate targetting in %s" % frame_name) self.start_subtest("Testing Yaw Rate targetting in %s" % frame_name)
def send_yaw_rate(rate, mav_frame): def send_yaw_rate(rate, mav_frame):
self.mav.mav.set_position_target_global_int_send( self.mav.mav.set_position_target_global_int_send(
@ -8425,7 +8425,7 @@ Also, ignores heartbeats not from our target system'''
self.stop_mavproxy(mavproxy) self.stop_mavproxy(mavproxy)
self.start_test("Getting back to home and disarm") self.progress("Getting back to home and disarm")
self.do_RTL(distance_min=0, distance_max=wp_accuracy) self.do_RTL(distance_min=0, distance_max=wp_accuracy)
self.disarm_vehicle() self.disarm_vehicle()