From b14dcf4baeae802f713791e72f31e0fe2b4940e7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 3 Jul 2020 09:04:28 +1000 Subject: [PATCH] Tools: add mission command to turn sprayer on and off --- .../ArduRover_Tests/Sprayer/sprayer-mission.txt | 7 +++++++ Tools/autotest/rover.py | 15 +++++++++++++++ 2 files changed, 22 insertions(+) create mode 100644 Tools/autotest/ArduRover_Tests/Sprayer/sprayer-mission.txt diff --git a/Tools/autotest/ArduRover_Tests/Sprayer/sprayer-mission.txt b/Tools/autotest/ArduRover_Tests/Sprayer/sprayer-mission.txt new file mode 100644 index 0000000000..4a9a7a19ec --- /dev/null +++ b/Tools/autotest/ArduRover_Tests/Sprayer/sprayer-mission.txt @@ -0,0 +1,7 @@ +QGC WPL 110 +0 0 0 16 0.000000 0.000000 0.000000 0.000000 40.071375 -105.229789 -0.020000 1 +1 0 3 16 0.000000 0.000000 0.000000 0.000000 40.071364 -105.230440 100.000000 1 +2 0 0 216 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1 +3 0 3 16 0.000000 0.000000 0.000000 0.000000 40.071319 -105.230331 100.000000 1 +4 0 0 216 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1 +5 0 3 16 0.000000 0.000000 0.000000 0.000000 40.071319 -105.230331 100.000000 1 diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 34b2690ad8..5f9aa7d1b9 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -5,6 +5,7 @@ from __future__ import print_function import copy import math +import operator import os import shutil import sys @@ -295,6 +296,20 @@ class AutoTestRover(AutoTest): # this is somewhat empirical... self.wait_servo_channel_value(pump_ch, 1695, timeout=60) + self.progress("Turning it off again") + self.set_rc(rc_ch, 1000) + self.wait_servo_channel_value(spinner_ch, spinner_ch_min) + self.wait_servo_channel_value(pump_ch, pump_ch_min) + + self.start_subtest("Sprayer Mission") + self.load_mission("sprayer-mission.txt") + self.change_mode("AUTO") +# self.send_debug_trap() + self.progress("Waiting for sprayer to start") + self.wait_servo_channel_value(pump_ch, 1300, timeout=60, comparator=operator.gt) + self.progress("Waiting for sprayer to stop") + self.wait_servo_channel_value(pump_ch, pump_ch_min, timeout=120) + self.progress("Sprayer OK") except Exception as e: self.progress("Caught exception: %s" %