Skip to content

Commit 7abba85

Browse files
committed
autotest: add test for conversion of command long to command int sanity checks
1 parent 0b4cee8 commit 7abba85

File tree

2 files changed

+66
-0
lines changed

2 files changed

+66
-0
lines changed

Tools/autotest/rover.py

Lines changed: 56 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6945,6 +6945,61 @@ def SDPolyFence(self):
69456945

69466946
self.delay_sim_time(1000)
69476947

6948+
def convert_COMMAND_LONG_to_COMMAND_INT(self):
6949+
'''test the convert_COMMAND_LONG_to_COMMAND_INT function'''
6950+
self.change_mode('GUIDED')
6951+
self.wait_ready_to_arm()
6952+
self.run_cmd(
6953+
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
6954+
p5=0, # lat
6955+
p6=0, # lng
6956+
p7=0, # alt
6957+
)
6958+
6959+
self.run_cmd(
6960+
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
6961+
p5=10, # lat
6962+
p6=20, # lng
6963+
p7=30, # alt
6964+
)
6965+
self.assert_home_position_at(10, 20, 30)
6966+
6967+
self.progress("Ensure NaN is bounced")
6968+
self.run_cmd(
6969+
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
6970+
p5=float("NaN"), # lat
6971+
p6=10, # lng
6972+
p7=10, # alt
6973+
want_result=mavutil.mavlink.MAV_RESULT_DENIED,
6974+
)
6975+
6976+
self.progress("Ensure INF is bounced")
6977+
self.run_cmd(
6978+
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
6979+
p5=float("Inf"), # lat
6980+
p6=10, # lng
6981+
p7=10, # alt
6982+
want_result=mavutil.mavlink.MAV_RESULT_DENIED,
6983+
)
6984+
6985+
self.progress("Ensure OOB lat is bounced")
6986+
self.run_cmd(
6987+
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
6988+
p5=91, # lat
6989+
p6=10, # lng
6990+
p7=10, # alt
6991+
want_result=mavutil.mavlink.MAV_RESULT_DENIED,
6992+
)
6993+
6994+
self.progress("Ensure OOB lng is bounced")
6995+
self.run_cmd(
6996+
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
6997+
p5=10, # lat
6998+
p6=190, # lng
6999+
p7=10, # alt
7000+
want_result=mavutil.mavlink.MAV_RESULT_DENIED,
7001+
)
7002+
69487003
def tests(self):
69497004
'''return list of all tests'''
69507005
ret = super(AutoTestRover, self).tests()
@@ -7043,6 +7098,7 @@ def tests(self):
70437098
self.ClearMission,
70447099
self.JammingSimulation,
70457100
self.BatteryInvalid,
7101+
self.convert_COMMAND_LONG_to_COMMAND_INT,
70467102
])
70477103
return ret
70487104

Tools/autotest/vehicle_test_suite.py

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9418,6 +9418,16 @@ def home_position_as_mav_location(self):
94189418
m = self.poll_home_position()
94199419
return mavutil.location(m.latitude*1.0e-7, m.longitude*1.0e-7, m.altitude*1.0e-3, 0)
94209420

9421+
def assert_home_position_at(self, lat, lng, alt):
9422+
'''assert home is at specified lat/lng/alt, deg/deg/metres'''
9423+
home = self.home_position_as_mav_location()
9424+
if home.lat != lat:
9425+
raise NotAchievedException("Bad lat")
9426+
if home.lng != lng:
9427+
raise NotAchievedException("Bad lng")
9428+
if home.alt != alt:
9429+
raise NotAchievedException("Bad alt")
9430+
94219431
def offset_location_ne(self, location, metres_north, metres_east):
94229432
'''return a new location offset from passed-in location'''
94239433
(target_lat, target_lng) = mavextra.gps_offset(location.lat,

0 commit comments

Comments
 (0)