From bfa15133c79f7894ef67d8d06aa602eac8b8fd04 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 21 Feb 2023 10:04:45 +0900 Subject: [PATCH] Tools: autotest fixes for rover fixes camera mission, set-message-interval, request-message, SendToComponents --- Tools/autotest/common.py | 4 ++++ Tools/autotest/rover.py | 6 +++++- 2 files changed, 9 insertions(+), 1 deletion(-) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 5908d28783..f5f8e52de0 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -9730,6 +9730,8 @@ Also, ignores heartbeats not from our target system''' def SET_MESSAGE_INTERVAL(self): '''Test MAV_CMD_SET_MESSAGE_INTERVAL''' + self.set_parameter("CAM1_TYPE", 1) # Camera with servo trigger + self.reboot_sitl() # needed for CAM1_TYPE to take effect self.start_subtest('Basic tests') self.test_set_message_interval_basic() self.start_subtest('Many-message tests') @@ -9895,6 +9897,8 @@ Also, ignores heartbeats not from our target system''' def REQUEST_MESSAGE(self, timeout=60): '''Test MAV_CMD_REQUEST_MESSAGE''' + self.set_parameter("CAM1_TYPE", 1) # Camera with servo trigger + self.reboot_sitl() # needed for CAM1_TYPE to take effect rate = round(self.get_message_rate("CAMERA_FEEDBACK", 10)) if rate != 0: raise PreconditionFailedException("Receiving camera feedback") diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 18afed01b1..bc15c185f2 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -1151,6 +1151,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) def CameraMission(self): '''Test Camera Mission Items''' + self.set_parameter("CAM1_TYPE", 1) # Camera with servo trigger + self.reboot_sitl() # needed for CAM1_TYPE to take effect self.load_mission("rover-camera-mission.txt") self.wait_ready_to_arm() self.change_mode("AUTO") @@ -5535,6 +5537,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) def SendToComponents(self): '''Test ArduPilot send_to_components function''' + self.set_parameter("CAM1_TYPE", 5) # Camera with MAVlink trigger + self.reboot_sitl() # needed for CAM1_TYPE to take effect self.progress("Introducing ourselves to the autopilot as a component") old_srcSystem = self.mav.mav.srcSystem self.mav.mav.srcSystem = 1 @@ -5552,7 +5556,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) 1, # zoom_pos 0, # zoom_step 0, # focus_lock - 1, # 1 shot or start filming + 0, # 1 shot or start filming 17, # command id (de-dupe field) 0, # extra_param 0.0, # extra_value