mirror of https://github.com/ArduPilot/ardupilot
Tools: Make soaring test a subclass of plane test.
This commit is contained in:
parent
4a39a43c10
commit
a4c5e12fac
|
@ -14,6 +14,8 @@ from common import AutoTestTimeoutException
|
|||
from common import NotAchievedException
|
||||
from common import PreconditionFailedException
|
||||
|
||||
import operator
|
||||
|
||||
# get location of scripts
|
||||
testdir = os.path.dirname(os.path.realpath(__file__))
|
||||
SITL_START_LOCATION = mavutil.location(-35.362938, 149.165085, 585, 354)
|
||||
|
@ -1746,3 +1748,121 @@ class AutoTestPlane(AutoTest):
|
|||
upload_logs=True))
|
||||
])
|
||||
return ret
|
||||
|
||||
class AutoTestSoaring(AutoTestPlane):
|
||||
|
||||
def log_name(self):
|
||||
return "Soaring"
|
||||
|
||||
def default_frame(self):
|
||||
return "plane-soaring"
|
||||
|
||||
def defaults_filepath(self):
|
||||
return os.path.join(testdir, 'default_params/plane.parm')
|
||||
|
||||
def fly_mission(self):
|
||||
|
||||
self.set_parameter("SOAR_ENABLE", 1)
|
||||
self.repeatedly_apply_parameter_file('default_params/plane-soaring.parm')
|
||||
self.load_mission('ArduPlane-Missions/CMAC-soar.txt')
|
||||
|
||||
|
||||
self.mavproxy.send("wp set 1\n")
|
||||
self.change_mode('AUTO')
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
|
||||
# Enable thermalling RC
|
||||
rc_chan = self.get_parameter('SOAR_ENABLE_CH')
|
||||
self.send_set_rc(rc_chan, 1900)
|
||||
|
||||
# Wait to detect thermal
|
||||
self.progress("Waiting for thermal")
|
||||
self.wait_mode('LOITER',timeout=600)
|
||||
|
||||
# Wait to climb to SOAR_ALT_MAX
|
||||
self.progress("Waiting for climb to max altitude")
|
||||
alt_max = self.get_parameter('SOAR_ALT_MAX')
|
||||
self.wait_altitude(alt_max-10, alt_max, timeout=600, relative=True)
|
||||
|
||||
# Wait for AUTO
|
||||
self.progress("Waiting for AUTO mode")
|
||||
self.wait_mode('AUTO')
|
||||
|
||||
# Disable thermals
|
||||
self.set_parameter("SIM_THML_SCENARI", 0)
|
||||
|
||||
|
||||
# Wait to descent to SOAR_ALT_MIN
|
||||
self.progress("Waiting for glide to min altitude")
|
||||
alt_min = self.get_parameter('SOAR_ALT_MIN')
|
||||
self.wait_altitude(alt_min-10, alt_min, timeout=600, relative=True)
|
||||
|
||||
self.progress("Waiting for throttle up")
|
||||
self.wait_servo_channel_value(3, 1200, timeout=2, comparator=operator.gt)
|
||||
|
||||
self.progress("Waiting for climb to cutoff altitude")
|
||||
alt_ctf = self.get_parameter('SOAR_ALT_CUTOFF')
|
||||
self.wait_altitude(alt_ctf-10, alt_ctf, timeout=600, relative=True)
|
||||
|
||||
# Now set FBWB mode
|
||||
self.change_mode('FBWB')
|
||||
self.delay_sim_time(5)
|
||||
|
||||
# Now disable soaring (should hold altitude)
|
||||
self.set_parameter("SOAR_ENABLE", 0)
|
||||
self.delay_sim_time(10)
|
||||
|
||||
#And reenable. This should force throttle-down
|
||||
self.set_parameter("SOAR_ENABLE", 1)
|
||||
self.delay_sim_time(10)
|
||||
|
||||
# Now wait for descent and check RTL
|
||||
self.wait_altitude(alt_min-10, alt_min, timeout=600, relative=True)
|
||||
|
||||
self.progress("Waiting for RTL")
|
||||
self.wait_mode('RTL')
|
||||
|
||||
alt_rtl = self.get_parameter('ALT_HOLD_RTL')/100
|
||||
|
||||
# Wait for climb to RTL.
|
||||
self.progress("Waiting for climb to RTL altitude")
|
||||
self.wait_altitude(alt_rtl-5, alt_rtl+5, timeout=60, relative=True)
|
||||
|
||||
# Back to auto
|
||||
self.change_mode('AUTO')
|
||||
|
||||
# Reenable thermals
|
||||
self.set_parameter("SIM_THML_SCENARI", 1)
|
||||
|
||||
# Disable soaring using RC channel.
|
||||
self.send_set_rc(rc_chan, 1100)
|
||||
|
||||
# Wait to get back to waypoint before thermal.
|
||||
self.progress("Waiting to get back to position")
|
||||
self.wait_current_waypoint(3,timeout=1200)
|
||||
|
||||
# Enable soaring with mode changes suppressed)
|
||||
self.send_set_rc(rc_chan, 1500)
|
||||
|
||||
# Make sure this causes throttle down.
|
||||
self.wait_servo_channel_value(3, 1200, timeout=2, comparator=operator.lt)
|
||||
|
||||
self.progress("Waiting for next WP with no loiter")
|
||||
self.wait_waypoint(4,4,timeout=1200,max_dist=120)
|
||||
|
||||
# Disarm
|
||||
self.disarm_vehicle()
|
||||
|
||||
self.progress("Mission OK")
|
||||
|
||||
def tests(self):
|
||||
'''return list of all tests'''
|
||||
ret = AutoTest.tests(self)
|
||||
|
||||
'''return list of all tests'''
|
||||
ret.extend([
|
||||
("Mission", "Soaring mission",
|
||||
self.fly_mission)
|
||||
])
|
||||
return ret
|
|
@ -24,7 +24,6 @@ import ardusub
|
|||
import antennatracker
|
||||
import quadplane
|
||||
import balancebot
|
||||
import soaring
|
||||
|
||||
import examples
|
||||
from pysim import util
|
||||
|
@ -306,7 +305,7 @@ tester_class_map = {
|
|||
"test.Helicopter": arducopter.AutoTestHeli,
|
||||
"test.Sub": ardusub.AutoTestSub,
|
||||
"test.Tracker": antennatracker.AutoTestTracker,
|
||||
"test.Soaring": soaring.AutoTestSoaring,
|
||||
"test.Soaring": arduplane.AutoTestSoaring,
|
||||
}
|
||||
|
||||
def run_specific_test(step, *args, **kwargs):
|
||||
|
|
|
@ -1011,7 +1011,7 @@ class AutoTest(ABC):
|
|||
vehicle = self.log_name()
|
||||
if vehicle == "HeliCopter":
|
||||
vehicle = "ArduCopter"
|
||||
if vehicle == "QuadPlane":
|
||||
if vehicle == "QuadPlane" or vehicle =="Soaring":
|
||||
vehicle = "ArduPlane"
|
||||
cmd = [param_parse_filepath, '--vehicle', vehicle]
|
||||
# cmd.append("--verbose")
|
||||
|
@ -1074,6 +1074,8 @@ class AutoTest(ABC):
|
|||
dirname = "ArduPlane"
|
||||
elif dirname == "HeliCopter":
|
||||
dirname = "ArduCopter"
|
||||
elif dirname == "Soaring":
|
||||
dirname = "ArduPlane"
|
||||
return os.path.join(self.rootdir(), dirname)
|
||||
|
||||
def all_log_format_ids(self):
|
||||
|
@ -1296,6 +1298,7 @@ class AutoTest(ABC):
|
|||
"HeliCopter": "Copter",
|
||||
"ArduPlane": "Plane",
|
||||
"QuadPlane": "Plane",
|
||||
"Soaring": "Plane",
|
||||
"APMrover2": "Rover",
|
||||
"AntennaTracker": "Tracker",
|
||||
"ArduSub": "Sub",
|
||||
|
|
|
@ -1,184 +0,0 @@
|
|||
#!/usr/bin/env python
|
||||
|
||||
# Fly ArduSoar in SITL
|
||||
from __future__ import print_function
|
||||
import os
|
||||
import pexpect
|
||||
from pymavlink import mavutil
|
||||
|
||||
from common import AutoTest
|
||||
from common import AutoTestTimeoutException
|
||||
|
||||
from pysim import util
|
||||
from pysim import vehicleinfo
|
||||
import operator
|
||||
|
||||
|
||||
# get location of scripts
|
||||
testdir = os.path.dirname(os.path.realpath(__file__))
|
||||
SITL_START_LOCATION = mavutil.location(-35.362938, 149.165085, 585, 354)
|
||||
MISSION = 'ArduPlane-Missions/CMAC-soar.txt'
|
||||
WIND = "0,180,0.2" # speed,direction,variance
|
||||
|
||||
|
||||
class AutoTestSoaring(AutoTest):
|
||||
|
||||
def default_frame(self):
|
||||
return "plane-soaring"
|
||||
|
||||
def test_filepath(self):
|
||||
return os.path.realpath(__file__)
|
||||
|
||||
def sitl_start_location(self):
|
||||
return SITL_START_LOCATION
|
||||
|
||||
def log_name(self):
|
||||
return "Soaring"
|
||||
|
||||
def apply_defaultfile_parameters(self):
|
||||
# plane passes in a defaults_file in place of applying
|
||||
# parameters afterwards.
|
||||
pass
|
||||
|
||||
def defaults_filepath(self):
|
||||
vinfo = vehicleinfo.VehicleInfo()
|
||||
defaults_file = vinfo.options["ArduPlane"]["frames"][self.frame]["default_params_filename"]
|
||||
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)
|
||||
|
||||
def is_plane(self):
|
||||
return True
|
||||
|
||||
def get_stick_arming_channel(self):
|
||||
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)
|
||||
|
||||
def fly_mission(self):
|
||||
|
||||
self.set_parameter("SOAR_ENABLE", 1)
|
||||
self.repeatedly_apply_parameter_file('default_params/plane-soaring.parm')
|
||||
self.load_mission(MISSION)
|
||||
|
||||
|
||||
self.mavproxy.send("wp set 1\n")
|
||||
self.change_mode('AUTO')
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
|
||||
# Enable thermalling RC
|
||||
rc_chan = self.get_parameter('SOAR_ENABLE_CH')
|
||||
self.send_set_rc(rc_chan, 1900)
|
||||
|
||||
# Wait to detect thermal
|
||||
self.progress("Waiting for thermal")
|
||||
self.wait_mode('LOITER',timeout=600)
|
||||
|
||||
# Wait to climb to SOAR_ALT_MAX
|
||||
self.progress("Waiting for climb to max altitude")
|
||||
alt_max = self.get_parameter('SOAR_ALT_MAX')
|
||||
self.wait_altitude(alt_max-10, alt_max, timeout=600, relative=True)
|
||||
|
||||
# Wait for AUTO
|
||||
self.progress("Waiting for AUTO mode")
|
||||
self.wait_mode('AUTO')
|
||||
|
||||
# Disable thermals
|
||||
self.set_parameter("SIM_THML_SCENARI", 0)
|
||||
|
||||
|
||||
# Wait to descent to SOAR_ALT_MIN
|
||||
self.progress("Waiting for glide to min altitude")
|
||||
alt_min = self.get_parameter('SOAR_ALT_MIN')
|
||||
self.wait_altitude(alt_min-10, alt_min, timeout=600, relative=True)
|
||||
|
||||
self.progress("Waiting for throttle up")
|
||||
self.wait_servo_channel_value(3, 1200, timeout=2, comparator=operator.gt)
|
||||
|
||||
self.progress("Waiting for climb to cutoff altitude")
|
||||
alt_ctf = self.get_parameter('SOAR_ALT_CUTOFF')
|
||||
self.wait_altitude(alt_ctf-10, alt_ctf, timeout=600, relative=True)
|
||||
|
||||
# Now set FBWB mode
|
||||
self.change_mode('FBWB')
|
||||
self.delay_sim_time(5)
|
||||
|
||||
# Now disable soaring (should hold altitude)
|
||||
self.set_parameter("SOAR_ENABLE", 0)
|
||||
self.delay_sim_time(10)
|
||||
|
||||
#And reenable. This should force throttle-down
|
||||
self.set_parameter("SOAR_ENABLE", 1)
|
||||
self.delay_sim_time(10)
|
||||
|
||||
# Now wait for descent and check RTL
|
||||
self.wait_altitude(alt_min-10, alt_min, timeout=600, relative=True)
|
||||
|
||||
self.progress("Waiting for RTL")
|
||||
self.wait_mode('RTL')
|
||||
|
||||
alt_rtl = self.get_parameter('ALT_HOLD_RTL')/100
|
||||
|
||||
# Wait for climb to RTL.
|
||||
self.progress("Waiting for climb to RTL altitude")
|
||||
self.wait_altitude(alt_rtl-5, alt_rtl+5, timeout=60, relative=True)
|
||||
|
||||
# Back to auto
|
||||
self.change_mode('AUTO')
|
||||
|
||||
# Reenable thermals
|
||||
self.set_parameter("SIM_THML_SCENARI", 1)
|
||||
|
||||
# Disable soaring using RC channel.
|
||||
self.send_set_rc(rc_chan, 1100)
|
||||
|
||||
# Wait to get back to waypoint before thermal.
|
||||
self.progress("Waiting to get back to position")
|
||||
self.wait_current_waypoint(3,timeout=1200)
|
||||
|
||||
# Enable soaring with mode changes suppressed)
|
||||
self.send_set_rc(rc_chan, 1500)
|
||||
|
||||
# Make sure this causes throttle down.
|
||||
self.wait_servo_channel_value(3, 1200, timeout=2, comparator=operator.lt)
|
||||
|
||||
self.progress("Waiting for next WP with no loiter")
|
||||
self.wait_waypoint(4,4,timeout=1200,max_dist=120)
|
||||
|
||||
# Disarm
|
||||
self.disarm_vehicle()
|
||||
|
||||
self.progress("Mission OK")
|
||||
|
||||
def default_mode(self):
|
||||
return "MANUAL"
|
||||
|
||||
def test_pid_tuning(self):
|
||||
# Do nothing, covered by fly.ArduPlane
|
||||
self.progress("Skipped")
|
||||
|
||||
def test_arm_feature(self):
|
||||
# Do nothing, covered by fly.ArduPlane
|
||||
self.progress("Skipped")
|
||||
|
||||
def fly_test_set_home(self):
|
||||
# Do nothing, covered by fly.ArduPlane
|
||||
self.progress("Skipped")
|
||||
|
||||
def tests(self):
|
||||
'''return list of all tests'''
|
||||
|
||||
ret = super(AutoTestSoaring, self).tests()
|
||||
ret.extend([
|
||||
("Mission", "CMAC Mission",
|
||||
self.fly_mission)
|
||||
])
|
||||
return ret
|
Loading…
Reference in New Issue