Skip to content

Commit

Permalink
autotest: add test for Rover's require-location-for-arming flag
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Feb 3, 2025
1 parent 068c742 commit 3ce8479
Show file tree
Hide file tree
Showing 3 changed files with 38 additions and 12 deletions.
10 changes: 0 additions & 10 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -12243,16 +12243,6 @@ def GripperReleaseOnThrustLoss(self):
self.context_pop()
self.reboot_sitl()

def assert_home_position_not_set(self):
try:
self.poll_home_position()
except NotAchievedException:
return

# if home.lng != 0: etc

raise NotAchievedException("Home is set when it shouldn't be")

def REQUIRE_LOCATION_FOR_ARMING(self):
'''check AP_Arming::Option::REQUIRE_LOCATION_FOR_ARMING works'''
self.context_push()
Expand Down
26 changes: 26 additions & 0 deletions Tools/autotest/rover.py
Original file line number Diff line number Diff line change
Expand Up @@ -6947,6 +6947,31 @@ def SDPolyFence(self):

self.delay_sim_time(1000)

def REQUIRE_POSITION_FOR_ARMING(self):
'''check DriveOption::REQUIRE_POSITION_FOR_ARMING works'''
self.context_push()
self.set_parameters({
"SIM_GPS1_NUMSATS": 3, # EKF does not like < 6
"AHRS_GPS_USE": 0, # stop DCM supplying home
})
self.reboot_sitl()
self.change_mode('MANUAL')
self.wait_prearm_sys_status_healthy()
self.assert_home_position_not_set()
self.arm_vehicle()
self.disarm_vehicle()

self.change_mode('GUIDED')
self.assert_prearm_failure("waiting for home", other_prearm_failures_fatal=False)

self.change_mode('MANUAL')
self.set_parameters({
"DRIVE_OPTIONS": 1,
})
self.assert_prearm_failure("waiting for home", other_prearm_failures_fatal=False)
self.context_pop()
self.reboot_sitl()

def tests(self):
'''return list of all tests'''
ret = super(AutoTestRover, self).tests()
Expand Down Expand Up @@ -7045,6 +7070,7 @@ def tests(self):
self.ClearMission,
self.JammingSimulation,
self.BatteryInvalid,
self.REQUIRE_POSITION_FOR_ARMING,
])
return ret

Expand Down
14 changes: 12 additions & 2 deletions Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -3625,6 +3625,16 @@ def assert_bytes_equal(self, bytes1, bytes2, maxlen=None):
if bytes1[i] != bytes2[i]:
raise NotAchievedException("differ at offset %u" % i)

def assert_home_position_not_set(self):
try:
self.poll_home_position()
except NotAchievedException:
return

# if home.lng != 0: etc

raise NotAchievedException("Home is set when it shouldn't be")

def HIGH_LATENCY2(self):
'''test sending of HIGH_LATENCY2'''

Expand Down Expand Up @@ -8331,8 +8341,8 @@ def assert_prearm_failure(self,
now = self.get_sim_time_cached()
if now - tstart > timeout:
raise NotAchievedException(
"Did not see failure-to-arm messages (statustext=%s command_ack=%s" %
(seen_statustext, seen_command_ack))
f"Did not see failure-to-arm messages ({seen_statustext=} {expected_statustext=} {seen_command_ack=})"
)
if now - arm_last_send > 1:
arm_last_send = now
self.send_mavlink_run_prearms_command()
Expand Down

0 comments on commit 3ce8479

Please sign in to comment.