diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index d60b3943b2..173191b5b8 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -9814,7 +9814,7 @@ class AutoTestCopter(AutoTest): self.do_RTL() - def RPLidar(self): + def test_rplidar(self, sim_device_name, expected_distances): '''plonks a Copter with a RPLidarA2 in the middle of a simulated field of posts and checks that the measurements are what we expect.''' self.set_parameters({ @@ -9822,21 +9822,10 @@ class AutoTestCopter(AutoTest): "PRX1_TYPE": 5, }) self.customise_SITL_commandline([ - "--uartF=sim:rplidara2:", + "--uartF=sim:%s:" % sim_device_name, "--home", "51.8752066,14.6487840,0,0", # SITL has "posts" here ]) - expected_distances = { - mavutil.mavlink.MAV_SENSOR_ROTATION_NONE: 276, - mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_45: 256, - mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_90: 1130, - mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_135: 1286, - mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_180: 626, - mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_225: 971, - mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_270: 762, - mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_315: 792, - } - self.wait_ready_to_arm() wanting_distances = copy.copy(expected_distances) @@ -9860,12 +9849,45 @@ class AutoTestCopter(AutoTest): wanting_distances[m.orientation], m.current_distance)) continue + self.progress("Correct distance for orient %u (want=%u got=%u)" % + (m.orientation, + wanting_distances[m.orientation], + m.current_distance)) del wanting_distances[m.orientation] - self.progress("Got correct distance for orient %u" % - (m.orientation)) if len(wanting_distances.items()) == 0: break + def RPLidarA2(self): + '''test Raspberry Pi Lidar A2''' + expected_distances = { + mavutil.mavlink.MAV_SENSOR_ROTATION_NONE: 276, + mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_45: 256, + mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_90: 1130, + mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_135: 1286, + mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_180: 626, + mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_225: 971, + mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_270: 762, + mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_315: 792, + } + + self.test_rplidar("rplidara2", expected_distances) + + def RPLidarA1(self): + '''test Raspberry Pi Lidar A1''' + return # we don't send distances when too long? + expected_distances = { + mavutil.mavlink.MAV_SENSOR_ROTATION_NONE: 276, + mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_45: 256, + mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_90: 800, + mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_135: 800, + mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_180: 626, + mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_225: 800, + mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_270: 762, + mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_315: 792, + } + + self.test_rplidar("rplidara1", expected_distances) + def tests2b(self): # this block currently around 9.5mins here '''return list of all tests''' ret = ([ @@ -9922,7 +9944,8 @@ class AutoTestCopter(AutoTest): self.AHRSTrimLand, self.GuidedYawRate, self.NoArmWithoutMissionItems, - self.RPLidar, + self.RPLidarA1, + self.RPLidarA2, ]) return ret