autotest: add regression tests for Winch
This commit is contained in:
parent
38ba5da09b
commit
0a98953ad7
@ -4735,6 +4735,74 @@ class AutoTestCopter(AutoTest):
|
||||
self.wait_heading(100, accuracy=8, timeout=100)
|
||||
self.do_RTL()
|
||||
|
||||
def _DO_WINCH(self, command):
|
||||
self.context_push()
|
||||
self.load_default_params_file("copter-winch.parm")
|
||||
self.reboot_sitl()
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
self.start_subtest("starts relaxed")
|
||||
self.wait_servo_channel_value(9, 0)
|
||||
|
||||
self.start_subtest("rate control")
|
||||
command(
|
||||
mavutil.mavlink.MAV_CMD_DO_WINCH,
|
||||
p1=1, # instance number
|
||||
p2=mavutil.mavlink.WINCH_RATE_CONTROL, # command
|
||||
p3=0, # length to release
|
||||
p4=1, # rate in m/s
|
||||
)
|
||||
self.wait_servo_channel_value(9, 1900)
|
||||
|
||||
self.start_subtest("relax")
|
||||
command(
|
||||
mavutil.mavlink.MAV_CMD_DO_WINCH,
|
||||
p1=1, # instance number
|
||||
p2=mavutil.mavlink.WINCH_RELAXED, # command
|
||||
p3=0, # length to release
|
||||
p4=1, # rate in m/s
|
||||
)
|
||||
self.wait_servo_channel_value(9, 0)
|
||||
|
||||
self.start_subtest("hold but zero output")
|
||||
command(
|
||||
mavutil.mavlink.MAV_CMD_DO_WINCH,
|
||||
p1=1, # instance number
|
||||
p2=mavutil.mavlink.WINCH_RATE_CONTROL, # command
|
||||
p3=0, # length to release
|
||||
p4=0, # rate in m/s
|
||||
)
|
||||
self.wait_servo_channel_value(9, 1500)
|
||||
|
||||
self.start_subtest("relax")
|
||||
command(
|
||||
mavutil.mavlink.MAV_CMD_DO_WINCH,
|
||||
p1=1, # instance number
|
||||
p2=mavutil.mavlink.WINCH_RELAXED, # command
|
||||
p3=0, # length to release
|
||||
p4=1, # rate in m/s
|
||||
)
|
||||
self.wait_servo_channel_value(9, 0)
|
||||
|
||||
self.start_subtest("position")
|
||||
command(
|
||||
mavutil.mavlink.MAV_CMD_DO_WINCH,
|
||||
p1=1, # instance number
|
||||
p2=mavutil.mavlink.WINCH_RELATIVE_LENGTH_CONTROL, # command
|
||||
p3=2, # length to release
|
||||
p4=1, # rate in m/s
|
||||
)
|
||||
self.wait_servo_channel_value(9, 1900)
|
||||
self.wait_servo_channel_value(9, 1500, timeout=60)
|
||||
|
||||
self.context_pop()
|
||||
self.reboot_sitl()
|
||||
|
||||
def DO_WINCH(self):
|
||||
'''test mavlink DO_WINCH command'''
|
||||
self._DO_WINCH(self.run_cmd_int)
|
||||
self._DO_WINCH(self.run_cmd)
|
||||
|
||||
def GuidedSubModeChange(self):
|
||||
""""Ensure we can move around in guided after a takeoff command."""
|
||||
|
||||
@ -10180,6 +10248,7 @@ class AutoTestCopter(AutoTest):
|
||||
self.WPNAV_SPEED,
|
||||
self.WPNAV_SPEED_UP,
|
||||
self.WPNAV_SPEED_DN,
|
||||
self.DO_WINCH,
|
||||
self.SensorErrorFlags,
|
||||
self.GPSForYaw,
|
||||
self.DefaultIntervalsFromFiles,
|
||||
|
Loading…
Reference in New Issue
Block a user