2017-02-21 13:32:26 -04:00
|
|
|
#!/usr/bin/env python
|
|
|
|
|
|
|
|
# Fly ArduPlane QuadPlane in SITL
|
2016-11-08 07:06:05 -04:00
|
|
|
from __future__ import print_function
|
2016-07-31 07:22:06 -03:00
|
|
|
import os
|
|
|
|
import pexpect
|
2016-01-09 01:27:03 -04:00
|
|
|
from pymavlink import mavutil
|
2016-07-31 07:22:06 -03:00
|
|
|
|
2018-03-14 08:08:53 -03:00
|
|
|
from common import AutoTest
|
2019-03-31 18:42:06 -03:00
|
|
|
from common import AutoTestTimeoutException
|
|
|
|
|
2016-07-31 07:22:06 -03:00
|
|
|
from pysim import util
|
2019-02-09 15:43:07 -04:00
|
|
|
from pysim import vehicleinfo
|
2019-02-11 13:55:18 -04:00
|
|
|
import operator
|
2016-01-09 01:27:03 -04:00
|
|
|
|
2019-03-31 18:42:06 -03:00
|
|
|
|
2016-01-09 01:27:03 -04:00
|
|
|
# get location of scripts
|
2016-07-31 07:22:06 -03:00
|
|
|
testdir = os.path.dirname(os.path.realpath(__file__))
|
2019-03-09 00:20:36 -04:00
|
|
|
SITL_START_LOCATION = mavutil.location(-27.274439, 151.290064, 343, 8.7)
|
2016-07-31 07:22:06 -03:00
|
|
|
MISSION = 'ArduPlane-Missions/Dalby-OBC2016.txt'
|
|
|
|
FENCE = 'ArduPlane-Missions/Dalby-OBC2016-fence.txt'
|
|
|
|
WIND = "0,180,0.2" # speed,direction,variance
|
2016-01-09 01:27:03 -04:00
|
|
|
|
2018-03-05 11:14:34 -04:00
|
|
|
|
2018-03-14 08:08:53 -03:00
|
|
|
class AutoTestQuadPlane(AutoTest):
|
2018-12-17 17:52:09 -04:00
|
|
|
|
2019-03-09 00:20:36 -04:00
|
|
|
def default_frame(self):
|
|
|
|
return "quadplane"
|
|
|
|
|
|
|
|
def test_filepath(self):
|
|
|
|
return os.path.realpath(__file__)
|
|
|
|
|
|
|
|
def sitl_start_location(self):
|
|
|
|
return SITL_START_LOCATION
|
|
|
|
|
|
|
|
def log_name(self):
|
|
|
|
return "QuadPlane"
|
|
|
|
|
|
|
|
def apply_defaultfile_parameters(self):
|
|
|
|
# plane passes in a defaults_file in place of applying
|
|
|
|
# parameters afterwards.
|
|
|
|
pass
|
|
|
|
|
|
|
|
def defaults_filepath(self):
|
2019-02-09 15:43:07 -04:00
|
|
|
vinfo = vehicleinfo.VehicleInfo()
|
|
|
|
defaults_file = vinfo.options["ArduPlane"]["frames"][self.frame]["default_params_filename"]
|
2019-04-14 10:44:04 -03:00
|
|
|
if isinstance(defaults_file, str):
|
|
|
|
defaults_file = [defaults_file]
|
|
|
|
defaults_list = []
|
|
|
|
for d in defaults_file:
|
|
|
|
defaults_list.append(os.path.join(testdir, d))
|
|
|
|
return ','.join(defaults_list)
|
2018-03-05 11:14:34 -04:00
|
|
|
|
2018-10-10 10:07:21 -03:00
|
|
|
def is_plane(self):
|
|
|
|
return True
|
|
|
|
|
2019-03-26 09:17:11 -03:00
|
|
|
def get_stick_arming_channel(self):
|
2018-10-10 10:07:21 -03:00
|
|
|
return int(self.get_parameter("RCMAP_YAW"))
|
|
|
|
|
|
|
|
def get_disarm_delay(self):
|
|
|
|
return int(self.get_parameter("LAND_DISARMDELAY"))
|
|
|
|
|
|
|
|
def set_autodisarm_delay(self, delay):
|
|
|
|
self.set_parameter("LAND_DISARMDELAY", delay)
|
2018-03-05 11:14:34 -04:00
|
|
|
|
2019-02-11 13:55:18 -04:00
|
|
|
def test_motor_mask(self):
|
|
|
|
"""Check operation of output_motor_mask"""
|
|
|
|
"""copter tailsitters will add condition: or (int(self.get_parameter('Q_TAILSIT_MOTMX')) & 1)"""
|
|
|
|
if not(int(self.get_parameter('Q_TILT_MASK')) & 1):
|
|
|
|
self.progress("output_motor_mask not in use")
|
|
|
|
return
|
|
|
|
self.progress("Testing output_motor_mask")
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
|
|
|
|
"""Default channel for Motor1 is 5"""
|
|
|
|
self.progress('Assert that SERVO5 is Motor1')
|
|
|
|
assert(33 == self.get_parameter('SERVO5_FUNCTION'))
|
|
|
|
|
|
|
|
modes = ('MANUAL', 'FBWA', 'QHOVER')
|
|
|
|
for mode in modes:
|
|
|
|
self.progress("Testing %s mode" % mode)
|
|
|
|
self.change_mode(mode)
|
|
|
|
self.arm_vehicle()
|
|
|
|
self.progress("Raising throttle")
|
|
|
|
self.set_rc(3, 1800)
|
|
|
|
self.progress("Waiting for Motor1 to start")
|
|
|
|
self.wait_servo_channel_value(5, 1100, comparator=operator.gt)
|
|
|
|
|
|
|
|
self.set_rc(3, 1000)
|
|
|
|
self.disarm_vehicle()
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
|
2018-03-05 11:14:34 -04:00
|
|
|
def fly_mission(self, filename, fence, height_accuracy=-1):
|
|
|
|
"""Fly a mission from a file."""
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Flying mission %s" % filename)
|
2018-11-09 08:32:02 -04:00
|
|
|
self.load_mission(filename)
|
2018-03-05 11:14:34 -04:00
|
|
|
self.mavproxy.send('fence load %s\n' % fence)
|
|
|
|
self.mavproxy.send('wp list\n')
|
|
|
|
self.mavproxy.expect('Requesting [0-9]+ waypoints')
|
2018-12-17 17:52:09 -04:00
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
2018-03-05 11:14:34 -04:00
|
|
|
self.mavproxy.send('mode AUTO\n')
|
|
|
|
self.wait_mode('AUTO')
|
2018-04-27 15:21:53 -03:00
|
|
|
self.wait_waypoint(1, 19, max_dist=60, timeout=1200)
|
|
|
|
|
2018-09-21 06:46:55 -03:00
|
|
|
self.mav.motors_disarmed_wait()
|
2018-03-05 11:14:34 -04:00
|
|
|
# wait for blood sample here
|
|
|
|
self.mavproxy.send('wp set 20\n')
|
2018-09-21 06:46:55 -03:00
|
|
|
self.wait_ready_to_arm()
|
2018-03-05 11:14:34 -04:00
|
|
|
self.arm_vehicle()
|
2018-04-27 15:21:53 -03:00
|
|
|
self.wait_waypoint(20, 34, max_dist=60, timeout=1200)
|
|
|
|
|
2018-09-21 06:46:55 -03:00
|
|
|
self.mav.motors_disarmed_wait()
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Mission OK")
|
2018-03-05 11:14:34 -04:00
|
|
|
|
2019-01-17 20:58:18 -04:00
|
|
|
def fly_qautotune(self):
|
|
|
|
self.change_mode("QHOVER")
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
|
|
|
self.set_rc(3, 1800)
|
|
|
|
self.wait_altitude(30,
|
|
|
|
40,
|
|
|
|
relative=True,
|
|
|
|
timeout=30)
|
|
|
|
self.set_rc(3, 1500)
|
|
|
|
self.change_mode("QAUTOTUNE")
|
|
|
|
tstart = self.get_sim_time()
|
|
|
|
sim_time_expected = 5000
|
|
|
|
deadline = tstart + sim_time_expected
|
|
|
|
while self.get_sim_time_cached() < deadline:
|
|
|
|
now = self.get_sim_time_cached()
|
|
|
|
m = self.mav.recv_match(type='STATUSTEXT',
|
|
|
|
blocking=True,
|
|
|
|
timeout=1)
|
|
|
|
if m is None:
|
|
|
|
continue
|
|
|
|
self.progress("STATUSTEXT (%u<%u): %s" % (now, deadline, m.text))
|
|
|
|
if "AutoTune: Success" in m.text:
|
2019-03-31 18:42:06 -03:00
|
|
|
break
|
|
|
|
self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart))
|
|
|
|
self.set_rc(3, 1200)
|
|
|
|
self.wait_altitude(-5, 1, relative=True, timeout=30)
|
|
|
|
while self.get_sim_time_cached() < deadline:
|
|
|
|
self.mavproxy.send('disarm\n')
|
|
|
|
try:
|
|
|
|
self.wait_text("AutoTune: Saved gains for Roll Pitch Yaw", timeout=0.5)
|
|
|
|
except AutoTestTimeoutException as e:
|
|
|
|
continue
|
|
|
|
break
|
2019-01-17 20:58:18 -04:00
|
|
|
self.mav.motors_disarmed_wait()
|
|
|
|
|
2019-02-28 19:04:23 -04:00
|
|
|
def test_pid_tuning(self):
|
|
|
|
self.change_mode("FBWA") # we don't update PIDs in MANUAL
|
|
|
|
super(AutoTestQuadPlane, self).test_pid_tuning()
|
|
|
|
|
2019-03-04 23:52:24 -04:00
|
|
|
def test_parameter_checks(self):
|
|
|
|
self.test_parameter_checks_poscontrol("Q_P")
|
|
|
|
|
2018-12-17 17:52:09 -04:00
|
|
|
def default_mode(self):
|
2019-02-11 13:55:18 -04:00
|
|
|
return "MANUAL"
|
2018-12-17 17:52:09 -04:00
|
|
|
|
2019-02-04 05:45:41 -04:00
|
|
|
def disabled_tests(self):
|
|
|
|
return {
|
|
|
|
"QAutoTune": "See https://github.com/ArduPilot/ardupilot/issues/10411",
|
|
|
|
}
|
|
|
|
|
2018-12-17 17:52:09 -04:00
|
|
|
def tests(self):
|
|
|
|
'''return list of all tests'''
|
|
|
|
m = os.path.join(testdir, "ArduPlane-Missions/Dalby-OBC2016.txt")
|
|
|
|
f = os.path.join(testdir,
|
|
|
|
"ArduPlane-Missions/Dalby-OBC2016-fence.txt")
|
|
|
|
|
|
|
|
ret = super(AutoTestQuadPlane, self).tests()
|
|
|
|
ret.extend([
|
2019-02-11 13:55:18 -04:00
|
|
|
("TestMotorMask", "Test output_motor_mask", self.test_motor_mask),
|
|
|
|
|
2019-01-17 20:58:18 -04:00
|
|
|
("QAutoTune", "Fly QAUTOTUNE mode", self.fly_qautotune),
|
|
|
|
|
2019-03-04 23:52:24 -04:00
|
|
|
("ParameterChecks",
|
|
|
|
"Test Arming Parameter Checks",
|
|
|
|
self.test_parameter_checks),
|
|
|
|
|
2018-12-17 17:52:09 -04:00
|
|
|
("Mission", "Dalby Mission",
|
|
|
|
lambda: self.fly_mission(m, f))
|
|
|
|
])
|
|
|
|
return ret
|