2021-02-11 22:44:28 -04:00
|
|
|
'''
|
|
|
|
Fly ArduPlane in SITL
|
|
|
|
|
|
|
|
AP_FLAKE8_CLEAN
|
|
|
|
'''
|
|
|
|
|
2016-11-08 07:06:05 -04:00
|
|
|
from __future__ import print_function
|
2016-07-31 07:22:06 -03:00
|
|
|
import math
|
|
|
|
import os
|
2021-07-31 00:55:49 -03:00
|
|
|
import signal
|
2021-10-10 22:06:48 -03:00
|
|
|
import sys
|
2020-02-28 20:14:11 -04:00
|
|
|
import time
|
2016-07-31 07:22:06 -03:00
|
|
|
|
2018-05-31 07:27:41 -03:00
|
|
|
from pymavlink import quaternion
|
2021-03-14 22:38:08 -03:00
|
|
|
from pymavlink import mavextra
|
2013-06-18 03:27:21 -03:00
|
|
|
from pymavlink import mavutil
|
2016-07-31 07:22:06 -03:00
|
|
|
|
2021-01-09 06:04:29 -04:00
|
|
|
from pymavlink.rotmat import Vector3
|
2022-02-23 08:07:15 -04:00
|
|
|
|
|
|
|
import vehicle_test_suite
|
|
|
|
|
|
|
|
from vehicle_test_suite import AutoTestTimeoutException
|
|
|
|
from vehicle_test_suite import NotAchievedException
|
|
|
|
from vehicle_test_suite import OldpymavlinkException
|
|
|
|
from vehicle_test_suite import PreconditionFailedException
|
|
|
|
from vehicle_test_suite import Test
|
|
|
|
from vehicle_test_suite import WaitModeTimeout
|
|
|
|
|
2021-06-20 22:33:12 -03:00
|
|
|
from pysim import vehicleinfo
|
2023-07-29 00:04:29 -03:00
|
|
|
from pysim import util
|
2018-03-14 08:08:53 -03:00
|
|
|
|
2020-04-05 21:45:02 -03:00
|
|
|
import operator
|
|
|
|
|
2011-11-12 07:13:17 -04:00
|
|
|
# get location of scripts
|
2016-07-31 07:22:06 -03:00
|
|
|
testdir = os.path.dirname(os.path.realpath(__file__))
|
2019-02-15 20:46:33 -04:00
|
|
|
SITL_START_LOCATION = mavutil.location(-35.362938, 149.165085, 585, 354)
|
2016-07-31 07:22:06 -03:00
|
|
|
WIND = "0,180,0.2" # speed,direction,variance
|
2011-11-12 07:13:17 -04:00
|
|
|
|
|
|
|
|
2022-02-23 08:07:15 -04:00
|
|
|
class AutoTestPlane(vehicle_test_suite.TestSuite):
|
2018-10-10 10:06:01 -03:00
|
|
|
@staticmethod
|
|
|
|
def get_not_armable_mode_list():
|
|
|
|
return []
|
|
|
|
|
|
|
|
@staticmethod
|
|
|
|
def get_not_disarmed_settable_modes_list():
|
|
|
|
return ["FOLLOW"]
|
|
|
|
|
|
|
|
@staticmethod
|
|
|
|
def get_no_position_not_settable_modes_list():
|
|
|
|
return []
|
|
|
|
|
|
|
|
@staticmethod
|
|
|
|
def get_position_armable_modes_list():
|
|
|
|
return ["GUIDED", "AUTO"]
|
|
|
|
|
|
|
|
@staticmethod
|
|
|
|
def get_normal_armable_modes_list():
|
|
|
|
return ["MANUAL", "STABILIZE", "ACRO"]
|
2019-03-09 00:20:36 -04:00
|
|
|
|
|
|
|
def log_name(self):
|
|
|
|
return "ArduPlane"
|
|
|
|
|
2022-06-10 21:52:34 -03:00
|
|
|
def default_speedup(self):
|
|
|
|
return 100
|
|
|
|
|
2019-03-09 00:20:36 -04:00
|
|
|
def test_filepath(self):
|
|
|
|
return os.path.realpath(__file__)
|
2018-03-15 08:54:34 -03:00
|
|
|
|
2019-02-15 20:46:33 -04:00
|
|
|
def sitl_start_location(self):
|
|
|
|
return SITL_START_LOCATION
|
|
|
|
|
2019-03-09 00:20:36 -04:00
|
|
|
def defaults_filepath(self):
|
|
|
|
return os.path.join(testdir, 'default_params/plane-jsbsim.parm')
|
|
|
|
|
2020-03-10 09:18:59 -03:00
|
|
|
def set_current_test_name(self, name):
|
|
|
|
self.current_test_name_directory = "ArduPlane_Tests/" + name + "/"
|
|
|
|
|
2019-03-09 00:20:36 -04:00
|
|
|
def default_frame(self):
|
|
|
|
return "plane-elevrev"
|
|
|
|
|
|
|
|
def apply_defaultfile_parameters(self):
|
2020-04-13 23:08:19 -03:00
|
|
|
# plane passes in a defaults_filepath in place of applying
|
2019-03-09 00:20:36 -04:00
|
|
|
# parameters afterwards.
|
|
|
|
pass
|
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)
|
|
|
|
|
2023-08-29 18:36:37 -03:00
|
|
|
def takeoff(self, alt=150, alt_max=None, relative=True, mode=None, timeout=None):
|
2019-04-25 21:57:19 -03:00
|
|
|
"""Takeoff to altitude."""
|
|
|
|
|
2023-08-29 18:36:37 -03:00
|
|
|
if mode == "TAKEOFF":
|
|
|
|
return self.takeoff_in_TAKEOFF(alt=alt, relative=relative, timeout=timeout)
|
|
|
|
|
|
|
|
return self.takeoff_in_FBWA(alt=alt, alt_max=alt_max, relative=relative, timeout=timeout)
|
|
|
|
|
|
|
|
def takeoff_in_TAKEOFF(self, alt=150, relative=True, mode=None, alt_epsilon=2, timeout=None):
|
|
|
|
if relative is not True:
|
|
|
|
raise ValueError("Only relative alt supported ATM")
|
|
|
|
self.change_mode("TAKEOFF")
|
|
|
|
self.context_push()
|
|
|
|
self.set_parameter('TKOFF_ALT', alt)
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
|
|
|
self.wait_altitude(alt-alt_epsilon, alt+alt_epsilon, relative=True, timeout=timeout)
|
|
|
|
self.context_pop()
|
|
|
|
|
|
|
|
def takeoff_in_FBWA(self, alt=150, alt_max=None, relative=True, mode=None, timeout=30):
|
2019-04-25 21:57:19 -03:00
|
|
|
if alt_max is None:
|
|
|
|
alt_max = alt + 30
|
2018-03-05 11:14:34 -04:00
|
|
|
|
2019-09-24 23:25:55 -03:00
|
|
|
self.change_mode("FBWA")
|
2018-03-05 11:14:34 -04:00
|
|
|
|
2018-08-13 08:07:34 -03:00
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
|
|
|
|
2018-03-05 11:14:34 -04:00
|
|
|
# some rudder to counteract the prop torque
|
|
|
|
self.set_rc(4, 1700)
|
|
|
|
|
|
|
|
# some up elevator to keep the tail down
|
|
|
|
self.set_rc(2, 1200)
|
|
|
|
|
|
|
|
# get it moving a bit first
|
|
|
|
self.set_rc(3, 1300)
|
2019-02-21 23:51:05 -04:00
|
|
|
self.wait_groundspeed(6, 100)
|
2018-03-05 11:14:34 -04:00
|
|
|
|
|
|
|
# a bit faster again, straighten rudder
|
2021-02-13 03:46:29 -04:00
|
|
|
self.set_rc_from_map({
|
|
|
|
3: 1600,
|
|
|
|
4: 1500,
|
|
|
|
})
|
2019-02-21 23:51:05 -04:00
|
|
|
self.wait_groundspeed(12, 100)
|
2018-03-05 11:14:34 -04:00
|
|
|
|
|
|
|
# hit the gas harder now, and give it some more elevator
|
2021-02-13 03:46:29 -04:00
|
|
|
self.set_rc_from_map({
|
|
|
|
2: 1100,
|
|
|
|
3: 2000,
|
|
|
|
})
|
2018-03-05 11:14:34 -04:00
|
|
|
|
|
|
|
# gain a bit of altitude
|
2023-08-29 18:36:37 -03:00
|
|
|
self.wait_altitude(alt, alt_max, timeout=timeout, relative=relative)
|
2016-07-31 07:22:06 -03:00
|
|
|
|
2018-03-05 11:14:34 -04:00
|
|
|
# level off
|
|
|
|
self.set_rc(2, 1500)
|
2013-07-16 00:23:48 -03:00
|
|
|
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("TAKEOFF COMPLETE")
|
2013-07-16 00:23:48 -03:00
|
|
|
|
2018-03-05 11:14:34 -04:00
|
|
|
def fly_left_circuit(self):
|
|
|
|
"""Fly a left circuit, 200m on a side."""
|
2020-12-28 21:30:53 -04:00
|
|
|
self.change_mode('FBWA')
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(3, 2000)
|
2018-04-27 15:21:53 -03:00
|
|
|
self.wait_level_flight()
|
2018-03-14 08:08:53 -03:00
|
|
|
|
|
|
|
self.progress("Flying left circuit")
|
2018-03-05 11:14:34 -04:00
|
|
|
# do 4 turns
|
|
|
|
for i in range(0, 4):
|
|
|
|
# hard left
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Starting turn %u" % i)
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(1, 1000)
|
2018-04-27 15:21:53 -03:00
|
|
|
self.wait_heading(270 - (90*i), accuracy=10)
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(1, 1500)
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Starting leg %u" % i)
|
2018-04-27 15:21:53 -03:00
|
|
|
self.wait_distance(100, accuracy=20)
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Circuit complete")
|
2018-03-05 11:14:34 -04:00
|
|
|
|
|
|
|
def fly_RTL(self):
|
|
|
|
"""Fly to home."""
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Flying home in RTL")
|
2020-12-28 21:30:53 -04:00
|
|
|
self.change_mode('RTL')
|
2018-04-27 15:21:53 -03:00
|
|
|
self.wait_location(self.homeloc,
|
2018-05-09 00:32:23 -03:00
|
|
|
accuracy=120,
|
|
|
|
target_altitude=self.homeloc.alt+100,
|
|
|
|
height_accuracy=20,
|
|
|
|
timeout=180)
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("RTL Complete")
|
2018-03-05 11:14:34 -04:00
|
|
|
|
2022-07-27 22:06:40 -03:00
|
|
|
def NeedEKFToArm(self):
|
|
|
|
"""Ensure the EKF must be healthy for the vehicle to arm."""
|
2020-12-10 04:06:22 -04:00
|
|
|
self.progress("Ensuring we need EKF to be healthy to arm")
|
2022-07-27 22:06:40 -03:00
|
|
|
self.set_parameter("SIM_GPS_DISABLE", 1)
|
2020-12-10 04:06:22 -04:00
|
|
|
self.context_collect("STATUSTEXT")
|
|
|
|
tstart = self.get_sim_time()
|
|
|
|
success = False
|
|
|
|
while not success:
|
|
|
|
if self.get_sim_time_cached() - tstart > 60:
|
|
|
|
raise NotAchievedException("Did not get correct failure reason")
|
2022-12-15 06:14:41 -04:00
|
|
|
self.run_cmd_run_prearms()
|
2020-12-10 04:06:22 -04:00
|
|
|
try:
|
2022-07-27 22:06:40 -03:00
|
|
|
self.wait_statustext(".*AHRS: not using configured AHRS type.*", timeout=1, check_context=True, regex=True)
|
2020-12-10 04:06:22 -04:00
|
|
|
success = True
|
|
|
|
continue
|
|
|
|
except AutoTestTimeoutException:
|
|
|
|
pass
|
|
|
|
|
2022-07-27 22:06:40 -03:00
|
|
|
self.set_parameter("SIM_GPS_DISABLE", 0)
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
|
2018-03-05 11:14:34 -04:00
|
|
|
def fly_LOITER(self, num_circles=4):
|
|
|
|
"""Loiter where we are."""
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Testing LOITER for %u turns" % num_circles)
|
2021-02-19 05:35:07 -04:00
|
|
|
self.change_mode('LOITER')
|
2018-03-05 11:14:34 -04:00
|
|
|
|
|
|
|
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
|
|
|
|
initial_alt = m.alt
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Initial altitude %u\n" % initial_alt)
|
2018-03-05 11:14:34 -04:00
|
|
|
|
|
|
|
while num_circles > 0:
|
2018-04-27 15:21:53 -03:00
|
|
|
self.wait_heading(0, accuracy=10, timeout=60)
|
|
|
|
self.wait_heading(180, accuracy=10, timeout=60)
|
2018-03-05 11:14:34 -04:00
|
|
|
num_circles -= 1
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Loiter %u circles left" % num_circles)
|
2018-03-05 11:14:34 -04:00
|
|
|
|
|
|
|
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
|
|
|
|
final_alt = m.alt
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Final altitude %u initial %u\n" %
|
|
|
|
(final_alt, initial_alt))
|
2018-03-05 11:14:34 -04:00
|
|
|
|
2021-02-19 05:35:07 -04:00
|
|
|
self.change_mode('FBWA')
|
2018-03-05 11:14:34 -04:00
|
|
|
|
|
|
|
if abs(final_alt - initial_alt) > 20:
|
2018-10-17 23:55:16 -03:00
|
|
|
raise NotAchievedException("Failed to maintain altitude")
|
2013-07-16 00:23:48 -03:00
|
|
|
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Completed Loiter OK")
|
2013-07-16 00:23:48 -03:00
|
|
|
|
2018-03-05 11:14:34 -04:00
|
|
|
def fly_CIRCLE(self, num_circles=1):
|
|
|
|
"""Circle where we are."""
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Testing CIRCLE for %u turns" % num_circles)
|
2021-02-19 05:35:07 -04:00
|
|
|
self.change_mode('CIRCLE')
|
2013-07-16 00:23:48 -03:00
|
|
|
|
2018-03-05 11:14:34 -04:00
|
|
|
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
|
|
|
|
initial_alt = m.alt
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Initial altitude %u\n" % initial_alt)
|
2013-07-16 00:23:48 -03:00
|
|
|
|
2018-03-05 11:14:34 -04:00
|
|
|
while num_circles > 0:
|
2018-04-27 15:21:53 -03:00
|
|
|
self.wait_heading(0, accuracy=10, timeout=60)
|
|
|
|
self.wait_heading(180, accuracy=10, timeout=60)
|
2018-03-05 11:14:34 -04:00
|
|
|
num_circles -= 1
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("CIRCLE %u circles left" % num_circles)
|
2011-11-12 07:13:17 -04:00
|
|
|
|
2018-03-05 11:14:34 -04:00
|
|
|
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
|
|
|
|
final_alt = m.alt
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Final altitude %u initial %u\n" %
|
|
|
|
(final_alt, initial_alt))
|
2011-11-12 07:13:17 -04:00
|
|
|
|
2021-02-19 05:35:07 -04:00
|
|
|
self.change_mode('FBWA')
|
2011-11-12 07:13:17 -04:00
|
|
|
|
2018-03-05 11:14:34 -04:00
|
|
|
if abs(final_alt - initial_alt) > 20:
|
2018-10-17 23:55:16 -03:00
|
|
|
raise NotAchievedException("Failed to maintain altitude")
|
2011-11-13 21:59:59 -04:00
|
|
|
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Completed CIRCLE OK")
|
2018-03-05 11:14:34 -04:00
|
|
|
|
|
|
|
def wait_level_flight(self, accuracy=5, timeout=30):
|
|
|
|
"""Wait for level flight."""
|
|
|
|
tstart = self.get_sim_time()
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Waiting for level flight")
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(1, 1500)
|
|
|
|
self.set_rc(2, 1500)
|
|
|
|
self.set_rc(4, 1500)
|
2019-03-07 18:34:09 -04:00
|
|
|
while self.get_sim_time_cached() < tstart + timeout:
|
2018-03-05 11:14:34 -04:00
|
|
|
m = self.mav.recv_match(type='ATTITUDE', blocking=True)
|
|
|
|
roll = math.degrees(m.roll)
|
|
|
|
pitch = math.degrees(m.pitch)
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Roll=%.1f Pitch=%.1f" % (roll, pitch))
|
2018-03-05 11:14:34 -04:00
|
|
|
if math.fabs(roll) <= accuracy and math.fabs(pitch) <= accuracy:
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Attained level flight")
|
2018-04-27 15:21:53 -03:00
|
|
|
return
|
2018-10-17 23:55:16 -03:00
|
|
|
raise NotAchievedException("Failed to attain level flight")
|
2011-11-13 21:59:59 -04:00
|
|
|
|
2018-03-05 11:14:34 -04:00
|
|
|
def change_altitude(self, altitude, accuracy=30):
|
|
|
|
"""Get to a given altitude."""
|
2021-02-19 05:35:07 -04:00
|
|
|
self.change_mode('FBWA')
|
2018-03-05 11:14:34 -04:00
|
|
|
alt_error = self.mav.messages['VFR_HUD'].alt - altitude
|
|
|
|
if alt_error > 0:
|
|
|
|
self.set_rc(2, 2000)
|
|
|
|
else:
|
|
|
|
self.set_rc(2, 1000)
|
2018-04-27 15:21:53 -03:00
|
|
|
self.wait_altitude(altitude-accuracy/2, altitude+accuracy/2)
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(2, 1500)
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Reached target altitude at %u" %
|
|
|
|
self.mav.messages['VFR_HUD'].alt)
|
2018-03-05 11:14:34 -04:00
|
|
|
return self.wait_level_flight()
|
|
|
|
|
|
|
|
def axial_left_roll(self, count=1):
|
|
|
|
"""Fly a left axial roll."""
|
|
|
|
# full throttle!
|
|
|
|
self.set_rc(3, 2000)
|
2018-04-27 15:21:53 -03:00
|
|
|
self.change_altitude(self.homeloc.alt+300)
|
2013-07-16 00:23:48 -03:00
|
|
|
|
2018-03-05 11:14:34 -04:00
|
|
|
# fly the roll in manual
|
2020-12-28 21:30:53 -04:00
|
|
|
self.change_mode('MANUAL')
|
2018-03-05 11:14:34 -04:00
|
|
|
|
|
|
|
while count > 0:
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Starting roll")
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(1, 1000)
|
2018-04-27 15:21:53 -03:00
|
|
|
try:
|
|
|
|
self.wait_roll(-150, accuracy=90)
|
|
|
|
self.wait_roll(150, accuracy=90)
|
|
|
|
self.wait_roll(0, accuracy=90)
|
|
|
|
except Exception as e:
|
2018-05-09 00:32:23 -03:00
|
|
|
self.set_rc(1, 1500)
|
2018-04-27 15:21:53 -03:00
|
|
|
raise e
|
2018-03-05 11:14:34 -04:00
|
|
|
count -= 1
|
|
|
|
|
|
|
|
# back to FBWA
|
|
|
|
self.set_rc(1, 1500)
|
2020-12-28 21:30:53 -04:00
|
|
|
self.change_mode('FBWA')
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(3, 1700)
|
|
|
|
return self.wait_level_flight()
|
|
|
|
|
|
|
|
def inside_loop(self, count=1):
|
|
|
|
"""Fly a inside loop."""
|
|
|
|
# full throttle!
|
|
|
|
self.set_rc(3, 2000)
|
2018-04-27 15:21:53 -03:00
|
|
|
self.change_altitude(self.homeloc.alt+300)
|
2018-03-05 11:14:34 -04:00
|
|
|
# fly the loop in manual
|
2020-12-28 21:30:53 -04:00
|
|
|
self.change_mode('MANUAL')
|
2018-03-05 11:14:34 -04:00
|
|
|
|
|
|
|
while count > 0:
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Starting loop")
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(2, 1000)
|
2018-04-27 15:21:53 -03:00
|
|
|
self.wait_pitch(-60, accuracy=20)
|
|
|
|
self.wait_pitch(0, accuracy=20)
|
2018-03-05 11:14:34 -04:00
|
|
|
count -= 1
|
|
|
|
|
|
|
|
# back to FBWA
|
|
|
|
self.set_rc(2, 1500)
|
2020-12-28 21:30:53 -04:00
|
|
|
self.change_mode('FBWA')
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(3, 1700)
|
|
|
|
return self.wait_level_flight()
|
|
|
|
|
2019-03-10 04:44:38 -03:00
|
|
|
def set_attitude_target(self, tolerance=10):
|
2018-05-31 07:27:41 -03:00
|
|
|
"""Test setting of attitude target in guided mode."""
|
2019-03-10 04:44:38 -03:00
|
|
|
self.change_mode("GUIDED")
|
2018-05-31 07:27:41 -03:00
|
|
|
|
2023-04-14 14:50:58 -03:00
|
|
|
steps = [{"name": "roll-over", "roll": 60, "pitch": 0, "yaw": 0, "throttle": 0, "type_mask": 0b10000001},
|
|
|
|
{"name": "roll-back", "roll": 0, "pitch": 0, "yaw": 0, "throttle": 0, "type_mask": 0b10000001},
|
|
|
|
{"name": "pitch-up+throttle", "roll": 0, "pitch": 20, "yaw": 0, "throttle": 1, "type_mask": 0b11000010},
|
|
|
|
{"name": "pitch-back", "roll": 0, "pitch": 0, "yaw": 0, "throttle": 0, "type_mask": 0b10000010}]
|
2018-05-31 07:27:41 -03:00
|
|
|
|
2023-04-14 14:50:58 -03:00
|
|
|
state_wait = "wait"
|
|
|
|
state_hold = "hold"
|
2018-05-31 07:27:41 -03:00
|
|
|
try:
|
2023-04-14 14:50:58 -03:00
|
|
|
for step in steps:
|
|
|
|
step_start = self.get_sim_time_cached()
|
|
|
|
state = state_wait
|
|
|
|
state_start = self.get_sim_time_cached()
|
|
|
|
while True:
|
|
|
|
m = self.mav.recv_match(type='ATTITUDE',
|
|
|
|
blocking=True,
|
|
|
|
timeout=0.1)
|
|
|
|
now = self.get_sim_time_cached()
|
|
|
|
if now - step_start > 30:
|
|
|
|
raise AutoTestTimeoutException("Manuevers not completed")
|
|
|
|
if m is None:
|
|
|
|
continue
|
|
|
|
|
|
|
|
angle_error = 0
|
|
|
|
if (step["type_mask"] & 0b00000001) or (step["type_mask"] == 0b10000000):
|
|
|
|
angle_error += abs(math.degrees(m.roll) - step["roll"])
|
|
|
|
|
|
|
|
if (step["type_mask"] & 0b00000010) or (step["type_mask"] == 0b10000000):
|
|
|
|
angle_error += abs(math.degrees(m.pitch) - step["pitch"])
|
|
|
|
|
|
|
|
if (step["type_mask"] & 0b00000100) or (step["type_mask"] == 0b10000000):
|
|
|
|
# Strictly we should angle wrap, by plane doesn't support yaw correctly anyway so its not tested here
|
|
|
|
angle_error += abs(math.degrees(m.yaw) - step["yaw"])
|
|
|
|
|
|
|
|
# Note were not checking throttle, however the SITL plane needs full throttle to meet the
|
|
|
|
# target pitch attitude, Pitch test will fail without throttle override
|
|
|
|
|
|
|
|
if state == state_wait:
|
|
|
|
# Reduced tolerance for initial trigger
|
|
|
|
if angle_error < (tolerance * 0.25):
|
|
|
|
state = state_hold
|
|
|
|
state_start = now
|
|
|
|
|
|
|
|
# Allow 10 seconds to reach attitude
|
|
|
|
if (now - state_start) > 10:
|
|
|
|
raise NotAchievedException(step["name"] + ": Failed to get to set attitude")
|
|
|
|
|
|
|
|
elif state == state_hold:
|
|
|
|
# Give 2 seconds to stabilize
|
|
|
|
if (now - state_start) > 2 and not (angle_error < tolerance):
|
|
|
|
raise NotAchievedException(step["name"] + ": Failed to hold set attitude")
|
|
|
|
|
|
|
|
# Hold for 10 seconds
|
|
|
|
if (now - state_start) > 12:
|
|
|
|
# move onto next step
|
|
|
|
self.progress("%s Done" % (step["name"]))
|
|
|
|
break
|
|
|
|
|
|
|
|
self.progress("%s %s error: %f" % (step["name"], state, angle_error))
|
|
|
|
|
|
|
|
time_boot_millis = 0 # FIXME
|
|
|
|
target_system = 1 # FIXME
|
|
|
|
target_component = 1 # FIXME
|
|
|
|
type_mask = step["type_mask"] ^ 0xFF # FIXME
|
|
|
|
# attitude in radians:
|
|
|
|
q = quaternion.Quaternion([math.radians(step["roll"]),
|
|
|
|
math.radians(step["pitch"]),
|
|
|
|
math.radians(step["yaw"])])
|
|
|
|
self.mav.mav.set_attitude_target_send(time_boot_millis,
|
|
|
|
target_system,
|
|
|
|
target_component,
|
|
|
|
type_mask,
|
|
|
|
q,
|
|
|
|
0, # roll rate, not used in AP
|
|
|
|
0, # pitch rate, not used in AP
|
|
|
|
0, # yaw rate, not used in AP
|
|
|
|
step["throttle"])
|
2018-05-31 07:27:41 -03:00
|
|
|
except Exception as e:
|
2021-02-19 05:35:07 -04:00
|
|
|
self.change_mode('FBWA')
|
2018-05-31 07:27:41 -03:00
|
|
|
self.set_rc(3, 1700)
|
|
|
|
raise e
|
|
|
|
|
|
|
|
# back to FBWA
|
2021-02-19 05:35:07 -04:00
|
|
|
self.change_mode('FBWA')
|
2018-05-31 07:27:41 -03:00
|
|
|
self.set_rc(3, 1700)
|
|
|
|
self.wait_level_flight()
|
|
|
|
|
2018-03-05 11:14:34 -04:00
|
|
|
def test_stabilize(self, count=1):
|
|
|
|
"""Fly stabilize mode."""
|
|
|
|
# full throttle!
|
|
|
|
self.set_rc(3, 2000)
|
|
|
|
self.set_rc(2, 1300)
|
2018-04-27 15:21:53 -03:00
|
|
|
self.change_altitude(self.homeloc.alt+300)
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(2, 1500)
|
|
|
|
|
2021-02-18 00:12:25 -04:00
|
|
|
self.change_mode('STABILIZE')
|
2018-03-05 11:14:34 -04:00
|
|
|
|
|
|
|
while count > 0:
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Starting roll")
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(1, 2000)
|
2018-04-27 15:21:53 -03:00
|
|
|
self.wait_roll(-150, accuracy=90)
|
|
|
|
self.wait_roll(150, accuracy=90)
|
|
|
|
self.wait_roll(0, accuracy=90)
|
2018-03-05 11:14:34 -04:00
|
|
|
count -= 1
|
|
|
|
|
|
|
|
self.set_rc(1, 1500)
|
2018-04-27 15:21:53 -03:00
|
|
|
self.wait_roll(0, accuracy=5)
|
2013-07-16 00:23:48 -03:00
|
|
|
|
2018-03-05 11:14:34 -04:00
|
|
|
# back to FBWA
|
2021-02-19 05:35:07 -04:00
|
|
|
self.change_mode('FBWA')
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(3, 1700)
|
|
|
|
return self.wait_level_flight()
|
|
|
|
|
|
|
|
def test_acro(self, count=1):
|
|
|
|
"""Fly ACRO mode."""
|
|
|
|
# full throttle!
|
|
|
|
self.set_rc(3, 2000)
|
|
|
|
self.set_rc(2, 1300)
|
2018-04-27 15:21:53 -03:00
|
|
|
self.change_altitude(self.homeloc.alt+300)
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(2, 1500)
|
|
|
|
|
2021-02-18 00:12:25 -04:00
|
|
|
self.change_mode('ACRO')
|
2018-03-05 11:14:34 -04:00
|
|
|
|
|
|
|
while count > 0:
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Starting roll")
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(1, 1000)
|
2018-04-27 15:21:53 -03:00
|
|
|
self.wait_roll(-150, accuracy=90)
|
|
|
|
self.wait_roll(150, accuracy=90)
|
|
|
|
self.wait_roll(0, accuracy=90)
|
2018-03-05 11:14:34 -04:00
|
|
|
count -= 1
|
|
|
|
self.set_rc(1, 1500)
|
|
|
|
|
|
|
|
# back to FBWA
|
2021-02-19 05:35:07 -04:00
|
|
|
self.change_mode('FBWA')
|
2018-03-05 11:14:34 -04:00
|
|
|
|
|
|
|
self.wait_level_flight()
|
|
|
|
|
2021-02-18 00:12:25 -04:00
|
|
|
self.change_mode('ACRO')
|
2018-03-05 11:14:34 -04:00
|
|
|
|
|
|
|
count = 2
|
|
|
|
while count > 0:
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Starting loop")
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(2, 1000)
|
2018-04-27 15:21:53 -03:00
|
|
|
self.wait_pitch(-60, accuracy=20)
|
|
|
|
self.wait_pitch(0, accuracy=20)
|
2018-03-05 11:14:34 -04:00
|
|
|
count -= 1
|
|
|
|
|
|
|
|
self.set_rc(2, 1500)
|
|
|
|
|
|
|
|
# back to FBWA
|
2021-02-19 05:35:07 -04:00
|
|
|
self.change_mode('FBWA')
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(3, 1700)
|
|
|
|
return self.wait_level_flight()
|
|
|
|
|
2018-07-31 06:47:49 -03:00
|
|
|
def test_FBWB(self, mode='FBWB'):
|
2018-03-05 11:14:34 -04:00
|
|
|
"""Fly FBWB or CRUISE mode."""
|
2021-02-18 00:12:25 -04:00
|
|
|
self.change_mode(mode)
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(3, 1700)
|
|
|
|
self.set_rc(2, 1500)
|
|
|
|
|
|
|
|
# lock in the altitude by asking for an altitude change then releasing
|
|
|
|
self.set_rc(2, 1000)
|
|
|
|
self.wait_distance(50, accuracy=20)
|
|
|
|
self.set_rc(2, 1500)
|
|
|
|
self.wait_distance(50, accuracy=20)
|
|
|
|
|
|
|
|
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
|
|
|
|
initial_alt = m.alt
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Initial altitude %u\n" % initial_alt)
|
2018-03-05 11:14:34 -04:00
|
|
|
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Flying right circuit")
|
2018-03-05 11:14:34 -04:00
|
|
|
# do 4 turns
|
|
|
|
for i in range(0, 4):
|
|
|
|
# hard left
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Starting turn %u" % i)
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(1, 1800)
|
2018-04-27 15:21:53 -03:00
|
|
|
try:
|
|
|
|
self.wait_heading(0 + (90*i), accuracy=20, timeout=60)
|
|
|
|
except Exception as e:
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(1, 1500)
|
2018-04-27 15:21:53 -03:00
|
|
|
raise e
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(1, 1500)
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Starting leg %u" % i)
|
2018-04-27 15:21:53 -03:00
|
|
|
self.wait_distance(100, accuracy=20)
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Circuit complete")
|
2018-03-05 11:14:34 -04:00
|
|
|
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Flying rudder left circuit")
|
2018-03-05 11:14:34 -04:00
|
|
|
# do 4 turns
|
|
|
|
for i in range(0, 4):
|
|
|
|
# hard left
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Starting turn %u" % i)
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(4, 1900)
|
2018-04-27 15:21:53 -03:00
|
|
|
try:
|
|
|
|
self.wait_heading(360 - (90*i), accuracy=20, timeout=60)
|
|
|
|
except Exception as e:
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(4, 1500)
|
2018-04-27 15:21:53 -03:00
|
|
|
raise e
|
2018-03-05 11:14:34 -04:00
|
|
|
self.set_rc(4, 1500)
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Starting leg %u" % i)
|
2018-04-27 15:21:53 -03:00
|
|
|
self.wait_distance(100, accuracy=20)
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Circuit complete")
|
2018-03-05 11:14:34 -04:00
|
|
|
|
|
|
|
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
|
|
|
|
final_alt = m.alt
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Final altitude %u initial %u\n" %
|
|
|
|
(final_alt, initial_alt))
|
2018-03-05 11:14:34 -04:00
|
|
|
|
|
|
|
# back to FBWA
|
2021-02-19 05:35:07 -04:00
|
|
|
self.change_mode('FBWA')
|
2018-03-05 11:14:34 -04:00
|
|
|
|
|
|
|
if abs(final_alt - initial_alt) > 20:
|
2018-10-17 23:55:16 -03:00
|
|
|
raise NotAchievedException("Failed to maintain altitude")
|
2018-03-05 11:14:34 -04:00
|
|
|
|
|
|
|
return self.wait_level_flight()
|
|
|
|
|
2021-06-20 22:33:12 -03:00
|
|
|
def fly_mission(self, filename, mission_timeout=60.0, strict=True, quadplane=False):
|
2018-08-13 08:07:34 -03:00
|
|
|
"""Fly a mission from a file."""
|
|
|
|
self.progress("Flying mission %s" % filename)
|
2021-02-24 21:02:57 -04:00
|
|
|
num_wp = self.load_mission(filename, strict=strict)-1
|
2022-08-01 05:49:40 -03:00
|
|
|
self.fly_mission_waypoints(num_wp, mission_timeout=mission_timeout, quadplane=quadplane)
|
|
|
|
|
|
|
|
def fly_mission_waypoints(self, num_wp, mission_timeout=60.0, quadplane=False):
|
2021-03-09 02:37:16 -04:00
|
|
|
self.set_current_waypoint(0, check_afterwards=False)
|
2022-06-13 06:36:32 -03:00
|
|
|
self.context_push()
|
|
|
|
self.context_collect('STATUSTEXT')
|
2020-12-28 21:30:53 -04:00
|
|
|
self.change_mode('AUTO')
|
2021-04-25 19:21:53 -03:00
|
|
|
self.wait_waypoint(1, num_wp, max_dist=60, timeout=mission_timeout)
|
2020-07-04 14:57:20 -03:00
|
|
|
self.wait_groundspeed(0, 0.5, timeout=mission_timeout)
|
2021-06-20 22:33:12 -03:00
|
|
|
if quadplane:
|
2022-06-13 06:36:32 -03:00
|
|
|
self.wait_statustext("Throttle disarmed", timeout=200, check_context=True)
|
2021-06-20 22:33:12 -03:00
|
|
|
else:
|
2022-06-13 06:36:32 -03:00
|
|
|
self.wait_statustext("Auto disarmed", timeout=60, check_context=True)
|
|
|
|
self.context_pop()
|
2018-03-14 08:08:53 -03:00
|
|
|
self.progress("Mission OK")
|
2018-03-05 11:14:34 -04:00
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def DO_REPOSITION(self):
|
|
|
|
'''Test mavlink DO_REPOSITION command'''
|
2019-08-05 08:09:07 -03:00
|
|
|
self.progress("Takeoff")
|
|
|
|
self.takeoff(alt=50)
|
|
|
|
self.set_rc(3, 1500)
|
|
|
|
self.progress("Entering guided and flying somewhere constant")
|
|
|
|
self.change_mode("GUIDED")
|
|
|
|
loc = self.mav.location()
|
|
|
|
self.location_offset_ne(loc, 500, 500)
|
|
|
|
|
|
|
|
new_alt = 100
|
|
|
|
self.run_cmd_int(
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
|
2023-07-15 09:40:01 -03:00
|
|
|
p5=int(loc.lat * 1e7),
|
|
|
|
p6=int(loc.lng * 1e7),
|
|
|
|
p7=new_alt, # alt
|
2019-08-05 08:09:07 -03:00
|
|
|
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
|
2019-08-05 08:09:07 -03:00
|
|
|
)
|
|
|
|
self.wait_altitude(new_alt-10, new_alt, timeout=30, relative=True)
|
|
|
|
|
2019-08-05 08:09:07 -03:00
|
|
|
self.install_terrain_handlers_context()
|
|
|
|
|
|
|
|
self.location_offset_ne(loc, 500, 500)
|
|
|
|
terrain_height_wanted = 150
|
|
|
|
self.run_cmd_int(
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
|
|
|
|
0,
|
|
|
|
0,
|
|
|
|
0,
|
|
|
|
0,
|
|
|
|
int(loc.lat*1e7),
|
|
|
|
int(loc.lng*1e7),
|
|
|
|
terrain_height_wanted, # alt
|
|
|
|
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT,
|
|
|
|
)
|
|
|
|
|
|
|
|
# move to specific terrain-relative altitude and hold for <n> seconds
|
|
|
|
tstart = self.get_sim_time_cached()
|
|
|
|
achieve_start = None
|
|
|
|
tr = None
|
|
|
|
while True:
|
|
|
|
if self.get_sim_time_cached() - tstart > 120:
|
|
|
|
raise NotAchievedException("Did not move to correct terrain alt")
|
|
|
|
|
|
|
|
m = self.mav.recv_match(type='TERRAIN_REPORT',
|
|
|
|
blocking=True,
|
|
|
|
timeout=1)
|
|
|
|
tr = m
|
|
|
|
terrain_height_achieved = m.current_height
|
|
|
|
self.progress("terrain_alt=%f want=%f" %
|
|
|
|
(terrain_height_achieved, terrain_height_wanted))
|
|
|
|
if m is None:
|
|
|
|
continue
|
|
|
|
if abs(terrain_height_wanted - terrain_height_achieved) > 5:
|
|
|
|
if achieve_start is not None:
|
|
|
|
self.progress("Achieve stop")
|
|
|
|
achieve_start = None
|
|
|
|
elif achieve_start is None:
|
|
|
|
self.progress("Achieve start")
|
|
|
|
achieve_start = self.get_sim_time_cached()
|
|
|
|
if achieve_start is not None:
|
|
|
|
if self.get_sim_time_cached() - achieve_start > 10:
|
|
|
|
break
|
|
|
|
m = self.mav.recv_match(type='GLOBAL_POSITION_INT',
|
|
|
|
blocking=True,
|
|
|
|
timeout=1)
|
|
|
|
self.progress("TR: %s" % tr)
|
|
|
|
self.progress("GPI: %s" % m)
|
|
|
|
min_delta = 4
|
|
|
|
delta = abs(m.relative_alt/1000.0 - tr.current_height)
|
|
|
|
if abs(delta < min_delta):
|
|
|
|
raise NotAchievedException("Expected altitude delta (want=%f got=%f)" %
|
|
|
|
(min_delta, delta))
|
|
|
|
|
|
|
|
self.fly_home_land_and_disarm(timeout=180)
|
2019-08-05 08:09:07 -03:00
|
|
|
|
2023-06-05 18:16:25 -03:00
|
|
|
def ExternalPositionEstimate(self):
|
|
|
|
'''Test mavlink EXTERNAL_POSITION_ESTIMATE command'''
|
|
|
|
if not hasattr(mavutil.mavlink, 'MAV_CMD_EXTERNAL_POSITION_ESTIMATE'):
|
2023-07-04 19:57:32 -03:00
|
|
|
raise OldpymavlinkException("pymavlink too old; upgrade pymavlink to get MAV_CMD_EXTERNAL_POSITION_ESTIMATE") # noqa
|
2023-06-05 18:16:25 -03:00
|
|
|
self.change_mode("TAKEOFF")
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
|
|
|
self.wait_altitude(48, 52, relative=True)
|
|
|
|
|
|
|
|
loc = self.mav.location()
|
|
|
|
self.location_offset_ne(loc, 2000, 2000)
|
|
|
|
|
|
|
|
# setting external position fail while we have GPS lock
|
|
|
|
self.progress("set new position with GPS")
|
|
|
|
self.run_cmd_int(
|
|
|
|
mavutil.mavlink.MAV_CMD_EXTERNAL_POSITION_ESTIMATE,
|
2023-07-15 09:40:01 -03:00
|
|
|
p1=self.get_sim_time()-1, # transmit time
|
|
|
|
p2=0.5, # processing delay
|
|
|
|
p3=50, # accuracy
|
|
|
|
p5=int(loc.lat * 1e7),
|
|
|
|
p6=int(loc.lng * 1e7),
|
|
|
|
p7=float("NaN"), # alt
|
2023-06-05 18:16:25 -03:00
|
|
|
frame=mavutil.mavlink.MAV_FRAME_GLOBAL,
|
|
|
|
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
|
|
|
|
)
|
|
|
|
|
|
|
|
self.progress("disable the GPS")
|
|
|
|
self.run_auxfunc(
|
|
|
|
65,
|
|
|
|
2,
|
|
|
|
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED
|
|
|
|
)
|
|
|
|
|
|
|
|
# fly for a bit to get into non-aiding state
|
|
|
|
self.progress("waiting 20 seconds")
|
|
|
|
tstart = self.get_sim_time()
|
|
|
|
while self.get_sim_time() < tstart + 20:
|
|
|
|
self.wait_heartbeat()
|
|
|
|
|
|
|
|
self.progress("getting base position")
|
|
|
|
gpi = self.mav.recv_match(
|
|
|
|
type='GLOBAL_POSITION_INT',
|
|
|
|
blocking=True,
|
|
|
|
timeout=5
|
|
|
|
)
|
|
|
|
loc = mavutil.location(gpi.lat*1e-7, gpi.lon*1e-7, 0, 0)
|
|
|
|
|
|
|
|
self.progress("set new position with no GPS")
|
|
|
|
self.run_cmd_int(
|
|
|
|
mavutil.mavlink.MAV_CMD_EXTERNAL_POSITION_ESTIMATE,
|
2023-07-15 09:40:01 -03:00
|
|
|
p1=self.get_sim_time()-1, # transmit time
|
|
|
|
p2=0.5, # processing delay
|
|
|
|
p3=50, # accuracy
|
|
|
|
p5=gpi.lat+1,
|
|
|
|
p6=gpi.lon+1,
|
|
|
|
p7=float("NaN"), # alt
|
2023-06-05 18:16:25 -03:00
|
|
|
frame=mavutil.mavlink.MAV_FRAME_GLOBAL,
|
|
|
|
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED
|
|
|
|
)
|
|
|
|
|
|
|
|
self.progress("waiting 3 seconds")
|
|
|
|
tstart = self.get_sim_time()
|
|
|
|
while self.get_sim_time() < tstart + 3:
|
|
|
|
self.wait_heartbeat()
|
|
|
|
|
|
|
|
gpi2 = self.mav.recv_match(
|
|
|
|
type='GLOBAL_POSITION_INT',
|
|
|
|
blocking=True,
|
|
|
|
timeout=5
|
|
|
|
)
|
|
|
|
loc2 = mavutil.location(gpi2.lat*1e-7, gpi2.lon*1e-7, 0, 0)
|
|
|
|
dist = self.get_distance(loc, loc2)
|
|
|
|
|
|
|
|
self.progress("dist is %.1f" % dist)
|
|
|
|
if dist > 200:
|
|
|
|
raise NotAchievedException("Position error dist=%.1f" % dist)
|
|
|
|
|
|
|
|
self.progress("re-enable the GPS")
|
|
|
|
self.run_auxfunc(
|
|
|
|
65,
|
|
|
|
0,
|
|
|
|
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED
|
|
|
|
)
|
|
|
|
|
|
|
|
self.progress("flying home")
|
|
|
|
self.fly_home_land_and_disarm()
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def DeepStall(self):
|
|
|
|
'''Test DeepStall Landing'''
|
2021-02-11 22:44:28 -04:00
|
|
|
# self.fly_deepstall_absolute()
|
2019-10-17 18:24:25 -03:00
|
|
|
self.fly_deepstall_relative()
|
|
|
|
|
|
|
|
def fly_deepstall_absolute(self):
|
|
|
|
self.start_subtest("DeepStall Relative Absolute")
|
2019-10-17 17:33:07 -03:00
|
|
|
deepstall_elevator_pwm = 1661
|
2022-03-13 00:16:27 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"LAND_TYPE": 1,
|
|
|
|
"LAND_DS_ELEV_PWM": deepstall_elevator_pwm,
|
|
|
|
"RTL_AUTOLAND": 1,
|
|
|
|
})
|
2019-10-17 17:33:07 -03:00
|
|
|
self.load_mission("plane-deepstall-mission.txt")
|
|
|
|
self.change_mode("AUTO")
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
|
|
|
self.progress("Waiting for deepstall messages")
|
|
|
|
|
2022-06-13 06:46:41 -03:00
|
|
|
# note that the following two don't necessarily happen in this
|
|
|
|
# order, but at very high speedups we may miss the elevator
|
|
|
|
# PWM if we first look for the text (due to the get_sim_time()
|
|
|
|
# in wait_servo_channel_value)
|
|
|
|
|
|
|
|
self.context_collect('STATUSTEXT')
|
2019-10-17 17:33:07 -03:00
|
|
|
|
|
|
|
# assume elevator is on channel 2:
|
2022-06-13 06:46:41 -03:00
|
|
|
self.wait_servo_channel_value(2, deepstall_elevator_pwm, timeout=240)
|
|
|
|
|
|
|
|
self.wait_text("Deepstall: Entry: ", check_context=True)
|
2019-10-17 17:33:07 -03:00
|
|
|
|
|
|
|
self.disarm_wait(timeout=120)
|
2019-10-17 18:24:25 -03:00
|
|
|
|
|
|
|
self.progress("Flying home")
|
2022-05-14 20:28:56 -03:00
|
|
|
self.set_current_waypoint(0, check_afterwards=False)
|
2019-10-17 18:24:25 -03:00
|
|
|
self.takeoff(10)
|
|
|
|
self.set_parameter("LAND_TYPE", 0)
|
|
|
|
self.fly_home_land_and_disarm()
|
|
|
|
|
|
|
|
def fly_deepstall_relative(self):
|
|
|
|
self.start_subtest("DeepStall Relative")
|
|
|
|
deepstall_elevator_pwm = 1661
|
2022-03-13 00:16:27 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"LAND_TYPE": 1,
|
|
|
|
"LAND_DS_ELEV_PWM": deepstall_elevator_pwm,
|
|
|
|
"RTL_AUTOLAND": 1,
|
|
|
|
})
|
2019-10-17 18:24:25 -03:00
|
|
|
self.load_mission("plane-deepstall-relative-mission.txt")
|
|
|
|
self.change_mode("AUTO")
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
2023-08-16 00:45:56 -03:00
|
|
|
self.wait_current_waypoint(4)
|
2019-10-17 18:24:25 -03:00
|
|
|
|
|
|
|
# assume elevator is on channel 2:
|
2022-06-13 06:46:41 -03:00
|
|
|
self.wait_servo_channel_value(2, deepstall_elevator_pwm, timeout=240)
|
|
|
|
|
2023-08-16 00:45:56 -03:00
|
|
|
self.progress("Waiting for stage DEEPSTALL_STAGE_LAND")
|
|
|
|
self.assert_receive_message(
|
|
|
|
'DEEPSTALL',
|
|
|
|
condition='DEEPSTALL.stage==6',
|
|
|
|
timeout=240,
|
|
|
|
)
|
|
|
|
self.progress("Reached stage DEEPSTALL_STAGE_LAND")
|
2019-10-17 18:24:25 -03:00
|
|
|
|
|
|
|
self.disarm_wait(timeout=120)
|
2022-05-14 03:02:17 -03:00
|
|
|
self.set_current_waypoint(0, check_afterwards=False)
|
2019-10-17 17:33:07 -03:00
|
|
|
|
|
|
|
self.progress("Flying home")
|
2022-05-14 20:28:56 -03:00
|
|
|
self.set_current_waypoint(0, check_afterwards=False)
|
2020-03-12 20:51:17 -03:00
|
|
|
self.takeoff(100)
|
2019-10-17 17:33:07 -03:00
|
|
|
self.set_parameter("LAND_TYPE", 0)
|
2020-03-12 20:51:17 -03:00
|
|
|
self.fly_home_land_and_disarm(timeout=240)
|
2019-10-17 17:33:07 -03:00
|
|
|
|
2021-06-08 02:20:27 -03:00
|
|
|
def SmartBattery(self):
|
2022-09-09 22:24:28 -03:00
|
|
|
'''Test smart battery logging etc'''
|
2021-06-08 02:20:27 -03:00
|
|
|
self.set_parameters({
|
2021-06-25 14:05:16 -03:00
|
|
|
"BATT_MONITOR": 16, # Maxell battery monitor
|
2021-06-08 02:20:27 -03:00
|
|
|
})
|
2021-06-25 14:05:16 -03:00
|
|
|
|
|
|
|
# Must reboot sitl after setting montior type for SMBus parameters to be set due to dynamic group
|
2021-06-08 02:20:27 -03:00
|
|
|
self.reboot_sitl()
|
2021-06-25 14:05:16 -03:00
|
|
|
self.set_parameters({
|
|
|
|
"BATT_I2C_BUS": 2, # specified in SIM_I2C.cpp
|
|
|
|
"BATT_I2C_ADDR": 11, # specified in SIM_I2C.cpp
|
|
|
|
})
|
|
|
|
self.reboot_sitl()
|
|
|
|
|
2021-06-08 02:20:27 -03:00
|
|
|
self.wait_ready_to_arm()
|
2022-02-09 20:59:34 -04:00
|
|
|
m = self.assert_receive_message('BATTERY_STATUS', timeout=10)
|
2021-06-08 02:20:27 -03:00
|
|
|
if m.voltages_ext[0] == 65536:
|
|
|
|
raise NotAchievedException("Flag value rather than voltage")
|
|
|
|
if abs(m.voltages_ext[0] - 1000) > 300:
|
|
|
|
raise NotAchievedException("Did not get good ext voltage (got=%f)" %
|
|
|
|
(m.voltages_ext[0],))
|
|
|
|
self.arm_vehicle()
|
|
|
|
self.delay_sim_time(5)
|
|
|
|
self.disarm_vehicle()
|
|
|
|
if not self.current_onboard_log_contains_message("BCL2"):
|
|
|
|
raise NotAchievedException("Expected BCL2 message")
|
|
|
|
|
2023-08-29 18:36:37 -03:00
|
|
|
def context_push_do_change_speed(self):
|
2019-05-20 09:47:01 -03:00
|
|
|
# the following lines ensure we revert these parameter values
|
|
|
|
# - DO_CHANGE_AIRSPEED is a permanent vehicle change!
|
2023-08-29 18:36:37 -03:00
|
|
|
self.context_push()
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"TRIM_ARSPD_CM": self.get_parameter("TRIM_ARSPD_CM"),
|
|
|
|
"MIN_GNDSPD_CM": self.get_parameter("MIN_GNDSPD_CM"),
|
2023-08-29 18:36:37 -03:00
|
|
|
"TRIM_THROTTLE": self.get_parameter("TRIM_THROTTLE"),
|
|
|
|
})
|
|
|
|
|
|
|
|
def DO_CHANGE_SPEED(self):
|
|
|
|
'''Test DO_CHANGE_SPEED command/item'''
|
|
|
|
self.set_parameters({
|
2022-05-03 00:39:04 -03:00
|
|
|
"RTL_AUTOLAND": 1,
|
2021-11-23 21:22:21 -04:00
|
|
|
})
|
2019-05-20 09:47:01 -03:00
|
|
|
|
2023-08-29 18:36:37 -03:00
|
|
|
self.context_push_do_change_speed()
|
|
|
|
self.DO_CHANGE_SPEED_mavlink_long()
|
|
|
|
self.context_pop()
|
|
|
|
|
|
|
|
self.set_current_waypoint(1)
|
|
|
|
self.zero_throttle()
|
|
|
|
|
|
|
|
self.context_push_do_change_speed()
|
|
|
|
self.DO_CHANGE_SPEED_mavlink_int()
|
|
|
|
self.context_pop()
|
|
|
|
|
|
|
|
self.context_push_do_change_speed()
|
2022-05-03 00:39:04 -03:00
|
|
|
self.DO_CHANGE_SPEED_mission()
|
2023-08-29 18:36:37 -03:00
|
|
|
self.context_pop()
|
2022-05-03 00:39:04 -03:00
|
|
|
|
|
|
|
def DO_CHANGE_SPEED_mission(self):
|
|
|
|
'''test DO_CHANGE_SPEED as a mission item'''
|
|
|
|
self.start_subtest("DO_CHANGE_SPEED_mission")
|
|
|
|
self.load_mission("mission.txt")
|
|
|
|
self.set_current_waypoint(1)
|
|
|
|
|
|
|
|
self.progress("Takeoff")
|
|
|
|
self.set_rc(3, 1000)
|
|
|
|
self.takeoff(alt=10)
|
|
|
|
self.set_rc(3, 1500)
|
|
|
|
|
|
|
|
self.start_subtest("Check initial speed")
|
|
|
|
|
|
|
|
self.change_mode('AUTO')
|
|
|
|
|
|
|
|
checks = [
|
|
|
|
(1, self.get_parameter("TRIM_ARSPD_CM") * 0.01),
|
|
|
|
(3, 10),
|
|
|
|
(5, 20),
|
|
|
|
(7, 15),
|
|
|
|
]
|
|
|
|
|
|
|
|
for (current_waypoint, want_airspeed) in checks:
|
2022-11-12 18:08:07 -04:00
|
|
|
self.wait_current_waypoint(current_waypoint, timeout=150)
|
2022-05-03 00:39:04 -03:00
|
|
|
self.wait_airspeed(want_airspeed-1, want_airspeed+1, minimum_duration=5, timeout=120)
|
|
|
|
|
|
|
|
self.fly_home_land_and_disarm()
|
|
|
|
|
2023-08-29 18:36:37 -03:00
|
|
|
def DO_CHANGE_SPEED_mavlink_int(self):
|
|
|
|
self.DO_CHANGE_SPEED_mavlink(self.run_cmd_int)
|
|
|
|
|
|
|
|
def DO_CHANGE_SPEED_mavlink_long(self):
|
|
|
|
self.DO_CHANGE_SPEED_mavlink(self.run_cmd)
|
|
|
|
|
|
|
|
def DO_CHANGE_SPEED_mavlink(self, run_cmd_method):
|
2022-05-03 00:39:04 -03:00
|
|
|
'''test DO_CHANGE_SPEED as a mavlink command'''
|
2019-05-20 09:47:01 -03:00
|
|
|
self.progress("Takeoff")
|
2023-08-29 18:36:37 -03:00
|
|
|
self.takeoff(alt=100, mode="TAKEOFF", timeout=120)
|
2019-05-20 09:47:01 -03:00
|
|
|
self.set_rc(3, 1500)
|
|
|
|
# ensure we know what the airspeed is:
|
|
|
|
self.progress("Entering guided and flying somewhere constant")
|
|
|
|
self.change_mode("GUIDED")
|
|
|
|
self.run_cmd_int(
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
|
2023-07-15 09:40:01 -03:00
|
|
|
p5=12345, # lat* 1e7
|
|
|
|
p6=12345, # lon* 1e7
|
|
|
|
p7=100 # alt
|
2019-05-20 09:47:01 -03:00
|
|
|
)
|
|
|
|
self.delay_sim_time(10)
|
|
|
|
self.progress("Ensuring initial speed is known and relatively constant")
|
2022-05-16 19:31:04 -03:00
|
|
|
initial_speed = 22.0
|
2022-05-19 06:11:28 -03:00
|
|
|
timeout = 15
|
|
|
|
self.wait_airspeed(initial_speed-1, initial_speed+1, minimum_duration=5, timeout=timeout)
|
2019-05-20 09:47:01 -03:00
|
|
|
|
2023-08-29 18:36:37 -03:00
|
|
|
self.start_subtest("Setting groundspeed")
|
|
|
|
for new_target_groundspeed in initial_speed + 5, initial_speed + 2:
|
|
|
|
run_cmd_method(
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
|
|
|
|
p1=1, # groundspeed
|
|
|
|
p2=new_target_groundspeed,
|
|
|
|
p3=-1, # throttle / no change
|
|
|
|
p4=0, # absolute values
|
|
|
|
)
|
|
|
|
self.wait_groundspeed(new_target_groundspeed-2, new_target_groundspeed+2, timeout=80, minimum_duration=5)
|
|
|
|
self.progress("Adding some wind, ensuring groundspeed holds")
|
|
|
|
self.set_parameter("SIM_WIND_SPD", 5)
|
|
|
|
self.delay_sim_time(5)
|
|
|
|
self.wait_groundspeed(new_target_groundspeed-2, new_target_groundspeed+2, timeout=40, minimum_duration=5)
|
|
|
|
self.set_parameter("SIM_WIND_SPD", 0)
|
2019-05-20 09:47:01 -03:00
|
|
|
|
2022-05-16 19:31:04 -03:00
|
|
|
# clear target groundspeed
|
2023-08-29 18:36:37 -03:00
|
|
|
run_cmd_method(
|
2022-05-16 19:31:04 -03:00
|
|
|
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
|
2023-07-15 09:40:01 -03:00
|
|
|
p1=1, # groundspeed
|
|
|
|
p2=0,
|
|
|
|
p3=-1, # throttle / no change
|
|
|
|
p4=0, # absolute values
|
|
|
|
)
|
2022-05-16 19:31:04 -03:00
|
|
|
|
2023-08-29 18:36:37 -03:00
|
|
|
self.start_subtest("Setting airspeed")
|
|
|
|
for new_target_airspeed in initial_speed - 5, initial_speed + 5:
|
|
|
|
run_cmd_method(
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
|
|
|
|
p1=0, # airspeed
|
|
|
|
p2=new_target_airspeed,
|
|
|
|
p3=-1, # throttle / no change
|
|
|
|
p4=0, # absolute values
|
|
|
|
)
|
|
|
|
self.wait_airspeed(new_target_airspeed-2, new_target_airspeed+2, minimum_duration=5)
|
|
|
|
|
|
|
|
self.context_push()
|
2019-05-20 09:47:01 -03:00
|
|
|
self.progress("Adding some wind, hoping groundspeed increases/decreases")
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
2022-05-16 19:31:04 -03:00
|
|
|
"SIM_WIND_SPD": 7,
|
2021-11-23 21:22:21 -04:00
|
|
|
"SIM_WIND_DIR": 270,
|
|
|
|
})
|
2019-05-20 09:47:01 -03:00
|
|
|
self.delay_sim_time(5)
|
|
|
|
timeout = 10
|
|
|
|
tstart = self.get_sim_time()
|
|
|
|
while True:
|
|
|
|
if self.get_sim_time_cached() - tstart > timeout:
|
|
|
|
raise NotAchievedException("Did not achieve groundspeed delta")
|
|
|
|
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
|
|
|
|
delta = abs(m.airspeed - m.groundspeed)
|
2022-05-16 19:31:04 -03:00
|
|
|
want_delta = 5
|
2019-05-20 09:47:01 -03:00
|
|
|
self.progress("groundspeed and airspeed should be different (have=%f want=%f)" % (delta, want_delta))
|
|
|
|
if delta > want_delta:
|
|
|
|
break
|
2023-08-29 18:36:37 -03:00
|
|
|
self.context_pop()
|
|
|
|
|
|
|
|
# cancel minimum groundspeed:
|
|
|
|
run_cmd_method(
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
|
|
|
|
p1=0, # groundspeed
|
|
|
|
p2=-2, # return to default
|
|
|
|
p3=0, # throttle / no change
|
|
|
|
p4=0, # absolute values
|
|
|
|
)
|
|
|
|
# cancel airspeed:
|
|
|
|
run_cmd_method(
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
|
|
|
|
p1=1, # airspeed
|
|
|
|
p2=-2, # return to default
|
|
|
|
p3=0, # throttle / no change
|
|
|
|
p4=0, # absolute values
|
|
|
|
)
|
|
|
|
|
|
|
|
self.start_subtest("Setting throttle")
|
|
|
|
self.set_parameter('ARSPD_USE', 0) # setting throttle only effective without airspeed
|
|
|
|
for (set_throttle, expected_throttle) in (97, 79), (60, 51), (95, 77):
|
|
|
|
run_cmd_method(
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
|
|
|
|
p1=3, # throttle
|
|
|
|
p2=0,
|
|
|
|
p3=set_throttle, # throttle / no change
|
|
|
|
p4=0, # absolute values
|
|
|
|
)
|
|
|
|
self.wait_message_field_values('VFR_HUD', {
|
|
|
|
"throttle": expected_throttle,
|
|
|
|
}, minimum_duration=5, epsilon=2)
|
|
|
|
|
2021-01-17 20:51:59 -04:00
|
|
|
self.fly_home_land_and_disarm(timeout=240)
|
2019-08-05 08:09:07 -03:00
|
|
|
|
2020-03-12 20:51:17 -03:00
|
|
|
def fly_home_land_and_disarm(self, timeout=120):
|
2020-03-10 09:18:59 -03:00
|
|
|
filename = "flaps.txt"
|
2019-05-20 09:47:01 -03:00
|
|
|
self.progress("Using %s to fly home" % filename)
|
2021-09-26 03:37:04 -03:00
|
|
|
self.load_generic_mission(filename)
|
2019-05-20 09:47:01 -03:00
|
|
|
self.change_mode("AUTO")
|
2021-04-20 08:18:17 -03:00
|
|
|
# don't set current waypoint to 8 unless we're distant from it
|
|
|
|
# or we arrive instantly and never see it as our current
|
|
|
|
# waypoint:
|
|
|
|
self.wait_distance_to_waypoint(8, 100, 10000000)
|
2021-03-08 23:15:58 -04:00
|
|
|
self.set_current_waypoint(8)
|
2020-03-12 20:51:17 -03:00
|
|
|
# TODO: reflect on file to find this magic waypoint number?
|
2021-02-11 22:44:28 -04:00
|
|
|
# self.wait_waypoint(7, num_wp-1, timeout=500) # we
|
|
|
|
# tend to miss the final waypoint by a fair bit, and
|
|
|
|
# this is probably too noisy anyway?
|
2020-03-12 20:51:17 -03:00
|
|
|
self.wait_disarmed(timeout=timeout)
|
2019-05-20 09:47:01 -03:00
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def TestFlaps(self):
|
2018-08-13 08:07:34 -03:00
|
|
|
"""Test flaps functionality."""
|
2020-03-10 09:18:59 -03:00
|
|
|
filename = "flaps.txt"
|
2018-08-13 08:07:34 -03:00
|
|
|
self.context_push()
|
|
|
|
ex = None
|
|
|
|
try:
|
2021-11-23 21:22:21 -04:00
|
|
|
|
2018-08-13 08:07:34 -03:00
|
|
|
flaps_ch = 5
|
|
|
|
flaps_ch_min = 1000
|
|
|
|
flaps_ch_trim = 1500
|
|
|
|
flaps_ch_max = 2000
|
|
|
|
|
2021-11-23 21:22:21 -04:00
|
|
|
servo_ch = 5
|
2018-08-13 08:07:34 -03:00
|
|
|
servo_ch_min = 1200
|
|
|
|
servo_ch_trim = 1300
|
|
|
|
servo_ch_max = 1800
|
2021-11-23 21:22:21 -04:00
|
|
|
|
|
|
|
self.set_parameters({
|
|
|
|
"SERVO%u_FUNCTION" % servo_ch: 3, # flapsauto
|
|
|
|
"RC%u_OPTION" % flaps_ch: 208, # Flaps RCx_OPTION
|
|
|
|
"LAND_FLAP_PERCNT": 50,
|
|
|
|
"LOG_DISARMED": 1,
|
2022-03-12 22:03:18 -04:00
|
|
|
"RTL_AUTOLAND": 1,
|
2021-11-23 21:22:21 -04:00
|
|
|
|
|
|
|
"RC%u_MIN" % flaps_ch: flaps_ch_min,
|
|
|
|
"RC%u_MAX" % flaps_ch: flaps_ch_max,
|
|
|
|
"RC%u_TRIM" % flaps_ch: flaps_ch_trim,
|
|
|
|
|
|
|
|
"SERVO%u_MIN" % servo_ch: servo_ch_min,
|
|
|
|
"SERVO%u_MAX" % servo_ch: servo_ch_max,
|
|
|
|
"SERVO%u_TRIM" % servo_ch: servo_ch_trim,
|
|
|
|
})
|
2018-08-13 08:07:34 -03:00
|
|
|
|
2018-11-28 18:48:31 -04:00
|
|
|
self.progress("check flaps are not deployed")
|
2018-08-13 08:07:34 -03:00
|
|
|
self.set_rc(flaps_ch, flaps_ch_min)
|
2021-11-23 21:22:21 -04:00
|
|
|
self.wait_servo_channel_value(servo_ch, servo_ch_min, timeout=3)
|
2018-11-28 18:48:31 -04:00
|
|
|
self.progress("deploy the flaps")
|
2018-08-13 08:07:34 -03:00
|
|
|
self.set_rc(flaps_ch, flaps_ch_max)
|
|
|
|
tstart = self.get_sim_time()
|
|
|
|
self.wait_servo_channel_value(servo_ch, servo_ch_max)
|
|
|
|
tstop = self.get_sim_time_cached()
|
|
|
|
delta_time = tstop - tstart
|
|
|
|
delta_time_min = 0.5
|
|
|
|
delta_time_max = 1.5
|
|
|
|
if delta_time < delta_time_min or delta_time > delta_time_max:
|
2018-10-17 23:55:16 -03:00
|
|
|
raise NotAchievedException((
|
|
|
|
"Flaps Slew not working (%f seconds)" % (delta_time,)))
|
2018-11-28 18:48:31 -04:00
|
|
|
self.progress("undeploy flaps")
|
2018-08-13 08:07:34 -03:00
|
|
|
self.set_rc(flaps_ch, flaps_ch_min)
|
|
|
|
self.wait_servo_channel_value(servo_ch, servo_ch_min)
|
|
|
|
|
|
|
|
self.progress("Flying mission %s" % filename)
|
2018-11-09 08:32:02 -04:00
|
|
|
self.load_mission(filename)
|
2021-02-18 06:32:49 -04:00
|
|
|
self.set_current_waypoint(1)
|
2020-12-28 21:30:53 -04:00
|
|
|
self.change_mode('AUTO')
|
2018-08-13 08:07:34 -03:00
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
2018-09-07 20:48:45 -03:00
|
|
|
last_mission_current_msg = 0
|
|
|
|
last_seq = None
|
2018-08-13 08:07:34 -03:00
|
|
|
while self.armed():
|
|
|
|
m = self.mav.recv_match(type='MISSION_CURRENT', blocking=True)
|
2018-09-07 20:48:45 -03:00
|
|
|
time_delta = (self.get_sim_time_cached() -
|
|
|
|
last_mission_current_msg)
|
2018-11-22 23:51:58 -04:00
|
|
|
if (time_delta > 1 or m.seq != last_seq):
|
2018-09-07 20:48:45 -03:00
|
|
|
dist = None
|
|
|
|
x = self.mav.messages.get("NAV_CONTROLLER_OUTPUT", None)
|
|
|
|
if x is not None:
|
|
|
|
dist = x.wp_dist
|
|
|
|
self.progress("MISSION_CURRENT.seq=%u (dist=%s)" %
|
2018-11-22 23:51:58 -04:00
|
|
|
(m.seq, str(dist)))
|
2018-09-07 20:48:45 -03:00
|
|
|
last_mission_current_msg = self.get_sim_time_cached()
|
|
|
|
last_seq = m.seq
|
2018-08-13 08:07:34 -03:00
|
|
|
# flaps should undeploy at the end
|
|
|
|
self.wait_servo_channel_value(servo_ch, servo_ch_min, timeout=30)
|
|
|
|
|
|
|
|
# do a short flight in FBWA, watching for flaps
|
|
|
|
# self.mavproxy.send('switch 4\n')
|
|
|
|
# self.wait_mode('FBWA')
|
2019-11-08 02:22:30 -04:00
|
|
|
# self.delay_sim_time(10)
|
2018-08-13 08:07:34 -03:00
|
|
|
# self.mavproxy.send('switch 6\n')
|
|
|
|
# self.wait_mode('MANUAL')
|
2019-11-08 02:22:30 -04:00
|
|
|
# self.delay_sim_time(10)
|
2018-08-13 08:07:34 -03:00
|
|
|
|
|
|
|
self.progress("Flaps OK")
|
|
|
|
except Exception as e:
|
2021-02-12 22:38:42 -04:00
|
|
|
self.print_exception_caught(e)
|
2018-08-13 08:07:34 -03:00
|
|
|
ex = e
|
|
|
|
self.context_pop()
|
|
|
|
if ex:
|
2018-09-07 08:15:02 -03:00
|
|
|
if self.armed():
|
|
|
|
self.disarm_vehicle()
|
2018-08-13 08:07:34 -03:00
|
|
|
raise ex
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def TestRCRelay(self):
|
|
|
|
'''Test Relay RC Channel Option'''
|
2018-12-16 18:54:05 -04:00
|
|
|
self.set_parameter("RC12_OPTION", 28) # Relay On/Off
|
|
|
|
self.set_rc(12, 1000)
|
|
|
|
self.reboot_sitl() # needed for RC12_OPTION to take effect
|
|
|
|
|
2018-08-03 07:16:10 -03:00
|
|
|
off = self.get_parameter("SIM_PIN_MASK")
|
|
|
|
if off:
|
2018-10-17 23:55:16 -03:00
|
|
|
raise PreconditionFailedException("SIM_MASK_PIN off")
|
2018-12-16 18:54:05 -04:00
|
|
|
|
|
|
|
# allow time for the RC library to register initial value:
|
|
|
|
self.delay_sim_time(1)
|
|
|
|
|
2018-08-03 07:16:10 -03:00
|
|
|
self.set_rc(12, 2000)
|
2018-12-13 18:17:02 -04:00
|
|
|
self.wait_heartbeat()
|
|
|
|
self.wait_heartbeat()
|
2018-12-16 18:54:05 -04:00
|
|
|
|
2018-08-03 07:16:10 -03:00
|
|
|
on = self.get_parameter("SIM_PIN_MASK")
|
|
|
|
if not on:
|
2018-10-17 23:55:16 -03:00
|
|
|
raise NotAchievedException("SIM_PIN_MASK doesn't reflect ON")
|
2018-08-03 07:16:10 -03:00
|
|
|
self.set_rc(12, 1000)
|
2018-12-13 18:17:02 -04:00
|
|
|
self.wait_heartbeat()
|
|
|
|
self.wait_heartbeat()
|
2018-08-03 07:16:10 -03:00
|
|
|
off = self.get_parameter("SIM_PIN_MASK")
|
|
|
|
if off:
|
2018-10-17 23:55:16 -03:00
|
|
|
raise NotAchievedException("SIM_PIN_MASK doesn't reflect OFF")
|
2018-08-03 07:16:10 -03:00
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def TestRCCamera(self):
|
|
|
|
'''Test RC Option - Camera Trigger'''
|
2018-12-16 18:54:05 -04:00
|
|
|
self.set_parameter("RC12_OPTION", 9) # CameraTrigger
|
2023-02-14 02:09:06 -04:00
|
|
|
self.set_parameter("CAM1_TYPE", 1) # Camera with servo trigger
|
2018-12-16 18:54:05 -04:00
|
|
|
self.reboot_sitl() # needed for RC12_OPTION to take effect
|
|
|
|
|
2018-08-03 07:50:15 -03:00
|
|
|
x = self.mav.messages.get("CAMERA_FEEDBACK", None)
|
|
|
|
if x is not None:
|
2018-10-17 23:55:16 -03:00
|
|
|
raise PreconditionFailedException("Receiving CAMERA_FEEDBACK?!")
|
2018-08-03 07:50:15 -03:00
|
|
|
self.set_rc(12, 2000)
|
|
|
|
tstart = self.get_sim_time()
|
2019-03-07 18:34:09 -04:00
|
|
|
while self.get_sim_time_cached() - tstart < 10:
|
2018-08-03 07:50:15 -03:00
|
|
|
x = self.mav.messages.get("CAMERA_FEEDBACK", None)
|
|
|
|
if x is not None:
|
|
|
|
break
|
2018-12-13 18:17:02 -04:00
|
|
|
self.wait_heartbeat()
|
2018-08-03 07:50:15 -03:00
|
|
|
self.set_rc(12, 1000)
|
|
|
|
if x is None:
|
2018-10-17 23:55:16 -03:00
|
|
|
raise NotAchievedException("No CAMERA_FEEDBACK message received")
|
2018-08-03 07:50:15 -03:00
|
|
|
|
2021-09-29 06:31:43 -03:00
|
|
|
self.wait_ready_to_arm()
|
|
|
|
|
|
|
|
original_alt = self.get_altitude()
|
|
|
|
|
|
|
|
takeoff_alt = 30
|
|
|
|
self.takeoff(takeoff_alt)
|
|
|
|
self.set_rc(12, 2000)
|
|
|
|
self.delay_sim_time(1)
|
|
|
|
self.set_rc(12, 1000)
|
|
|
|
x = self.mav.messages.get("CAMERA_FEEDBACK", None)
|
|
|
|
if abs(x.alt_rel - takeoff_alt) > 10:
|
|
|
|
raise NotAchievedException("Bad relalt (want=%f vs got=%f)" % (takeoff_alt, x.alt_rel))
|
|
|
|
if abs(x.alt_msl - (original_alt+30)) > 10:
|
|
|
|
raise NotAchievedException("Bad absalt (want=%f vs got=%f)" % (original_alt+30, x.alt_msl))
|
|
|
|
self.fly_home_land_and_disarm()
|
|
|
|
|
2022-02-24 22:23:57 -04:00
|
|
|
def ThrottleFailsafe(self):
|
2022-09-09 22:24:28 -03:00
|
|
|
'''Fly throttle failsafe'''
|
2018-08-20 21:55:59 -03:00
|
|
|
self.change_mode('MANUAL')
|
|
|
|
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
|
|
|
|
receiver_bit = mavutil.mavlink.MAV_SYS_STATUS_SENSOR_RC_RECEIVER
|
|
|
|
self.progress("Testing receiver enabled")
|
|
|
|
if (not (m.onboard_control_sensors_enabled & receiver_bit)):
|
|
|
|
raise PreconditionFailedException()
|
|
|
|
self.progress("Testing receiver present")
|
|
|
|
if (not (m.onboard_control_sensors_present & receiver_bit)):
|
|
|
|
raise PreconditionFailedException()
|
|
|
|
self.progress("Testing receiver health")
|
|
|
|
if (not (m.onboard_control_sensors_health & receiver_bit)):
|
|
|
|
raise PreconditionFailedException()
|
|
|
|
|
|
|
|
self.progress("Ensure we know original throttle value")
|
|
|
|
self.wait_rc_channel_value(3, 1000)
|
|
|
|
|
|
|
|
self.set_parameter("THR_FS_VALUE", 960)
|
|
|
|
self.progress("Failing receiver (throttle-to-950)")
|
2020-09-07 03:57:10 -03:00
|
|
|
self.context_collect("HEARTBEAT")
|
2018-08-20 21:55:59 -03:00
|
|
|
self.set_parameter("SIM_RC_FAIL", 2) # throttle-to-950
|
|
|
|
self.wait_mode('RTL') # long failsafe
|
2023-08-31 18:46:25 -03:00
|
|
|
if (self.get_mode_from_mode_mapping("CIRCLE") not in
|
2021-02-11 22:44:28 -04:00
|
|
|
[x.custom_mode for x in self.context_stop_collecting("HEARTBEAT")]):
|
2020-09-07 03:57:10 -03:00
|
|
|
raise NotAchievedException("Did not go via circle mode")
|
2018-08-20 21:55:59 -03:00
|
|
|
self.progress("Ensure we've had our throttle squashed to 950")
|
|
|
|
self.wait_rc_channel_value(3, 950)
|
2022-07-19 21:57:18 -03:00
|
|
|
self.do_timesync_roundtrip()
|
|
|
|
m = self.assert_receive_message('SYS_STATUS')
|
2021-01-07 19:27:27 -04:00
|
|
|
self.progress("Got (%s)" % str(m))
|
2018-08-20 21:55:59 -03:00
|
|
|
self.progress("Testing receiver enabled")
|
|
|
|
if (not (m.onboard_control_sensors_enabled & receiver_bit)):
|
|
|
|
raise NotAchievedException("Receiver not enabled")
|
|
|
|
self.progress("Testing receiver present")
|
|
|
|
if (not (m.onboard_control_sensors_present & receiver_bit)):
|
|
|
|
raise NotAchievedException("Receiver not present")
|
2019-02-13 18:50:46 -04:00
|
|
|
# skip this until RC is fixed
|
|
|
|
# self.progress("Testing receiver health")
|
|
|
|
# if (m.onboard_control_sensors_health & receiver_bit):
|
|
|
|
# raise NotAchievedException("Sensor healthy when it shouldn't be")
|
2018-08-20 21:55:59 -03:00
|
|
|
self.set_parameter("SIM_RC_FAIL", 0)
|
2019-09-16 22:46:47 -03:00
|
|
|
# have to allow time for RC to be fetched from SITL
|
|
|
|
self.delay_sim_time(0.5)
|
2022-07-19 21:57:18 -03:00
|
|
|
self.do_timesync_roundtrip()
|
|
|
|
m = self.assert_receive_message('SYS_STATUS')
|
2018-08-20 21:55:59 -03:00
|
|
|
self.progress("Testing receiver enabled")
|
|
|
|
if (not (m.onboard_control_sensors_enabled & receiver_bit)):
|
|
|
|
raise NotAchievedException("Receiver not enabled")
|
|
|
|
self.progress("Testing receiver present")
|
|
|
|
if (not (m.onboard_control_sensors_present & receiver_bit)):
|
|
|
|
raise NotAchievedException("Receiver not present")
|
|
|
|
self.progress("Testing receiver health")
|
|
|
|
if (not (m.onboard_control_sensors_health & receiver_bit)):
|
2019-08-26 03:37:42 -03:00
|
|
|
raise NotAchievedException("Receiver not healthy2")
|
2018-08-20 21:55:59 -03:00
|
|
|
self.change_mode('MANUAL')
|
|
|
|
|
|
|
|
self.progress("Failing receiver (no-pulses)")
|
2020-09-07 03:57:10 -03:00
|
|
|
self.context_collect("HEARTBEAT")
|
2018-08-20 21:55:59 -03:00
|
|
|
self.set_parameter("SIM_RC_FAIL", 1) # no-pulses
|
|
|
|
self.wait_mode('RTL') # long failsafe
|
2023-08-31 18:46:25 -03:00
|
|
|
if (self.get_mode_from_mode_mapping("CIRCLE") not in
|
2021-02-11 22:44:28 -04:00
|
|
|
[x.custom_mode for x in self.context_stop_collecting("HEARTBEAT")]):
|
2020-09-07 03:57:10 -03:00
|
|
|
raise NotAchievedException("Did not go via circle mode")
|
2022-07-19 21:57:18 -03:00
|
|
|
self.do_timesync_roundtrip()
|
|
|
|
m = self.assert_receive_message('SYS_STATUS')
|
2021-01-07 19:27:27 -04:00
|
|
|
self.progress("Got (%s)" % str(m))
|
2018-08-20 21:55:59 -03:00
|
|
|
self.progress("Testing receiver enabled")
|
|
|
|
if (not (m.onboard_control_sensors_enabled & receiver_bit)):
|
|
|
|
raise NotAchievedException("Receiver not enabled")
|
|
|
|
self.progress("Testing receiver present")
|
|
|
|
if (not (m.onboard_control_sensors_present & receiver_bit)):
|
|
|
|
raise NotAchievedException("Receiver not present")
|
|
|
|
self.progress("Testing receiver health")
|
|
|
|
if (m.onboard_control_sensors_health & receiver_bit):
|
|
|
|
raise NotAchievedException("Sensor healthy when it shouldn't be")
|
2019-03-07 19:06:46 -04:00
|
|
|
self.progress("Making RC work again")
|
2018-08-20 21:55:59 -03:00
|
|
|
self.set_parameter("SIM_RC_FAIL", 0)
|
2019-10-06 18:17:12 -03:00
|
|
|
# have to allow time for RC to be fetched from SITL
|
2019-02-26 00:29:12 -04:00
|
|
|
self.progress("Giving receiver time to recover")
|
2019-10-06 18:17:12 -03:00
|
|
|
self.delay_sim_time(0.5)
|
2022-07-19 21:57:18 -03:00
|
|
|
self.do_timesync_roundtrip()
|
|
|
|
m = self.assert_receive_message('SYS_STATUS')
|
2018-08-20 21:55:59 -03:00
|
|
|
self.progress("Testing receiver enabled")
|
|
|
|
if (not (m.onboard_control_sensors_enabled & receiver_bit)):
|
|
|
|
raise NotAchievedException("Receiver not enabled")
|
|
|
|
self.progress("Testing receiver present")
|
|
|
|
if (not (m.onboard_control_sensors_present & receiver_bit)):
|
|
|
|
raise NotAchievedException("Receiver not present")
|
|
|
|
self.progress("Testing receiver health")
|
|
|
|
if (not (m.onboard_control_sensors_health & receiver_bit)):
|
|
|
|
raise NotAchievedException("Receiver not healthy")
|
|
|
|
self.change_mode('MANUAL')
|
|
|
|
|
2019-08-14 20:51:23 -03:00
|
|
|
self.progress("Ensure long failsafe can trigger when short failsafe disabled")
|
|
|
|
self.context_push()
|
2020-09-07 03:57:10 -03:00
|
|
|
self.context_collect("STATUSTEXT")
|
2019-08-14 20:51:23 -03:00
|
|
|
ex = None
|
|
|
|
try:
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"FS_SHORT_ACTN": 3, # 3 means disabled
|
|
|
|
"SIM_RC_FAIL": 1,
|
|
|
|
})
|
2022-02-26 09:40:12 -04:00
|
|
|
self.wait_statustext("Long failsafe on", check_context=True)
|
2019-08-20 23:22:34 -03:00
|
|
|
self.wait_mode("RTL")
|
2020-09-07 03:57:10 -03:00
|
|
|
# self.context_clear_collection("STATUSTEXT")
|
2019-08-20 23:22:34 -03:00
|
|
|
self.set_parameter("SIM_RC_FAIL", 0)
|
2022-02-26 09:40:12 -04:00
|
|
|
self.wait_text("Long Failsafe Cleared", check_context=True)
|
2019-08-20 23:22:34 -03:00
|
|
|
self.change_mode("MANUAL")
|
|
|
|
|
|
|
|
self.progress("Trying again with THR_FS_VALUE")
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"THR_FS_VALUE": 960,
|
|
|
|
"SIM_RC_FAIL": 2,
|
|
|
|
})
|
2022-02-26 09:40:12 -04:00
|
|
|
self.wait_statustext("Long Failsafe on", check_context=True)
|
2019-08-20 23:22:34 -03:00
|
|
|
self.wait_mode("RTL")
|
2019-08-14 20:51:23 -03:00
|
|
|
except Exception as e:
|
2021-02-12 22:38:42 -04:00
|
|
|
self.print_exception_caught(e)
|
2019-08-14 20:51:23 -03:00
|
|
|
ex = e
|
|
|
|
self.context_pop()
|
|
|
|
if ex is not None:
|
|
|
|
raise ex
|
|
|
|
|
2022-02-24 22:23:57 -04:00
|
|
|
self.start_subtest("Not use RC throttle input when THR_FAILSAFE==2")
|
|
|
|
self.takeoff(100)
|
|
|
|
self.set_rc(3, 1800)
|
|
|
|
self.set_rc(1, 2000)
|
|
|
|
self.wait_attitude(desroll=45, timeout=1)
|
|
|
|
self.context_push()
|
|
|
|
self.set_parameters({
|
|
|
|
"THR_FAILSAFE": 2,
|
|
|
|
"SIM_RC_FAIL": 1, # no pulses
|
|
|
|
})
|
|
|
|
self.delay_sim_time(1)
|
|
|
|
self.wait_attitude(desroll=0, timeout=5)
|
|
|
|
self.assert_servo_channel_value(3, self.get_parameter("RC3_MIN"))
|
|
|
|
self.set_parameters({
|
|
|
|
"SIM_RC_FAIL": 0, # fix receiver
|
|
|
|
})
|
|
|
|
self.zero_throttle()
|
2022-03-08 17:15:15 -04:00
|
|
|
self.disarm_vehicle(force=True)
|
2022-02-24 22:23:57 -04:00
|
|
|
self.context_pop()
|
|
|
|
self.reboot_sitl()
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def ThrottleFailsafeFence(self):
|
|
|
|
'''Fly fence survives throttle failsafe'''
|
2019-11-02 19:08:07 -03:00
|
|
|
fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE
|
|
|
|
|
|
|
|
self.progress("Checking fence is not present before being configured")
|
|
|
|
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
|
2021-01-07 19:27:27 -04:00
|
|
|
self.progress("Got (%s)" % str(m))
|
2019-11-02 19:08:07 -03:00
|
|
|
if (m.onboard_control_sensors_enabled & fence_bit):
|
|
|
|
raise NotAchievedException("Fence enabled before being configured")
|
|
|
|
|
|
|
|
self.change_mode('MANUAL')
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
|
|
|
|
self.load_fence("CMAC-fence.txt")
|
|
|
|
|
2020-09-08 03:58:23 -03:00
|
|
|
self.set_parameter("RC7_OPTION", 11) # AC_Fence uses Aux switch functionality
|
|
|
|
self.set_parameter("FENCE_ACTION", 4) # Fence action Brake
|
2020-12-25 08:51:30 -04:00
|
|
|
self.set_rc_from_map({
|
|
|
|
3: 1000,
|
|
|
|
7: 2000,
|
2020-12-18 05:14:42 -04:00
|
|
|
}) # Turn fence on with aux function
|
|
|
|
|
2021-01-07 19:27:27 -04:00
|
|
|
m = self.mav.recv_match(type='FENCE_STATUS', blocking=True, timeout=2)
|
|
|
|
self.progress("Got (%s)" % str(m))
|
|
|
|
if m is None:
|
|
|
|
raise NotAchievedException("Got FENCE_STATUS unexpectedly")
|
2019-11-02 19:08:07 -03:00
|
|
|
|
|
|
|
self.progress("Checking fence is initially OK")
|
2020-12-25 08:51:30 -04:00
|
|
|
self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE,
|
|
|
|
present=True,
|
|
|
|
enabled=True,
|
|
|
|
healthy=True,
|
|
|
|
verbose=True,
|
|
|
|
timeout=30)
|
2019-11-02 19:08:07 -03:00
|
|
|
|
|
|
|
self.set_parameter("THR_FS_VALUE", 960)
|
|
|
|
self.progress("Failing receiver (throttle-to-950)")
|
|
|
|
self.set_parameter("SIM_RC_FAIL", 2) # throttle-to-950
|
|
|
|
self.wait_mode("CIRCLE")
|
|
|
|
self.delay_sim_time(1) # give
|
2022-07-19 21:57:18 -03:00
|
|
|
self.do_timesync_roundtrip()
|
2019-11-02 19:08:07 -03:00
|
|
|
|
|
|
|
self.progress("Checking fence is OK after receiver failure (bind-values)")
|
|
|
|
fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE
|
2022-07-19 21:57:18 -03:00
|
|
|
m = self.assert_receive_message('SYS_STATUS')
|
2019-11-02 19:08:07 -03:00
|
|
|
if (not (m.onboard_control_sensors_enabled & fence_bit)):
|
|
|
|
raise NotAchievedException("Fence not enabled after RC fail")
|
2021-01-22 00:33:09 -04:00
|
|
|
self.do_fence_disable() # Ensure the fence is disabled after test
|
2019-11-02 19:08:07 -03:00
|
|
|
|
2023-02-25 14:22:41 -04:00
|
|
|
def GCSFailsafe(self):
|
|
|
|
'''Ensure Long-Failsafe works on GCS loss'''
|
|
|
|
self.start_subtest("Test Failsafe: RTL")
|
|
|
|
self.load_sample_mission()
|
2023-02-26 02:25:15 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"FS_GCS_ENABL": 1,
|
|
|
|
"FS_LONG_ACTN": 1,
|
2023-07-27 23:20:58 -03:00
|
|
|
"RTL_AUTOLAND": 1,
|
|
|
|
"SYSID_MYGCS": self.mav.source_system,
|
2023-02-26 02:25:15 -04:00
|
|
|
})
|
2023-07-27 23:20:58 -03:00
|
|
|
self.takeoff()
|
|
|
|
self.change_mode('LOITER')
|
2023-02-25 14:22:41 -04:00
|
|
|
self.progress("Disconnecting GCS")
|
|
|
|
self.set_heartbeat_rate(0)
|
2023-07-27 23:20:58 -03:00
|
|
|
self.wait_mode("RTL", timeout=10)
|
2023-02-25 14:22:41 -04:00
|
|
|
self.set_heartbeat_rate(self.speedup)
|
|
|
|
self.end_subtest("Completed RTL Failsafe test")
|
|
|
|
|
2023-02-25 14:25:07 -04:00
|
|
|
self.start_subtest("Test Failsafe: FBWA Glide")
|
2023-02-26 02:25:15 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"FS_LONG_ACTN": 2,
|
|
|
|
})
|
2023-07-27 23:20:58 -03:00
|
|
|
self.change_mode('AUTO')
|
2023-02-25 14:25:07 -04:00
|
|
|
self.progress("Disconnecting GCS")
|
|
|
|
self.set_heartbeat_rate(0)
|
2023-07-27 23:20:58 -03:00
|
|
|
self.wait_mode("FBWA", timeout=10)
|
2023-02-25 14:25:07 -04:00
|
|
|
self.set_heartbeat_rate(self.speedup)
|
|
|
|
self.end_subtest("Completed FBWA Failsafe test")
|
|
|
|
|
|
|
|
self.start_subtest("Test Failsafe: Deploy Parachute")
|
|
|
|
self.load_mission("plane-parachute-mission.txt")
|
|
|
|
self.set_current_waypoint(1)
|
|
|
|
self.set_parameters({
|
|
|
|
"CHUTE_ENABLED": 1,
|
|
|
|
"CHUTE_TYPE": 10,
|
|
|
|
"SERVO9_FUNCTION": 27,
|
|
|
|
"SIM_PARA_ENABLE": 1,
|
|
|
|
"SIM_PARA_PIN": 9,
|
2023-02-26 02:25:15 -04:00
|
|
|
"FS_LONG_ACTN": 3,
|
2023-02-25 14:25:07 -04:00
|
|
|
})
|
|
|
|
self.change_mode("AUTO")
|
|
|
|
self.progress("Disconnecting GCS")
|
|
|
|
self.set_heartbeat_rate(0)
|
|
|
|
self.wait_statustext("BANG", timeout=60)
|
|
|
|
self.set_heartbeat_rate(self.speedup)
|
|
|
|
self.disarm_vehicle(force=True)
|
|
|
|
self.reboot_sitl()
|
|
|
|
self.end_subtest("Completed Parachute Failsafe test")
|
2023-02-25 14:22:41 -04:00
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def TestGripperMission(self):
|
|
|
|
'''Test Gripper mission items'''
|
2018-10-23 01:56:36 -03:00
|
|
|
self.context_push()
|
|
|
|
ex = None
|
|
|
|
try:
|
2022-03-13 00:16:27 -04:00
|
|
|
self.set_parameter("RTL_AUTOLAND", 1)
|
2018-11-09 08:32:02 -04:00
|
|
|
self.load_mission("plane-gripper-mission.txt")
|
2021-02-18 06:32:49 -04:00
|
|
|
self.set_current_waypoint(1)
|
2018-12-16 18:54:05 -04:00
|
|
|
self.change_mode('AUTO')
|
2018-10-23 01:56:36 -03:00
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
2021-02-16 21:53:13 -04:00
|
|
|
self.wait_statustext("Gripper Grabbed", timeout=60)
|
|
|
|
self.wait_statustext("Gripper Released", timeout=60)
|
|
|
|
self.wait_statustext("Auto disarmed", timeout=60)
|
2018-10-23 01:56:36 -03:00
|
|
|
except Exception as e:
|
2021-02-12 22:38:42 -04:00
|
|
|
self.print_exception_caught(e)
|
2018-10-23 01:56:36 -03:00
|
|
|
ex = e
|
|
|
|
self.context_pop()
|
|
|
|
if ex is not None:
|
|
|
|
raise ex
|
|
|
|
|
2019-06-01 02:07:49 -03:00
|
|
|
def assert_fence_sys_status(self, present, enabled, health):
|
|
|
|
self.delay_sim_time(1)
|
2022-07-19 21:57:18 -03:00
|
|
|
self.do_timesync_roundtrip()
|
2022-02-09 20:59:34 -04:00
|
|
|
m = self.assert_receive_message('SYS_STATUS', timeout=1)
|
2021-02-11 22:44:28 -04:00
|
|
|
tests = [
|
|
|
|
("present", present, m.onboard_control_sensors_present),
|
|
|
|
("enabled", enabled, m.onboard_control_sensors_enabled),
|
|
|
|
("health", health, m.onboard_control_sensors_health),
|
|
|
|
]
|
2019-06-01 02:07:49 -03:00
|
|
|
bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE
|
|
|
|
for test in tests:
|
|
|
|
(name, want, field) = test
|
|
|
|
got = (field & bit) != 0
|
|
|
|
if want != got:
|
|
|
|
raise NotAchievedException("fence status incorrect; %s want=%u got=%u" %
|
|
|
|
(name, want, got))
|
|
|
|
|
2019-06-25 06:23:22 -03:00
|
|
|
def wait_circling_point_with_radius(self, loc, want_radius, epsilon=5.0, min_circle_time=5, timeout=120):
|
2019-06-01 02:07:49 -03:00
|
|
|
on_radius_start_heading = None
|
|
|
|
average_radius = 0.0
|
|
|
|
circle_time_start = 0
|
|
|
|
done_time = False
|
|
|
|
done_angle = False
|
2019-06-25 06:23:22 -03:00
|
|
|
tstart = self.get_sim_time()
|
2019-06-01 02:07:49 -03:00
|
|
|
while True:
|
2019-06-25 06:23:22 -03:00
|
|
|
if self.get_sim_time() - tstart > timeout:
|
|
|
|
raise AutoTestTimeoutException("Did not get onto circle")
|
2019-06-01 02:07:49 -03:00
|
|
|
here = self.mav.location()
|
|
|
|
got_radius = self.get_distance(loc, here)
|
|
|
|
average_radius = 0.95*average_radius + 0.05*got_radius
|
|
|
|
on_radius = abs(got_radius - want_radius) < epsilon
|
|
|
|
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
|
|
|
|
heading = m.heading
|
|
|
|
on_string = "off"
|
|
|
|
got_angle = ""
|
|
|
|
if on_radius_start_heading is not None:
|
|
|
|
got_angle = "%0.2f" % abs(on_radius_start_heading - heading) # FIXME
|
|
|
|
on_string = "on"
|
|
|
|
|
|
|
|
want_angle = 180 # we don't actually get this (angle-substraction issue. But we get enough...
|
|
|
|
self.progress("wait-circling: got-r=%0.2f want-r=%f avg-r=%f %s want-a=%0.1f got-a=%s" %
|
|
|
|
(got_radius, want_radius, average_radius, on_string, want_angle, got_angle))
|
|
|
|
if on_radius:
|
|
|
|
if on_radius_start_heading is None:
|
|
|
|
on_radius_start_heading = heading
|
|
|
|
average_radius = got_radius
|
|
|
|
circle_time_start = self.get_sim_time()
|
|
|
|
continue
|
|
|
|
if abs(on_radius_start_heading - heading) > want_angle: # FIXME
|
|
|
|
done_angle = True
|
|
|
|
if self.get_sim_time() - circle_time_start > min_circle_time:
|
|
|
|
done_time = True
|
|
|
|
if done_time and done_angle:
|
|
|
|
return
|
|
|
|
continue
|
|
|
|
if on_radius_start_heading is not None:
|
|
|
|
average_radius = 0.0
|
|
|
|
on_radius_start_heading = None
|
|
|
|
circle_time_start = 0
|
|
|
|
|
2022-07-13 22:09:08 -03:00
|
|
|
def MODE_SWITCH_RESET(self):
|
|
|
|
'''test the MODE_SWITCH_RESET auxiliary function'''
|
|
|
|
self.set_parameters({
|
|
|
|
"RC9_OPTION": 96,
|
|
|
|
})
|
|
|
|
|
|
|
|
self.progress("Using RC to change modes")
|
|
|
|
self.set_rc(8, 1500)
|
|
|
|
self.wait_mode('FBWA')
|
|
|
|
|
|
|
|
self.progress("Killing RC to engage RC failsafe")
|
|
|
|
self.set_parameter('SIM_RC_FAIL', 1)
|
|
|
|
self.wait_mode('RTL')
|
|
|
|
|
|
|
|
self.progress("Reinstating RC")
|
|
|
|
self.set_parameter('SIM_RC_FAIL', 0)
|
|
|
|
|
|
|
|
self.progress("Ensuring we don't automatically revert mode")
|
|
|
|
self.delay_sim_time(2)
|
|
|
|
self.assert_mode_is('RTL')
|
|
|
|
|
|
|
|
self.progress("Ensuring MODE_SWITCH_RESET switch resets to pre-failsafe mode")
|
|
|
|
self.set_rc(9, 2000)
|
|
|
|
self.wait_mode('FBWA')
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def FenceStatic(self):
|
|
|
|
'''Test Basic Fence Functionality'''
|
2019-06-01 02:07:49 -03:00
|
|
|
ex = None
|
|
|
|
try:
|
|
|
|
self.progress("Checking for bizarre healthy-when-not-present-or-enabled")
|
2020-12-18 05:14:42 -04:00
|
|
|
self.set_parameter("FENCE_TYPE", 4) # Start by only setting polygon fences, otherwise fence will report present
|
2019-06-01 02:07:49 -03:00
|
|
|
self.assert_fence_sys_status(False, False, True)
|
2019-08-05 01:43:27 -03:00
|
|
|
self.load_fence("CMAC-fence.txt")
|
2019-06-01 02:07:49 -03:00
|
|
|
m = self.mav.recv_match(type='FENCE_STATUS', blocking=True, timeout=2)
|
|
|
|
if m is not None:
|
2021-02-11 22:44:28 -04:00
|
|
|
raise NotAchievedException("Got FENCE_STATUS unexpectedly")
|
2020-09-08 03:58:23 -03:00
|
|
|
self.set_parameter("FENCE_ACTION", 0) # report only
|
|
|
|
self.assert_fence_sys_status(True, False, True)
|
|
|
|
self.set_parameter("FENCE_ACTION", 1) # RTL
|
2019-06-01 02:07:49 -03:00
|
|
|
self.assert_fence_sys_status(True, False, True)
|
2021-02-28 20:49:18 -04:00
|
|
|
self.do_fence_enable()
|
2019-06-01 02:07:49 -03:00
|
|
|
self.assert_fence_sys_status(True, True, True)
|
2022-02-09 20:59:34 -04:00
|
|
|
m = self.assert_receive_message('FENCE_STATUS', timeout=2)
|
2019-06-01 02:07:49 -03:00
|
|
|
if m.breach_status:
|
|
|
|
raise NotAchievedException("Breached fence unexpectedly (%u)" %
|
|
|
|
(m.breach_status))
|
2021-02-28 20:49:18 -04:00
|
|
|
self.do_fence_disable()
|
2019-06-01 02:07:49 -03:00
|
|
|
self.assert_fence_sys_status(True, False, True)
|
2020-09-08 03:58:23 -03:00
|
|
|
self.set_parameter("FENCE_ACTION", 1)
|
|
|
|
self.assert_fence_sys_status(True, False, True)
|
|
|
|
self.set_parameter("FENCE_ACTION", 0)
|
2019-06-01 02:07:49 -03:00
|
|
|
self.assert_fence_sys_status(True, False, True)
|
2021-02-28 20:49:18 -04:00
|
|
|
self.clear_fence()
|
2019-06-01 02:07:49 -03:00
|
|
|
if self.get_parameter("FENCE_TOTAL") != 0:
|
|
|
|
raise NotAchievedException("Expected zero points remaining")
|
|
|
|
self.assert_fence_sys_status(False, False, True)
|
|
|
|
self.progress("Trying to enable fence with no points")
|
|
|
|
self.do_fence_enable(want_result=mavutil.mavlink.MAV_RESULT_FAILED)
|
|
|
|
|
|
|
|
# test a rather unfortunate behaviour:
|
|
|
|
self.progress("Killing a live fence with fence-clear")
|
2019-08-05 01:43:27 -03:00
|
|
|
self.load_fence("CMAC-fence.txt")
|
2021-02-15 23:20:56 -04:00
|
|
|
self.set_parameter("FENCE_ACTION", 1) # AC_FENCE_ACTION_RTL_AND_LAND == 1. mavutil.mavlink.FENCE_ACTION_RTL == 4
|
2019-06-01 02:07:49 -03:00
|
|
|
self.do_fence_enable()
|
|
|
|
self.assert_fence_sys_status(True, True, True)
|
2021-02-28 20:49:18 -04:00
|
|
|
self.clear_fence()
|
2021-01-17 21:05:46 -04:00
|
|
|
self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE, False, False, True)
|
2019-06-01 02:07:49 -03:00
|
|
|
if self.get_parameter("FENCE_TOTAL") != 0:
|
|
|
|
raise NotAchievedException("Expected zero points remaining")
|
2020-12-18 05:14:42 -04:00
|
|
|
self.assert_fence_sys_status(False, False, True)
|
|
|
|
self.do_fence_disable()
|
|
|
|
|
|
|
|
# ensure that a fence is present if it is tin can, min alt or max alt
|
|
|
|
self.progress("Test other fence types (tin-can, min alt, max alt")
|
|
|
|
self.set_parameter("FENCE_TYPE", 1) # max alt
|
|
|
|
self.assert_fence_sys_status(True, False, True)
|
|
|
|
self.set_parameter("FENCE_TYPE", 8) # min alt
|
|
|
|
self.assert_fence_sys_status(True, False, True)
|
|
|
|
self.set_parameter("FENCE_TYPE", 2) # tin can
|
|
|
|
self.assert_fence_sys_status(True, False, True)
|
|
|
|
|
2021-02-15 23:20:56 -04:00
|
|
|
# Test cannot arm if outside of fence and fence is enabled
|
|
|
|
self.progress("Test Arming while vehicle below FENCE_ALT_MIN")
|
|
|
|
default_fence_alt_min = self.get_parameter("FENCE_ALT_MIN")
|
|
|
|
self.set_parameter("FENCE_ALT_MIN", 50)
|
|
|
|
self.set_parameter("FENCE_TYPE", 8) # Enables minimum altitude breaches
|
|
|
|
self.do_fence_enable()
|
2021-02-16 04:32:54 -04:00
|
|
|
self.delay_sim_time(2) # Allow breach to propagate
|
2021-02-15 23:20:56 -04:00
|
|
|
self.assert_fence_enabled()
|
2021-02-16 04:32:54 -04:00
|
|
|
|
2021-02-15 23:20:56 -04:00
|
|
|
self.try_arm(False, "vehicle outside fence")
|
|
|
|
self.do_fence_disable()
|
|
|
|
self.set_parameter("FENCE_ALT_MIN", default_fence_alt_min)
|
|
|
|
|
|
|
|
# Test arming outside inclusion zone
|
|
|
|
self.progress("Test arming while vehicle outside of inclusion zone")
|
|
|
|
self.set_parameter("FENCE_TYPE", 4) # Enables polygon fence types
|
|
|
|
locs = [
|
2021-02-18 01:49:25 -04:00
|
|
|
mavutil.location(1.000, 1.000, 0, 0),
|
|
|
|
mavutil.location(1.000, 1.001, 0, 0),
|
2021-02-15 23:20:56 -04:00
|
|
|
mavutil.location(1.001, 1.001, 0, 0),
|
2021-02-18 01:49:25 -04:00
|
|
|
mavutil.location(1.001, 1.000, 0, 0)
|
2021-02-15 23:20:56 -04:00
|
|
|
]
|
|
|
|
self.upload_fences_from_locations(
|
2021-02-18 01:49:25 -04:00
|
|
|
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,
|
2021-02-16 04:32:54 -04:00
|
|
|
[
|
|
|
|
locs
|
|
|
|
]
|
|
|
|
)
|
2021-02-15 23:20:56 -04:00
|
|
|
self.delay_sim_time(10) # let fence check run so it loads-from-eeprom
|
|
|
|
self.do_fence_enable()
|
|
|
|
self.assert_fence_enabled()
|
2021-02-16 04:32:54 -04:00
|
|
|
self.delay_sim_time(2) # Allow breach to propagate
|
2021-02-15 23:20:56 -04:00
|
|
|
self.try_arm(False, "vehicle outside fence")
|
|
|
|
self.do_fence_disable()
|
|
|
|
self.clear_fence()
|
|
|
|
|
|
|
|
self.progress("Test arming while vehicle inside exclusion zone")
|
|
|
|
self.set_parameter("FENCE_TYPE", 4) # Enables polygon fence types
|
|
|
|
home_loc = self.mav.location()
|
|
|
|
locs = [
|
|
|
|
mavutil.location(home_loc.lat - 0.001, home_loc.lng - 0.001, 0, 0),
|
|
|
|
mavutil.location(home_loc.lat - 0.001, home_loc.lng + 0.001, 0, 0),
|
|
|
|
mavutil.location(home_loc.lat + 0.001, home_loc.lng + 0.001, 0, 0),
|
|
|
|
mavutil.location(home_loc.lat + 0.001, home_loc.lng - 0.001, 0, 0),
|
|
|
|
]
|
|
|
|
self.upload_fences_from_locations(
|
2021-02-18 01:49:25 -04:00
|
|
|
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION,
|
2021-02-16 04:32:54 -04:00
|
|
|
[
|
|
|
|
locs
|
|
|
|
]
|
|
|
|
)
|
2021-02-15 23:20:56 -04:00
|
|
|
self.delay_sim_time(10) # let fence check run so it loads-from-eeprom
|
|
|
|
self.do_fence_enable()
|
|
|
|
self.assert_fence_enabled()
|
2021-02-16 04:32:54 -04:00
|
|
|
self.delay_sim_time(2) # Allow breach to propagate
|
2021-02-15 23:20:56 -04:00
|
|
|
self.try_arm(False, "vehicle outside fence")
|
|
|
|
self.do_fence_disable()
|
|
|
|
self.clear_fence()
|
|
|
|
|
2019-06-01 02:07:49 -03:00
|
|
|
except Exception as e:
|
2021-02-12 22:38:42 -04:00
|
|
|
self.print_exception_caught(e)
|
2019-06-01 02:07:49 -03:00
|
|
|
ex = e
|
2021-02-28 20:49:18 -04:00
|
|
|
self.clear_fence()
|
2019-06-01 02:07:49 -03:00
|
|
|
if ex is not None:
|
|
|
|
raise ex
|
|
|
|
|
2019-06-13 23:02:12 -03:00
|
|
|
def test_fence_breach_circle_at(self, loc, disable_on_breach=False):
|
2019-06-01 02:07:49 -03:00
|
|
|
ex = None
|
|
|
|
try:
|
2019-08-05 01:43:27 -03:00
|
|
|
self.load_fence("CMAC-fence.txt")
|
2019-06-01 02:07:49 -03:00
|
|
|
want_radius = 100
|
|
|
|
# when ArduPlane is fixed, remove this fudge factor
|
|
|
|
REALLY_BAD_FUDGE_FACTOR = 1.16
|
|
|
|
expected_radius = REALLY_BAD_FUDGE_FACTOR * want_radius
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"RTL_RADIUS": want_radius,
|
|
|
|
"NAVL1_LIM_BANK": 60,
|
|
|
|
"FENCE_ACTION": 1, # AC_FENCE_ACTION_RTL_AND_LAND == 1. mavutil.mavlink.FENCE_ACTION_RTL == 4
|
|
|
|
})
|
2019-06-01 02:07:49 -03:00
|
|
|
|
2021-08-12 03:01:51 -03:00
|
|
|
self.wait_ready_to_arm() # need an origin to load fence
|
|
|
|
|
2019-06-01 02:07:49 -03:00
|
|
|
self.do_fence_enable()
|
|
|
|
self.assert_fence_sys_status(True, True, True)
|
|
|
|
|
|
|
|
self.takeoff(alt=45, alt_max=300)
|
|
|
|
|
|
|
|
tstart = self.get_sim_time()
|
|
|
|
while True:
|
|
|
|
if self.get_sim_time() - tstart > 30:
|
|
|
|
raise NotAchievedException("Did not breach fence")
|
2022-02-09 20:59:34 -04:00
|
|
|
m = self.assert_receive_message('FENCE_STATUS', timeout=2)
|
2019-06-01 02:07:49 -03:00
|
|
|
if m.breach_status == 0:
|
|
|
|
continue
|
|
|
|
|
|
|
|
# we've breached; check our state;
|
|
|
|
if m.breach_type != mavutil.mavlink.FENCE_BREACH_BOUNDARY:
|
|
|
|
raise NotAchievedException("Unexpected breach type %u" %
|
|
|
|
(m.breach_type,))
|
|
|
|
if m.breach_count == 0:
|
|
|
|
raise NotAchievedException("Unexpected breach count %u" %
|
|
|
|
(m.breach_count,))
|
|
|
|
self.assert_fence_sys_status(True, True, False)
|
|
|
|
break
|
|
|
|
|
2019-06-13 23:02:12 -03:00
|
|
|
if disable_on_breach:
|
|
|
|
self.do_fence_disable()
|
|
|
|
|
2019-06-01 02:07:49 -03:00
|
|
|
self.wait_circling_point_with_radius(loc, expected_radius)
|
|
|
|
|
|
|
|
self.disarm_vehicle(force=True)
|
|
|
|
self.reboot_sitl()
|
|
|
|
|
|
|
|
except Exception as e:
|
2021-02-12 22:38:42 -04:00
|
|
|
self.print_exception_caught(e)
|
2019-06-01 02:07:49 -03:00
|
|
|
ex = e
|
2021-02-28 20:49:18 -04:00
|
|
|
self.clear_fence()
|
2019-06-01 02:07:49 -03:00
|
|
|
if ex is not None:
|
|
|
|
raise ex
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def FenceRTL(self):
|
|
|
|
'''Test Fence RTL'''
|
2019-06-01 02:07:49 -03:00
|
|
|
self.progress("Testing FENCE_ACTION_RTL no rally point")
|
2019-06-13 23:02:12 -03:00
|
|
|
# have to disable the fence once we've breached or we breach
|
|
|
|
# it as part of the loiter-at-home!
|
|
|
|
self.test_fence_breach_circle_at(self.home_position_as_mav_location(),
|
|
|
|
disable_on_breach=True)
|
2019-06-01 02:07:49 -03:00
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def FenceRTLRally(self):
|
|
|
|
'''Test Fence RTL Rally'''
|
2019-06-01 02:07:49 -03:00
|
|
|
ex = None
|
|
|
|
target_system = 1
|
|
|
|
target_component = 1
|
|
|
|
try:
|
|
|
|
self.progress("Testing FENCE_ACTION_RTL with rally point")
|
|
|
|
|
|
|
|
self.wait_ready_to_arm()
|
2021-06-11 02:20:52 -03:00
|
|
|
loc = self.home_relative_loc_ne(50, -50)
|
2019-06-01 02:07:49 -03:00
|
|
|
|
|
|
|
self.set_parameter("RALLY_TOTAL", 1)
|
|
|
|
self.mav.mav.rally_point_send(target_system,
|
|
|
|
target_component,
|
|
|
|
0, # sequence number
|
|
|
|
1, # total count
|
|
|
|
int(loc.lat * 1e7),
|
|
|
|
int(loc.lng * 1e7),
|
|
|
|
15,
|
|
|
|
0, # "break" alt?!
|
|
|
|
0, # "land dir"
|
|
|
|
0) # flags
|
|
|
|
self.delay_sim_time(1)
|
2021-02-28 20:49:18 -04:00
|
|
|
if self.mavproxy is not None:
|
|
|
|
self.mavproxy.send("rally list\n")
|
2019-06-01 02:07:49 -03:00
|
|
|
self.test_fence_breach_circle_at(loc)
|
|
|
|
except Exception as e:
|
2021-02-12 22:38:42 -04:00
|
|
|
self.print_exception_caught(e)
|
2019-06-01 02:07:49 -03:00
|
|
|
ex = e
|
2021-02-28 20:49:18 -04:00
|
|
|
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
|
2019-06-01 02:07:49 -03:00
|
|
|
if ex is not None:
|
|
|
|
raise ex
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def FenceRetRally(self):
|
2021-02-16 03:14:01 -04:00
|
|
|
""" Tests the FENCE_RET_RALLY flag, either returning to fence return point,
|
|
|
|
or rally point """
|
|
|
|
target_system = 1
|
|
|
|
target_component = 1
|
|
|
|
self.progress("Testing FENCE_ACTION_RTL with fence rally point")
|
|
|
|
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.homeloc = self.mav.location()
|
|
|
|
|
|
|
|
# Grab a location for fence return point, and upload it.
|
|
|
|
fence_loc = self.home_position_as_mav_location()
|
|
|
|
self.location_offset_ne(fence_loc, 50, 50)
|
|
|
|
fence_return_mission_items = [
|
|
|
|
self.mav.mav.mission_item_int_encode(
|
|
|
|
target_system,
|
|
|
|
target_component,
|
|
|
|
0, # seq
|
|
|
|
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
|
|
|
|
mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,
|
|
|
|
0, # current
|
|
|
|
0, # autocontinue
|
|
|
|
0, # p1
|
|
|
|
0, # p2
|
|
|
|
0, # p3
|
|
|
|
0, # p4
|
2021-02-18 01:49:25 -04:00
|
|
|
int(fence_loc.lat * 1e7), # latitude
|
|
|
|
int(fence_loc.lng * 1e7), # longitude
|
2021-02-16 03:14:01 -04:00
|
|
|
0, # altitude
|
|
|
|
mavutil.mavlink.MAV_MISSION_TYPE_FENCE
|
|
|
|
)
|
|
|
|
]
|
|
|
|
self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
|
2021-02-18 01:49:25 -04:00
|
|
|
fence_return_mission_items)
|
2021-02-16 03:14:01 -04:00
|
|
|
self.delay_sim_time(1)
|
|
|
|
|
|
|
|
# Grab a location for rally point, and upload it.
|
2021-06-11 02:20:52 -03:00
|
|
|
rally_loc = self.home_relative_loc_ne(-50, 50)
|
2021-02-16 03:14:01 -04:00
|
|
|
self.set_parameter("RALLY_TOTAL", 1)
|
|
|
|
self.mav.mav.rally_point_send(target_system,
|
2021-02-18 01:49:25 -04:00
|
|
|
target_component,
|
|
|
|
0, # sequence number
|
|
|
|
1, # total count
|
|
|
|
int(rally_loc.lat * 1e7),
|
|
|
|
int(rally_loc.lng * 1e7),
|
|
|
|
15,
|
|
|
|
0, # "break" alt?!
|
|
|
|
0, # "land dir"
|
|
|
|
0) # flags
|
2021-02-16 03:14:01 -04:00
|
|
|
self.delay_sim_time(1)
|
|
|
|
|
|
|
|
return_radius = 100
|
|
|
|
return_alt = 80
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"RTL_RADIUS": return_radius,
|
|
|
|
"FENCE_ACTION": 6, # Set Fence Action to Guided
|
|
|
|
"FENCE_TYPE": 8, # Only use fence floor
|
|
|
|
"FENCE_RET_ALT": return_alt,
|
|
|
|
})
|
2021-02-16 03:14:01 -04:00
|
|
|
self.do_fence_enable()
|
|
|
|
self.assert_fence_enabled()
|
2021-02-16 04:32:54 -04:00
|
|
|
|
2021-02-16 03:14:01 -04:00
|
|
|
self.takeoff(alt=50, alt_max=300)
|
|
|
|
# Trigger fence breach, fly to rally location
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"FENCE_RET_RALLY": 1,
|
|
|
|
"FENCE_ALT_MIN": 60,
|
|
|
|
})
|
2021-02-16 03:14:01 -04:00
|
|
|
self.wait_circling_point_with_radius(rally_loc, return_radius)
|
|
|
|
self.set_parameter("FENCE_ALT_MIN", 0) # Clear fence breach
|
|
|
|
|
2022-08-08 15:31:21 -03:00
|
|
|
# 10 second fence min retrigger time
|
|
|
|
self.delay_sim_time(15)
|
|
|
|
|
2021-02-16 03:14:01 -04:00
|
|
|
# Fly up before re-triggering fence breach. Fly to fence return point
|
|
|
|
self.change_altitude(self.homeloc.alt+30)
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"FENCE_RET_RALLY": 0,
|
|
|
|
"FENCE_ALT_MIN": 60,
|
|
|
|
})
|
2021-02-16 03:14:01 -04:00
|
|
|
self.wait_altitude(altitude_min=return_alt-3,
|
2021-02-18 01:49:25 -04:00
|
|
|
altitude_max=return_alt+3,
|
|
|
|
relative=True)
|
2021-02-16 03:14:01 -04:00
|
|
|
self.wait_circling_point_with_radius(fence_loc, return_radius)
|
|
|
|
self.do_fence_disable() # Disable fence so we can land
|
|
|
|
self.fly_home_land_and_disarm() # Pack it up, we're going home.
|
|
|
|
|
2023-10-12 19:54:15 -03:00
|
|
|
def TerrainRally(self):
|
|
|
|
""" Tests terrain follow with a rally point """
|
|
|
|
self.context_push()
|
|
|
|
self.install_terrain_handlers_context()
|
|
|
|
|
|
|
|
def terrain_following_above_80m(mav, m):
|
|
|
|
if m.get_type() == 'TERRAIN_REPORT':
|
|
|
|
if m.current_height < 50:
|
|
|
|
raise NotAchievedException(
|
|
|
|
"TERRAIN_REPORT.current_height below 50m %fm" % m.current_height)
|
|
|
|
if m.get_type() == 'VFR_HUD':
|
|
|
|
if m.groundspeed < 2:
|
|
|
|
raise NotAchievedException("hit ground")
|
|
|
|
|
|
|
|
def terrain_wait_path(loc1, loc2, steps):
|
|
|
|
'''wait till we have terrain for N steps from loc1 to loc2'''
|
|
|
|
tstart = self.get_sim_time_cached()
|
|
|
|
self.progress("Waiting for terrain data")
|
|
|
|
while True:
|
|
|
|
now = self.get_sim_time_cached()
|
|
|
|
if now - tstart > 60:
|
|
|
|
raise NotAchievedException("Did not get correct required terrain")
|
|
|
|
for i in range(steps):
|
|
|
|
lat = loc1.lat + i * (loc2.lat-loc1.lat)/steps
|
|
|
|
lon = loc1.lng + i * (loc2.lng-loc1.lng)/steps
|
|
|
|
self.mav.mav.terrain_check_send(int(lat*1.0e7), int(lon*1.0e7))
|
|
|
|
|
|
|
|
report = self.assert_receive_message('TERRAIN_REPORT', timeout=60)
|
|
|
|
self.progress("Terrain pending=%u" % report.pending)
|
|
|
|
if report.pending == 0:
|
|
|
|
break
|
|
|
|
self.progress("Got required terrain")
|
|
|
|
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.homeloc = self.mav.location()
|
|
|
|
|
|
|
|
guided_loc = mavutil.location(-35.39723762, 149.07284612, 99.0, 0)
|
|
|
|
rally_loc = mavutil.location(-35.3654952000, 149.1558698000, 100, 0)
|
|
|
|
|
|
|
|
terrain_wait_path(self.homeloc, rally_loc, 10)
|
|
|
|
|
|
|
|
# set a rally point to the west of home
|
|
|
|
self.upload_rally_points_from_locations([rally_loc])
|
|
|
|
|
|
|
|
self.set_parameter("TKOFF_ALT", 100)
|
|
|
|
self.change_mode("TAKEOFF")
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
|
|
|
self.set_parameter("TERRAIN_FOLLOW", 1)
|
|
|
|
self.wait_altitude(90, 120, timeout=30, relative=True)
|
|
|
|
self.progress("Done takeoff")
|
|
|
|
|
|
|
|
self.install_message_hook_context(terrain_following_above_80m)
|
|
|
|
|
|
|
|
self.change_mode("GUIDED")
|
|
|
|
self.do_reposition(guided_loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT)
|
|
|
|
self.progress("Flying to guided location")
|
|
|
|
self.wait_location(guided_loc,
|
|
|
|
accuracy=200,
|
|
|
|
target_altitude=None,
|
|
|
|
timeout=600)
|
|
|
|
|
|
|
|
self.progress("Reached guided location")
|
|
|
|
self.set_parameter("RALLY_LIMIT_KM", 50)
|
|
|
|
self.change_mode("RTL")
|
|
|
|
self.progress("Flying to rally point")
|
|
|
|
self.wait_location(rally_loc,
|
|
|
|
accuracy=200,
|
|
|
|
target_altitude=None,
|
|
|
|
timeout=600)
|
|
|
|
self.progress("Reached rally point")
|
|
|
|
|
|
|
|
self.context_pop()
|
|
|
|
self.disarm_vehicle(force=True)
|
|
|
|
self.reboot_sitl()
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def Parachute(self):
|
|
|
|
'''Test Parachute'''
|
2019-01-31 19:11:25 -04:00
|
|
|
self.set_rc(9, 1000)
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"CHUTE_ENABLED": 1,
|
|
|
|
"CHUTE_TYPE": 10,
|
|
|
|
"SERVO9_FUNCTION": 27,
|
|
|
|
"SIM_PARA_ENABLE": 1,
|
|
|
|
"SIM_PARA_PIN": 9,
|
|
|
|
})
|
2019-01-31 19:11:25 -04:00
|
|
|
|
|
|
|
self.load_mission("plane-parachute-mission.txt")
|
2021-02-18 06:32:49 -04:00
|
|
|
self.set_current_waypoint(1)
|
2019-01-31 19:11:25 -04:00
|
|
|
self.change_mode('AUTO')
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
2021-02-16 21:53:13 -04:00
|
|
|
self.wait_statustext("BANG", timeout=60)
|
2019-02-26 00:29:12 -04:00
|
|
|
self.disarm_vehicle(force=True)
|
2019-01-31 19:11:25 -04:00
|
|
|
self.reboot_sitl()
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def ParachuteSinkRate(self):
|
|
|
|
'''Test Parachute (SinkRate triggering)'''
|
2019-04-25 21:57:19 -03:00
|
|
|
self.set_rc(9, 1000)
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"CHUTE_ENABLED": 1,
|
|
|
|
"CHUTE_TYPE": 10,
|
|
|
|
"SERVO9_FUNCTION": 27,
|
|
|
|
"SIM_PARA_ENABLE": 1,
|
|
|
|
"SIM_PARA_PIN": 9,
|
|
|
|
"CHUTE_CRT_SINK": 9,
|
|
|
|
})
|
2019-04-25 21:57:19 -03:00
|
|
|
|
|
|
|
self.progress("Takeoff")
|
|
|
|
self.takeoff(alt=300)
|
|
|
|
|
|
|
|
self.progress("Diving")
|
|
|
|
self.set_rc(2, 2000)
|
2021-02-16 21:53:13 -04:00
|
|
|
self.wait_statustext("BANG", timeout=60)
|
2019-04-25 21:57:19 -03:00
|
|
|
|
|
|
|
self.disarm_vehicle(force=True)
|
|
|
|
self.reboot_sitl()
|
|
|
|
|
2018-12-16 18:54:05 -04:00
|
|
|
def run_subtest(self, desc, func):
|
|
|
|
self.start_subtest(desc)
|
|
|
|
func()
|
|
|
|
|
2021-03-14 22:38:08 -03:00
|
|
|
def check_attitudes_match(self, a, b):
|
|
|
|
'''make sure ahrs2 and simstate and ATTTIUDE_QUATERNION all match'''
|
2021-03-02 00:43:37 -04:00
|
|
|
|
2021-03-14 22:38:08 -03:00
|
|
|
# these are ordered to bookend the list with timestamps (which
|
|
|
|
# both attitude messages have):
|
2021-08-06 21:11:56 -03:00
|
|
|
get_names = ['ATTITUDE', 'SIMSTATE', 'AHRS2', 'ATTITUDE_QUATERNION']
|
2021-03-14 22:38:08 -03:00
|
|
|
msgs = self.get_messages_frame(get_names)
|
2021-03-02 00:43:37 -04:00
|
|
|
|
2021-03-14 22:38:08 -03:00
|
|
|
for get_name in get_names:
|
|
|
|
self.progress("%s: %s" % (get_name, msgs[get_name]))
|
|
|
|
|
2021-08-06 21:11:56 -03:00
|
|
|
simstate = msgs['SIMSTATE']
|
2021-03-14 22:38:08 -03:00
|
|
|
attitude = msgs['ATTITUDE']
|
|
|
|
ahrs2 = msgs['AHRS2']
|
|
|
|
attitude_quaternion = msgs['ATTITUDE_QUATERNION']
|
|
|
|
|
|
|
|
# check ATTITUDE
|
|
|
|
want = math.degrees(simstate.roll)
|
|
|
|
got = math.degrees(attitude.roll)
|
|
|
|
if abs(mavextra.angle_diff(want, got)) > 20:
|
|
|
|
raise NotAchievedException("ATTITUDE.Roll looks bad (want=%f got=%f)" %
|
|
|
|
(want, got))
|
|
|
|
want = math.degrees(simstate.pitch)
|
|
|
|
got = math.degrees(attitude.pitch)
|
|
|
|
if abs(mavextra.angle_diff(want, got)) > 20:
|
|
|
|
raise NotAchievedException("ATTITUDE.Pitch looks bad (want=%f got=%f)" %
|
|
|
|
(want, got))
|
2021-03-02 00:43:37 -04:00
|
|
|
|
2021-03-14 22:38:08 -03:00
|
|
|
# check AHRS2
|
2021-03-03 01:51:10 -04:00
|
|
|
want = math.degrees(simstate.roll)
|
|
|
|
got = math.degrees(ahrs2.roll)
|
2021-03-14 22:38:08 -03:00
|
|
|
if abs(mavextra.angle_diff(want, got)) > 20:
|
|
|
|
raise NotAchievedException("AHRS2.Roll looks bad (want=%f got=%f)" %
|
2021-03-03 01:51:10 -04:00
|
|
|
(want, got))
|
2021-03-14 22:38:08 -03:00
|
|
|
|
2021-03-03 01:51:10 -04:00
|
|
|
want = math.degrees(simstate.pitch)
|
|
|
|
got = math.degrees(ahrs2.pitch)
|
2021-03-14 22:38:08 -03:00
|
|
|
if abs(mavextra.angle_diff(want, got)) > 20:
|
|
|
|
raise NotAchievedException("AHRS2.Pitch looks bad (want=%f got=%f)" %
|
2021-03-03 01:51:10 -04:00
|
|
|
(want, got))
|
2021-03-02 00:43:37 -04:00
|
|
|
|
2021-03-14 22:38:08 -03:00
|
|
|
# check ATTITUDE_QUATERNION
|
2021-03-03 02:42:45 -04:00
|
|
|
q = quaternion.Quaternion([
|
|
|
|
attitude_quaternion.q1,
|
|
|
|
attitude_quaternion.q2,
|
|
|
|
attitude_quaternion.q3,
|
|
|
|
attitude_quaternion.q4
|
|
|
|
])
|
|
|
|
euler = q.euler
|
|
|
|
self.progress("attquat:%s q:%s euler:%s" % (
|
|
|
|
str(attitude_quaternion), q, euler))
|
|
|
|
|
|
|
|
want = math.degrees(simstate.roll)
|
|
|
|
got = math.degrees(euler[0])
|
2021-03-14 22:38:08 -03:00
|
|
|
if mavextra.angle_diff(want, got) > 20:
|
2021-03-03 02:42:45 -04:00
|
|
|
raise NotAchievedException("quat roll differs from attitude roll; want=%f got=%f" %
|
|
|
|
(want, got))
|
|
|
|
|
|
|
|
want = math.degrees(simstate.pitch)
|
|
|
|
got = math.degrees(euler[1])
|
2021-03-14 22:38:08 -03:00
|
|
|
if mavextra.angle_diff(want, got) > 20:
|
2021-03-03 02:42:45 -04:00
|
|
|
raise NotAchievedException("quat pitch differs from attitude pitch; want=%f got=%f" %
|
|
|
|
(want, got))
|
|
|
|
|
2021-03-14 22:38:08 -03:00
|
|
|
def fly_ahrs2_test(self):
|
|
|
|
'''check secondary estimator is looking OK'''
|
|
|
|
|
|
|
|
ahrs2 = self.mav.recv_match(type='AHRS2', blocking=True, timeout=1)
|
|
|
|
if ahrs2 is None:
|
|
|
|
raise NotAchievedException("Did not receive AHRS2 message")
|
|
|
|
self.progress("AHRS2: %s" % str(ahrs2))
|
|
|
|
|
|
|
|
# check location
|
|
|
|
gpi = self.mav.recv_match(
|
|
|
|
type='GLOBAL_POSITION_INT',
|
|
|
|
blocking=True,
|
|
|
|
timeout=5
|
|
|
|
)
|
|
|
|
if gpi is None:
|
|
|
|
raise NotAchievedException("Did not receive GLOBAL_POSITION_INT message")
|
|
|
|
self.progress("GPI: %s" % str(gpi))
|
|
|
|
if self.get_distance_int(gpi, ahrs2) > 10:
|
|
|
|
raise NotAchievedException("Secondary location looks bad")
|
|
|
|
|
|
|
|
self.check_attitudes_match(1, 2)
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def MainFlight(self):
|
|
|
|
'''Lots of things in one flight'''
|
2018-12-16 18:54:05 -04:00
|
|
|
self.change_mode('MANUAL')
|
|
|
|
|
2020-12-18 05:14:42 -04:00
|
|
|
self.progress("Asserting we do support transfer of fence via mission item protocol")
|
|
|
|
self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_MISSION_FENCE)
|
2020-06-01 23:59:24 -03:00
|
|
|
|
2018-12-16 18:54:05 -04:00
|
|
|
# grab home position:
|
2019-09-21 03:04:51 -03:00
|
|
|
self.mav.recv_match(type='HOME_POSITION', blocking=True)
|
2018-12-16 18:54:05 -04:00
|
|
|
self.homeloc = self.mav.location()
|
2018-04-27 15:21:53 -03:00
|
|
|
|
2018-12-16 18:54:05 -04:00
|
|
|
self.run_subtest("Takeoff", self.takeoff)
|
2018-08-13 08:07:34 -03:00
|
|
|
|
2018-12-16 18:54:05 -04:00
|
|
|
self.run_subtest("Set Attitude Target", self.set_attitude_target)
|
2018-09-07 08:15:02 -03:00
|
|
|
|
2018-12-16 18:54:05 -04:00
|
|
|
self.run_subtest("Fly left circuit", self.fly_left_circuit)
|
2018-04-27 15:21:53 -03:00
|
|
|
|
2018-12-16 18:54:05 -04:00
|
|
|
self.run_subtest("Left roll", lambda: self.axial_left_roll(1))
|
2018-05-31 07:27:41 -03:00
|
|
|
|
2018-12-16 18:54:05 -04:00
|
|
|
self.run_subtest("Inside loop", self.inside_loop)
|
2018-04-27 15:21:53 -03:00
|
|
|
|
2018-12-16 18:54:05 -04:00
|
|
|
self.run_subtest("Stablize test", self.test_stabilize)
|
2018-04-27 15:21:53 -03:00
|
|
|
|
2018-12-16 18:54:05 -04:00
|
|
|
self.run_subtest("ACRO test", self.test_acro)
|
2018-04-27 15:21:53 -03:00
|
|
|
|
2018-12-16 18:54:05 -04:00
|
|
|
self.run_subtest("FBWB test", self.test_FBWB)
|
2018-04-27 15:21:53 -03:00
|
|
|
|
2018-12-16 18:54:05 -04:00
|
|
|
self.run_subtest("CRUISE test", lambda: self.test_FBWB(mode='CRUISE'))
|
2018-04-27 15:21:53 -03:00
|
|
|
|
2018-12-16 18:54:05 -04:00
|
|
|
self.run_subtest("RTL test", self.fly_RTL)
|
2018-04-27 15:21:53 -03:00
|
|
|
|
2018-12-16 18:54:05 -04:00
|
|
|
self.run_subtest("LOITER test", self.fly_LOITER)
|
2018-04-27 15:21:53 -03:00
|
|
|
|
2018-12-16 18:54:05 -04:00
|
|
|
self.run_subtest("CIRCLE test", self.fly_CIRCLE)
|
2018-04-27 15:21:53 -03:00
|
|
|
|
2021-03-02 00:43:37 -04:00
|
|
|
self.run_subtest("AHRS2 test", self.fly_ahrs2_test)
|
|
|
|
|
2018-12-16 18:54:05 -04:00
|
|
|
self.run_subtest("Mission test",
|
2021-02-24 21:02:57 -04:00
|
|
|
lambda: self.fly_mission("ap1.txt", strict=False))
|
2018-04-27 15:21:53 -03:00
|
|
|
|
2022-07-03 02:46:32 -03:00
|
|
|
def PitotBlockage(self):
|
|
|
|
'''Test detection and isolation of a blocked pitot tube'''
|
2022-09-14 04:16:04 -03:00
|
|
|
self.set_parameters({
|
2022-09-21 04:12:03 -03:00
|
|
|
"ARSPD_OPTIONS": 15,
|
2022-09-14 04:16:04 -03:00
|
|
|
"ARSPD_USE": 1,
|
2022-09-22 19:35:30 -03:00
|
|
|
"SIM_WIND_SPD": 7,
|
2022-09-14 04:16:04 -03:00
|
|
|
"SIM_WIND_DIR": 0,
|
2022-09-21 04:12:03 -03:00
|
|
|
"ARSPD_WIND_MAX": 15,
|
2022-09-14 05:06:33 -03:00
|
|
|
})
|
2022-07-03 02:46:32 -03:00
|
|
|
self.change_mode("TAKEOFF")
|
2022-09-14 04:17:51 -03:00
|
|
|
self.wait_ready_to_arm()
|
2022-07-03 02:46:32 -03:00
|
|
|
self.arm_vehicle()
|
|
|
|
# simulate the effect of a blocked pitot tube
|
2022-07-18 21:17:20 -03:00
|
|
|
self.set_parameter("ARSPD_RATIO", 0.1)
|
2022-07-03 02:46:32 -03:00
|
|
|
self.delay_sim_time(10)
|
|
|
|
if (self.get_parameter("ARSPD_USE") == 0):
|
|
|
|
self.progress("Faulty Sensor Disabled")
|
|
|
|
else:
|
|
|
|
raise NotAchievedException("Airspeed Sensor Not Disabled")
|
|
|
|
self.delay_sim_time(20)
|
2022-07-04 05:53:52 -03:00
|
|
|
# simulate the effect of blockage partially clearing
|
2022-07-18 21:17:20 -03:00
|
|
|
self.set_parameter("ARSPD_RATIO", 1.0)
|
2022-07-04 05:53:52 -03:00
|
|
|
self.delay_sim_time(60)
|
|
|
|
if (self.get_parameter("ARSPD_USE") == 0):
|
|
|
|
self.progress("Faulty Sensor Remains Disabled")
|
|
|
|
else:
|
|
|
|
raise NotAchievedException("Fault Sensor Re-Enabled")
|
|
|
|
# simulate the effect of blockage fully clearing
|
2022-07-18 21:17:20 -03:00
|
|
|
self.set_parameter("ARSPD_RATIO", 2.0)
|
2022-07-03 02:46:32 -03:00
|
|
|
self.delay_sim_time(60)
|
|
|
|
if (self.get_parameter("ARSPD_USE") == 1):
|
|
|
|
self.progress("Sensor Re-Enabled")
|
|
|
|
else:
|
|
|
|
raise NotAchievedException("Airspeed Sensor Not Re-Enabled")
|
|
|
|
self.disarm_vehicle(force=True)
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def AIRSPEED_AUTOCAL(self):
|
|
|
|
'''Test AIRSPEED_AUTOCAL'''
|
2019-03-01 22:24:00 -04:00
|
|
|
self.progress("Ensure no AIRSPEED_AUTOCAL on ground")
|
2022-03-13 00:16:27 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"ARSPD_AUTOCAL": 1,
|
2022-05-13 00:44:35 -03:00
|
|
|
"ARSPD_PIN": 2,
|
|
|
|
"ARSPD_RATIO": 0,
|
|
|
|
"ARSPD2_RATIO": 4,
|
|
|
|
"ARSPD2_TYPE": 3, # MS5525
|
|
|
|
"ARSPD2_BUS": 1,
|
|
|
|
"ARSPD2_AUTOCAL": 1,
|
|
|
|
"SIM_ARSPD2_OFS": 1900, # default is 2013
|
|
|
|
|
2022-03-13 00:16:27 -04:00
|
|
|
"RTL_AUTOLAND": 1,
|
|
|
|
})
|
2022-05-13 00:44:35 -03:00
|
|
|
self.context_collect('STATUSTEXT')
|
|
|
|
self.reboot_sitl()
|
|
|
|
|
|
|
|
self.assert_not_receive_message('AIRSPEED_AUTOCAL', timeout=5)
|
|
|
|
|
|
|
|
# these are boot-time calibration messages:
|
|
|
|
self.wait_statustext('Airspeed 1 calibrated', check_context=True, timeout=30)
|
|
|
|
self.wait_statustext('Airspeed 2 calibrated', check_context=True)
|
|
|
|
|
2020-03-10 09:18:59 -03:00
|
|
|
mission_filepath = "flaps.txt"
|
2022-05-13 00:44:35 -03:00
|
|
|
self.load_mission(mission_filepath)
|
2019-03-01 22:24:00 -04:00
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
|
|
|
self.change_mode("AUTO")
|
|
|
|
self.progress("Ensure AIRSPEED_AUTOCAL in air")
|
2022-05-13 00:44:35 -03:00
|
|
|
self.assert_receive_message('AIRSPEED_AUTOCAL')
|
|
|
|
self.wait_statustext("Airspeed 0 ratio reset", check_context=True, timeout=70)
|
|
|
|
self.wait_statustext("Airspeed 1 ratio reset", check_context=True, timeout=70)
|
|
|
|
self.fly_home_land_and_disarm()
|
2019-03-01 22:24:00 -04:00
|
|
|
|
2020-08-15 05:07:02 -03:00
|
|
|
def deadreckoning_main(self, disable_airspeed_sensor=False):
|
2023-06-28 21:17:40 -03:00
|
|
|
self.reboot_sitl()
|
2021-01-17 21:06:14 -04:00
|
|
|
self.wait_ready_to_arm()
|
2020-08-15 05:07:02 -03:00
|
|
|
self.gpi = None
|
|
|
|
self.simstate = None
|
|
|
|
self.last_print = 0
|
|
|
|
self.max_divergence = 0
|
2021-02-11 22:44:28 -04:00
|
|
|
|
2020-08-15 05:07:02 -03:00
|
|
|
def validate_global_position_int_against_simstate(mav, m):
|
|
|
|
if m.get_type() == 'GLOBAL_POSITION_INT':
|
|
|
|
self.gpi = m
|
2021-08-06 21:11:56 -03:00
|
|
|
elif m.get_type() == 'SIMSTATE':
|
2020-08-15 05:07:02 -03:00
|
|
|
self.simstate = m
|
|
|
|
if self.gpi is None:
|
|
|
|
return
|
|
|
|
if self.simstate is None:
|
|
|
|
return
|
|
|
|
divergence = self.get_distance_int(self.gpi, self.simstate)
|
|
|
|
max_allowed_divergence = 200
|
2021-03-01 21:58:00 -04:00
|
|
|
if (time.time() - self.last_print > 1 or
|
|
|
|
divergence > self.max_divergence):
|
2020-08-15 05:07:02 -03:00
|
|
|
self.progress("position-estimate-divergence=%fm" % (divergence,))
|
|
|
|
self.last_print = time.time()
|
|
|
|
if divergence > self.max_divergence:
|
|
|
|
self.max_divergence = divergence
|
2021-03-01 21:58:00 -04:00
|
|
|
if divergence > max_allowed_divergence:
|
|
|
|
raise NotAchievedException(
|
|
|
|
"global-position-int diverged from simstate by %fm (max=%fm" %
|
|
|
|
(divergence, max_allowed_divergence,))
|
2020-08-15 05:07:02 -03:00
|
|
|
|
|
|
|
self.install_message_hook(validate_global_position_int_against_simstate)
|
|
|
|
|
|
|
|
try:
|
|
|
|
# wind is from the West:
|
|
|
|
self.set_parameter("SIM_WIND_DIR", 270)
|
|
|
|
# light winds:
|
|
|
|
self.set_parameter("SIM_WIND_SPD", 10)
|
|
|
|
if disable_airspeed_sensor:
|
|
|
|
self.set_parameter("ARSPD_USE", 0)
|
|
|
|
|
|
|
|
self.takeoff(50)
|
|
|
|
loc = self.mav.location()
|
2021-03-01 21:58:00 -04:00
|
|
|
self.location_offset_ne(loc, 500, 500)
|
2020-08-15 05:07:02 -03:00
|
|
|
self.run_cmd_int(
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
|
2023-07-15 09:40:01 -03:00
|
|
|
p1=0,
|
|
|
|
p2=mavutil.mavlink.MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
|
|
|
|
p5=int(loc.lat * 1e7),
|
|
|
|
p6=int(loc.lng * 1e7),
|
|
|
|
p7=100, # alt
|
2020-08-15 05:07:02 -03:00
|
|
|
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
|
|
|
|
)
|
|
|
|
self.wait_location(loc, accuracy=100)
|
|
|
|
self.progress("Stewing")
|
|
|
|
self.delay_sim_time(20)
|
|
|
|
self.set_parameter("SIM_GPS_DISABLE", 1)
|
|
|
|
self.progress("Roasting")
|
|
|
|
self.delay_sim_time(20)
|
|
|
|
self.change_mode("RTL")
|
|
|
|
self.wait_distance_to_home(100, 200, timeout=200)
|
|
|
|
self.set_parameter("SIM_GPS_DISABLE", 0)
|
|
|
|
self.delay_sim_time(10)
|
|
|
|
self.set_rc(3, 1000)
|
|
|
|
self.fly_home_land_and_disarm()
|
|
|
|
self.progress("max-divergence: %fm" % (self.max_divergence,))
|
|
|
|
finally:
|
|
|
|
self.remove_message_hook(validate_global_position_int_against_simstate)
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def Deadreckoning(self):
|
|
|
|
'''Test deadreckoning support'''
|
2020-08-15 05:07:02 -03:00
|
|
|
self.deadreckoning_main()
|
2021-03-01 21:58:00 -04:00
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def DeadreckoningNoAirSpeed(self):
|
|
|
|
'''Test deadreckoning support with no airspeed sensor'''
|
2020-08-15 05:07:02 -03:00
|
|
|
self.deadreckoning_main(disable_airspeed_sensor=True)
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def ClimbBeforeTurn(self):
|
|
|
|
'''Test climb-before-turn'''
|
2021-03-12 13:21:49 -04:00
|
|
|
self.wait_ready_to_arm()
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"FLIGHT_OPTIONS": 0,
|
|
|
|
"ALT_HOLD_RTL": 8000,
|
2022-03-13 00:16:27 -04:00
|
|
|
"RTL_AUTOLAND": 1,
|
2021-11-23 21:22:21 -04:00
|
|
|
})
|
2021-03-16 10:07:46 -03:00
|
|
|
takeoff_alt = 10
|
2021-03-12 13:21:49 -04:00
|
|
|
self.takeoff(alt=takeoff_alt)
|
|
|
|
self.change_mode("CRUISE")
|
|
|
|
self.wait_distance_to_home(500, 1000, timeout=60)
|
|
|
|
self.change_mode("RTL")
|
|
|
|
expected_alt = self.get_parameter("ALT_HOLD_RTL") / 100.0
|
|
|
|
|
|
|
|
home = self.home_position_as_mav_location()
|
|
|
|
distance = self.get_distance(home, self.mav.location())
|
|
|
|
|
2022-06-29 01:44:53 -03:00
|
|
|
self.wait_altitude(expected_alt - 10, expected_alt + 10, relative=True, timeout=80)
|
2021-03-12 13:21:49 -04:00
|
|
|
|
|
|
|
new_distance = self.get_distance(home, self.mav.location())
|
|
|
|
# We should be closer to home.
|
|
|
|
if new_distance > distance:
|
|
|
|
raise NotAchievedException(
|
|
|
|
"Expected to be closer to home (was %fm, now %fm)."
|
|
|
|
% (distance, new_distance)
|
|
|
|
)
|
|
|
|
|
|
|
|
self.fly_home_land_and_disarm()
|
2022-05-14 20:28:56 -03:00
|
|
|
self.set_current_waypoint(0, check_afterwards=False)
|
|
|
|
|
2021-03-12 13:21:49 -04:00
|
|
|
self.change_mode("MANUAL")
|
|
|
|
self.set_rc(3, 1000)
|
|
|
|
|
|
|
|
self.wait_ready_to_arm()
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"FLIGHT_OPTIONS": 16,
|
|
|
|
"ALT_HOLD_RTL": 10000,
|
|
|
|
})
|
2021-03-12 13:21:49 -04:00
|
|
|
self.takeoff(alt=takeoff_alt)
|
|
|
|
self.change_mode("CRUISE")
|
|
|
|
self.wait_distance_to_home(500, 1000, timeout=60)
|
|
|
|
self.change_mode("RTL")
|
|
|
|
|
|
|
|
home = self.home_position_as_mav_location()
|
|
|
|
distance = self.get_distance(home, self.mav.location())
|
|
|
|
|
2022-06-29 02:12:39 -03:00
|
|
|
self.wait_altitude(expected_alt - 10, expected_alt + 10, relative=True, timeout=80)
|
2021-03-12 13:21:49 -04:00
|
|
|
|
|
|
|
new_distance = self.get_distance(home, self.mav.location())
|
|
|
|
# We should be farther from to home.
|
|
|
|
if new_distance < distance:
|
|
|
|
raise NotAchievedException(
|
|
|
|
"Expected to be farther from home (was %fm, now %fm)."
|
|
|
|
% (distance, new_distance)
|
|
|
|
)
|
|
|
|
|
2021-03-31 21:30:11 -03:00
|
|
|
self.fly_home_land_and_disarm(timeout=240)
|
2021-03-12 13:21:49 -04:00
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def RTL_CLIMB_MIN(self):
|
|
|
|
'''Test RTL_CLIMB_MIN'''
|
2021-02-08 22:24:09 -04:00
|
|
|
self.wait_ready_to_arm()
|
|
|
|
rtl_climb_min = 100
|
|
|
|
self.set_parameter("RTL_CLIMB_MIN", rtl_climb_min)
|
|
|
|
takeoff_alt = 50
|
|
|
|
self.takeoff(alt=takeoff_alt)
|
|
|
|
self.change_mode('CRUISE')
|
|
|
|
self.wait_distance_to_home(1000, 1500, timeout=60)
|
|
|
|
post_cruise_alt = self.get_altitude(relative=True)
|
|
|
|
self.change_mode('RTL')
|
|
|
|
expected_alt = self.get_parameter("ALT_HOLD_RTL")/100.0
|
|
|
|
if expected_alt == -1:
|
|
|
|
expected_alt = self.get_altitude(relative=True)
|
|
|
|
|
|
|
|
# ensure we're about half-way-down at the half-way-home stage:
|
|
|
|
self.wait_distance_to_nav_target(
|
|
|
|
0,
|
|
|
|
500,
|
2022-06-29 00:48:26 -03:00
|
|
|
timeout=240,
|
2021-02-08 22:24:09 -04:00
|
|
|
)
|
|
|
|
alt = self.get_altitude(relative=True)
|
|
|
|
expected_halfway_alt = expected_alt + (post_cruise_alt + rtl_climb_min - expected_alt)/2.0
|
|
|
|
if abs(alt - expected_halfway_alt) > 30:
|
|
|
|
raise NotAchievedException("Not half-way-down and half-way-home (want=%f got=%f" %
|
|
|
|
(expected_halfway_alt, alt))
|
|
|
|
self.progress("Half-way-down at half-way-home (want=%f vs got=%f)" %
|
|
|
|
(expected_halfway_alt, alt))
|
|
|
|
|
|
|
|
rtl_radius = self.get_parameter("RTL_RADIUS")
|
|
|
|
if rtl_radius == 0:
|
|
|
|
rtl_radius = self.get_parameter("WP_LOITER_RAD")
|
|
|
|
self.wait_distance_to_nav_target(
|
|
|
|
0,
|
|
|
|
rtl_radius,
|
|
|
|
timeout=120,
|
|
|
|
)
|
|
|
|
alt = self.get_altitude(relative=True)
|
|
|
|
if abs(alt - expected_alt) > 10:
|
|
|
|
raise NotAchievedException(
|
|
|
|
"Expected to have %fm altitude at end of RTL (got %f)" %
|
|
|
|
(expected_alt, alt))
|
|
|
|
self.fly_home_land_and_disarm()
|
|
|
|
|
2020-01-14 21:14:43 -04:00
|
|
|
def sample_enable_parameter(self):
|
|
|
|
return "Q_ENABLE"
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def RangeFinder(self):
|
|
|
|
'''Test RangeFinder Basic Functionality'''
|
2019-04-08 23:26:18 -03:00
|
|
|
self.context_push()
|
|
|
|
self.progress("Making sure we don't ordinarily get RANGEFINDER")
|
2023-01-03 20:03:03 -04:00
|
|
|
self.assert_not_receive_message('RANGEFDINDER')
|
2019-04-08 23:26:18 -03:00
|
|
|
|
2023-01-03 20:03:03 -04:00
|
|
|
self.set_analog_rangefinder_parameters()
|
2019-04-08 23:26:18 -03:00
|
|
|
|
2023-01-03 20:03:03 -04:00
|
|
|
self.reboot_sitl()
|
2019-04-08 23:26:18 -03:00
|
|
|
|
2023-01-03 20:03:03 -04:00
|
|
|
'''ensure rangefinder gives height-above-ground'''
|
|
|
|
self.load_mission("plane-gripper-mission.txt") # borrow this
|
|
|
|
self.set_parameter("RTL_AUTOLAND", 1)
|
|
|
|
self.set_current_waypoint(1)
|
|
|
|
self.change_mode('AUTO')
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
|
|
|
self.wait_waypoint(5, 5, max_dist=100)
|
|
|
|
rf = self.mav.recv_match(type="RANGEFINDER", timeout=1, blocking=True)
|
|
|
|
if rf is None:
|
|
|
|
raise NotAchievedException("Did not receive rangefinder message")
|
|
|
|
gpi = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True, timeout=1)
|
|
|
|
if gpi is None:
|
|
|
|
raise NotAchievedException("Did not receive GLOBAL_POSITION_INT message")
|
|
|
|
if abs(rf.distance - gpi.relative_alt/1000.0) > 3:
|
|
|
|
raise NotAchievedException(
|
|
|
|
"rangefinder alt (%s) disagrees with global-position-int.relative_alt (%s)" %
|
|
|
|
(rf.distance, gpi.relative_alt/1000.0))
|
|
|
|
self.wait_statustext("Auto disarmed", timeout=60)
|
2019-04-08 23:26:18 -03:00
|
|
|
|
2023-01-03 20:03:03 -04:00
|
|
|
self.progress("Ensure RFND messages in log")
|
|
|
|
if not self.current_onboard_log_contains_message("RFND"):
|
|
|
|
raise NotAchievedException("No RFND messages in log")
|
2019-04-08 23:26:18 -03:00
|
|
|
|
|
|
|
self.context_pop()
|
|
|
|
self.reboot_sitl()
|
|
|
|
|
2019-02-03 06:43:07 -04:00
|
|
|
def rc_defaults(self):
|
|
|
|
ret = super(AutoTestPlane, self).rc_defaults()
|
|
|
|
ret[3] = 1000
|
|
|
|
ret[8] = 1800
|
|
|
|
return ret
|
2018-04-27 15:21:53 -03:00
|
|
|
|
2020-12-09 15:51:01 -04:00
|
|
|
def initial_mode_switch_mode(self):
|
|
|
|
return "MANUAL"
|
|
|
|
|
2018-12-16 18:54:05 -04:00
|
|
|
def default_mode(self):
|
|
|
|
return "MANUAL"
|
2018-04-27 15:21:53 -03:00
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def PIDTuning(self):
|
|
|
|
'''Test PID Tuning'''
|
2019-02-28 19:04:23 -04:00
|
|
|
self.change_mode("FBWA") # we don't update PIDs in MANUAL
|
2022-09-09 22:24:28 -03:00
|
|
|
super(AutoTestPlane, self).PIDTuning()
|
2019-02-28 19:04:23 -04:00
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def AuxModeSwitch(self):
|
|
|
|
'''Set modes via auxswitches'''
|
2020-12-28 21:30:53 -04:00
|
|
|
self.set_parameter("FLTMODE1", 1) # circle
|
|
|
|
self.set_rc(8, 950)
|
2019-04-05 02:15:33 -03:00
|
|
|
self.wait_mode("CIRCLE")
|
|
|
|
self.set_rc(9, 1000)
|
|
|
|
self.set_rc(10, 1000)
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"RC9_OPTION": 4, # RTL
|
|
|
|
"RC10_OPTION": 55, # guided
|
|
|
|
})
|
2019-04-05 02:15:33 -03:00
|
|
|
self.set_rc(9, 1900)
|
|
|
|
self.wait_mode("RTL")
|
|
|
|
self.set_rc(10, 1900)
|
|
|
|
self.wait_mode("GUIDED")
|
|
|
|
|
|
|
|
self.progress("resetting both switches - should go back to CIRCLE")
|
|
|
|
self.set_rc(9, 1000)
|
|
|
|
self.set_rc(10, 1000)
|
|
|
|
self.wait_mode("CIRCLE")
|
|
|
|
|
|
|
|
self.set_rc(9, 1900)
|
|
|
|
self.wait_mode("RTL")
|
|
|
|
self.set_rc(10, 1900)
|
|
|
|
self.wait_mode("GUIDED")
|
|
|
|
|
|
|
|
self.progress("Resetting switch should repoll mode switch")
|
|
|
|
self.set_rc(10, 1000) # this re-polls the mode switch
|
|
|
|
self.wait_mode("CIRCLE")
|
|
|
|
self.set_rc(9, 1000)
|
|
|
|
|
2019-11-05 21:52:28 -04:00
|
|
|
def wait_for_collision_threat_to_clear(self):
|
|
|
|
'''wait to get a "clear" collision message", then slurp remaining
|
|
|
|
messages'''
|
|
|
|
last_collision = self.get_sim_time()
|
|
|
|
while True:
|
|
|
|
now = self.get_sim_time()
|
|
|
|
if now - last_collision > 5:
|
|
|
|
return
|
|
|
|
self.progress("Waiting for collision message")
|
|
|
|
m = self.mav.recv_match(type='COLLISION', blocking=True, timeout=1)
|
|
|
|
self.progress("Got (%s)" % str(m))
|
|
|
|
if m is None:
|
|
|
|
continue
|
|
|
|
last_collision = now
|
|
|
|
|
2021-11-09 02:22:30 -04:00
|
|
|
def SimADSB(self):
|
2022-09-09 22:24:28 -03:00
|
|
|
'''Tests to ensure simulated ADSB sensor continues to function'''
|
2021-11-09 02:22:30 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"SIM_ADSB_COUNT": 1,
|
|
|
|
"ADSB_TYPE": 1,
|
|
|
|
})
|
|
|
|
self.reboot_sitl()
|
|
|
|
self.assert_receive_message('ADSB_VEHICLE', timeout=30)
|
|
|
|
|
2022-03-18 22:57:13 -03:00
|
|
|
def ADSB(self):
|
2022-09-09 22:24:28 -03:00
|
|
|
'''Test ADSB'''
|
2022-03-18 22:57:13 -03:00
|
|
|
self.ADSB_f_action_rtl()
|
|
|
|
self.ADSB_r_action_resume_or_loiter()
|
|
|
|
|
|
|
|
def ADSB_r_action_resume_or_loiter(self):
|
|
|
|
'''ensure we resume auto mission or enter loiter'''
|
|
|
|
self.set_parameters({
|
|
|
|
"ADSB_TYPE": 1,
|
|
|
|
"AVD_ENABLE": 1,
|
|
|
|
"AVD_F_ACTION": mavutil.mavlink.MAV_COLLISION_ACTION_MOVE_HORIZONTALLY,
|
|
|
|
"AVD_F_RCVRY": 3, # resume auto or loiter
|
|
|
|
})
|
|
|
|
self.reboot_sitl()
|
|
|
|
self.takeoff(50)
|
|
|
|
# fly North, create thread to east, wait for flying east
|
|
|
|
self.start_subtest("Testing loiter resume")
|
|
|
|
self.reach_heading_manual(0)
|
|
|
|
here = self.mav.location()
|
|
|
|
self.test_adsb_send_threatening_adsb_message(here, offset_ne=(0, 30))
|
|
|
|
self.wait_mode('AVOID_ADSB')
|
|
|
|
# recovery has the vehicle circling a point... but we don't
|
|
|
|
# know which point. So wait 'til it looks like it is
|
|
|
|
# circling, then grab the point, then check we're circling
|
|
|
|
# it...
|
|
|
|
self.wait_heading(290)
|
|
|
|
self.wait_heading(300)
|
|
|
|
dest = self.position_target_loc()
|
|
|
|
REALLY_BAD_FUDGE_FACTOR = 1.25 # FIXME
|
|
|
|
expected_radius = REALLY_BAD_FUDGE_FACTOR * self.get_parameter('WP_LOITER_RAD')
|
|
|
|
self.wait_circling_point_with_radius(dest, expected_radius)
|
|
|
|
|
|
|
|
self.start_subtest("Testing mission resume")
|
|
|
|
self.reach_heading_manual(270)
|
|
|
|
self.load_generic_mission("CMAC-circuit.txt", strict=False)
|
|
|
|
self.change_mode('AUTO')
|
|
|
|
self.wait_current_waypoint(2)
|
|
|
|
self.test_adsb_send_threatening_adsb_message(here, offset_ne=(0, 30))
|
|
|
|
self.wait_mode('AVOID_ADSB')
|
|
|
|
self.wait_mode('AUTO')
|
|
|
|
|
|
|
|
self.fly_home_land_and_disarm()
|
|
|
|
|
|
|
|
def ADSB_f_action_rtl(self):
|
2019-11-05 21:52:28 -04:00
|
|
|
self.context_push()
|
|
|
|
ex = None
|
|
|
|
try:
|
|
|
|
# message ADSB_VEHICLE 37 -353632614 1491652305 0 584070 0 0 0 "bob" 3 1 255 17
|
|
|
|
self.set_parameter("RC12_OPTION", 38) # avoid-adsb
|
|
|
|
self.set_rc(12, 2000)
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"ADSB_TYPE": 1,
|
|
|
|
"AVD_ENABLE": 1,
|
|
|
|
"AVD_F_ACTION": mavutil.mavlink.MAV_COLLISION_ACTION_RTL,
|
|
|
|
})
|
2019-11-05 21:52:28 -04:00
|
|
|
self.reboot_sitl()
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
here = self.mav.location()
|
|
|
|
self.change_mode("FBWA")
|
|
|
|
self.delay_sim_time(2) # TODO: work out why this is required...
|
|
|
|
self.test_adsb_send_threatening_adsb_message(here)
|
|
|
|
self.progress("Waiting for collision message")
|
2022-02-09 20:59:34 -04:00
|
|
|
m = self.assert_receive_message('COLLISION', timeout=4)
|
2019-11-05 21:52:28 -04:00
|
|
|
if m.threat_level != 2:
|
|
|
|
raise NotAchievedException("Expected some threat at least")
|
|
|
|
if m.action != mavutil.mavlink.MAV_COLLISION_ACTION_RTL:
|
|
|
|
raise NotAchievedException("Incorrect action; want=%u got=%u" %
|
|
|
|
(mavutil.mavlink.MAV_COLLISION_ACTION_RTL, m.action))
|
|
|
|
self.wait_mode("RTL")
|
|
|
|
|
|
|
|
self.progress("Sending far-away ABSD_VEHICLE message")
|
2021-02-11 22:44:28 -04:00
|
|
|
self.mav.mav.adsb_vehicle_send(
|
|
|
|
37, # ICAO address
|
|
|
|
int(here.lat+1 * 1e7),
|
|
|
|
int(here.lng * 1e7),
|
|
|
|
mavutil.mavlink.ADSB_ALTITUDE_TYPE_PRESSURE_QNH,
|
|
|
|
int(here.alt*1000 + 10000), # 10m up
|
|
|
|
0, # heading in cdeg
|
|
|
|
0, # horizontal velocity cm/s
|
|
|
|
0, # vertical velocity cm/s
|
|
|
|
"bob".encode("ascii"), # callsign
|
|
|
|
mavutil.mavlink.ADSB_EMITTER_TYPE_LIGHT,
|
|
|
|
1, # time since last communication
|
|
|
|
65535, # flags
|
|
|
|
17 # squawk
|
2019-11-05 21:52:28 -04:00
|
|
|
)
|
|
|
|
self.wait_for_collision_threat_to_clear()
|
|
|
|
self.change_mode("FBWA")
|
|
|
|
|
|
|
|
self.progress("Disabling ADSB-avoidance with RC channel")
|
|
|
|
self.set_rc(12, 1000)
|
|
|
|
self.delay_sim_time(1) # let the switch get polled
|
|
|
|
self.test_adsb_send_threatening_adsb_message(here)
|
|
|
|
m = self.mav.recv_match(type='COLLISION', blocking=True, timeout=4)
|
2021-01-07 19:27:27 -04:00
|
|
|
self.progress("Got (%s)" % str(m))
|
2019-11-05 21:52:28 -04:00
|
|
|
if m is not None:
|
|
|
|
raise NotAchievedException("Got collision message when I shouldn't have")
|
|
|
|
|
|
|
|
except Exception as e:
|
2021-02-12 22:38:42 -04:00
|
|
|
self.print_exception_caught(e)
|
2019-11-05 21:52:28 -04:00
|
|
|
ex = e
|
|
|
|
self.context_pop()
|
|
|
|
self.reboot_sitl()
|
|
|
|
if ex is not None:
|
|
|
|
raise ex
|
2019-07-09 10:39:32 -03:00
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def GuidedRequest(self, target_system=1, target_component=1):
|
|
|
|
'''Test handling of MISSION_ITEM in guided mode'''
|
2019-11-10 20:20:03 -04:00
|
|
|
self.progress("Takeoff")
|
|
|
|
self.takeoff(alt=50)
|
|
|
|
self.set_rc(3, 1500)
|
|
|
|
self.start_subtest("Ensure command bounced outside guided mode")
|
|
|
|
desired_relative_alt = 33
|
|
|
|
loc = self.mav.location()
|
|
|
|
self.location_offset_ne(loc, 300, 300)
|
|
|
|
loc.alt += desired_relative_alt
|
|
|
|
self.mav.mav.mission_item_int_send(
|
|
|
|
target_system,
|
|
|
|
target_component,
|
|
|
|
0, # seq
|
|
|
|
mavutil.mavlink.MAV_FRAME_GLOBAL,
|
|
|
|
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
|
|
|
|
2, # current - guided-mode request
|
|
|
|
0, # autocontinue
|
|
|
|
0, # p1
|
|
|
|
0, # p2
|
|
|
|
0, # p3
|
|
|
|
0, # p4
|
2021-02-11 22:44:28 -04:00
|
|
|
int(loc.lat * 1e7), # latitude
|
|
|
|
int(loc.lng * 1e7), # longitude
|
2019-11-10 20:20:03 -04:00
|
|
|
loc.alt, # altitude
|
|
|
|
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
|
2022-02-09 20:59:34 -04:00
|
|
|
m = self.assert_receive_message('MISSION_ACK', timeout=5)
|
2019-11-10 20:20:03 -04:00
|
|
|
if m.type != mavutil.mavlink.MAV_MISSION_ERROR:
|
|
|
|
raise NotAchievedException("Did not get appropriate error")
|
|
|
|
|
|
|
|
self.start_subtest("Enter guided and flying somewhere constant")
|
|
|
|
self.change_mode("GUIDED")
|
|
|
|
self.mav.mav.mission_item_int_send(
|
|
|
|
target_system,
|
|
|
|
target_component,
|
|
|
|
0, # seq
|
|
|
|
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
|
|
|
|
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
|
|
|
|
2, # current - guided-mode request
|
|
|
|
0, # autocontinue
|
|
|
|
0, # p1
|
|
|
|
0, # p2
|
|
|
|
0, # p3
|
|
|
|
0, # p4
|
2021-02-11 22:44:28 -04:00
|
|
|
int(loc.lat * 1e7), # latitude
|
|
|
|
int(loc.lng * 1e7), # longitude
|
2019-11-10 20:20:03 -04:00
|
|
|
desired_relative_alt, # altitude
|
|
|
|
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
|
2022-02-09 20:59:34 -04:00
|
|
|
m = self.assert_receive_message('MISSION_ACK', timeout=5)
|
2019-11-10 20:20:03 -04:00
|
|
|
if m.type != mavutil.mavlink.MAV_MISSION_ACCEPTED:
|
|
|
|
raise NotAchievedException("Did not get accepted response")
|
|
|
|
self.wait_location(loc, accuracy=100) # based on loiter radius
|
2019-07-09 12:31:53 -03:00
|
|
|
self.wait_altitude(altitude_min=desired_relative_alt-3,
|
|
|
|
altitude_max=desired_relative_alt+3,
|
2022-01-29 07:58:42 -04:00
|
|
|
relative=True,
|
|
|
|
timeout=30)
|
|
|
|
|
|
|
|
self.start_subtest("changing alt with mission item in guided mode")
|
|
|
|
|
|
|
|
# test changing alt only - NOTE - this is still a
|
|
|
|
# NAV_WAYPOINT, not a changel-alt request!
|
|
|
|
desired_relative_alt = desired_relative_alt + 50
|
|
|
|
self.mav.mav.mission_item_int_send(
|
|
|
|
target_system,
|
|
|
|
target_component,
|
|
|
|
0, # seq
|
|
|
|
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
|
|
|
|
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
|
|
|
|
3, # current - change-alt request
|
|
|
|
0, # autocontinue
|
|
|
|
0, # p1
|
|
|
|
0, # p2
|
|
|
|
0, # p3
|
|
|
|
0, # p4
|
|
|
|
0, # latitude
|
|
|
|
0,
|
|
|
|
desired_relative_alt, # altitude
|
|
|
|
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
|
|
|
|
|
|
|
|
self.wait_altitude(altitude_min=desired_relative_alt-3,
|
|
|
|
altitude_max=desired_relative_alt+3,
|
|
|
|
relative=True,
|
|
|
|
timeout=30)
|
2019-11-10 20:20:03 -04:00
|
|
|
|
|
|
|
self.fly_home_land_and_disarm()
|
|
|
|
|
2020-02-06 18:12:45 -04:00
|
|
|
def LOITER(self):
|
2022-09-09 22:24:28 -03:00
|
|
|
'''Test Loiter mode'''
|
2022-05-10 09:53:10 -03:00
|
|
|
# first test old loiter behavour
|
|
|
|
self.set_parameter("FLIGHT_OPTIONS", 0)
|
2020-02-06 18:12:45 -04:00
|
|
|
self.takeoff(alt=200)
|
|
|
|
self.set_rc(3, 1500)
|
|
|
|
self.change_mode("LOITER")
|
|
|
|
self.progress("Doing a bit of loitering to start with")
|
|
|
|
tstart = self.get_sim_time()
|
|
|
|
while True:
|
|
|
|
now = self.get_sim_time_cached()
|
|
|
|
if now - tstart > 60:
|
|
|
|
break
|
|
|
|
m = self.mav.recv_match(type='VFR_HUD', blocking=True, timeout=5)
|
|
|
|
if m is None:
|
|
|
|
raise NotAchievedException("Did not get VFR_HUD")
|
|
|
|
new_throttle = m.throttle
|
|
|
|
alt = m.alt
|
2022-02-09 20:59:34 -04:00
|
|
|
m = self.assert_receive_message('ATTITUDE', timeout=5)
|
2020-02-06 18:12:45 -04:00
|
|
|
pitch = math.degrees(m.pitch)
|
|
|
|
self.progress("Pitch:%f throttle:%u alt:%f" % (pitch, new_throttle, alt))
|
2022-02-09 20:59:34 -04:00
|
|
|
m = self.assert_receive_message('VFR_HUD', timeout=5)
|
2020-02-06 18:12:45 -04:00
|
|
|
initial_throttle = m.throttle
|
|
|
|
initial_alt = m.alt
|
|
|
|
self.progress("Initial throttle: %u" % initial_throttle)
|
|
|
|
# pitch down, ensure throttle decreases:
|
|
|
|
rc2_max = self.get_parameter("RC2_MAX")
|
2020-12-28 21:30:53 -04:00
|
|
|
self.set_rc(2, int(rc2_max))
|
2020-02-06 18:12:45 -04:00
|
|
|
tstart = self.get_sim_time()
|
|
|
|
while True:
|
|
|
|
now = self.get_sim_time_cached()
|
|
|
|
'''stick-mixing is pushing the aircraft down. It doesn't want to go
|
|
|
|
down (the target loiter altitude hasn't changed), so it
|
|
|
|
tries to add energy by increasing the throttle.
|
|
|
|
'''
|
|
|
|
if now - tstart > 60:
|
|
|
|
raise NotAchievedException("Did not see increase in throttle")
|
2022-02-09 20:59:34 -04:00
|
|
|
m = self.assert_receive_message('VFR_HUD', timeout=5)
|
2020-02-06 18:12:45 -04:00
|
|
|
new_throttle = m.throttle
|
|
|
|
alt = m.alt
|
2022-02-09 20:59:34 -04:00
|
|
|
m = self.assert_receive_message('ATTITUDE', timeout=5)
|
2020-02-06 18:12:45 -04:00
|
|
|
pitch = math.degrees(m.pitch)
|
|
|
|
self.progress("Pitch:%f throttle:%u alt:%f" % (pitch, new_throttle, alt))
|
|
|
|
if new_throttle - initial_throttle > 20:
|
|
|
|
self.progress("Throttle delta achieved")
|
|
|
|
break
|
|
|
|
self.progress("Centering elevator and ensuring we get back to loiter altitude")
|
|
|
|
self.set_rc(2, 1500)
|
|
|
|
self.wait_altitude(initial_alt-1, initial_alt+1)
|
2022-05-10 09:53:10 -03:00
|
|
|
# Test new loiter behavour
|
|
|
|
self.set_parameter("FLIGHT_OPTIONS", 1 << 12)
|
|
|
|
# should decend at max stick
|
|
|
|
self.set_rc(2, int(rc2_max))
|
|
|
|
self.wait_altitude(initial_alt - 110, initial_alt - 90, timeout=90)
|
|
|
|
# should not climb back at mid stick
|
|
|
|
self.set_rc(2, 1500)
|
|
|
|
self.delay_sim_time(60)
|
|
|
|
self.wait_altitude(initial_alt - 110, initial_alt - 90)
|
|
|
|
# should climb at min stick
|
|
|
|
self.set_rc(2, 1100)
|
|
|
|
self.wait_altitude(initial_alt - 10, initial_alt + 10, timeout=90)
|
|
|
|
# return stick to center and fly home
|
|
|
|
self.set_rc(2, 1500)
|
2020-02-06 18:12:45 -04:00
|
|
|
self.fly_home_land_and_disarm()
|
|
|
|
|
2020-02-28 20:14:11 -04:00
|
|
|
def CPUFailsafe(self):
|
|
|
|
'''In lockup Plane should copy RC inputs to RC outputs'''
|
|
|
|
self.plane_CPUFailsafe()
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def LargeMissions(self):
|
|
|
|
'''Test Manipulation of Large missions'''
|
2021-02-24 21:02:57 -04:00
|
|
|
self.load_mission("Kingaroy-vlarge.txt", strict=False)
|
|
|
|
self.load_mission("Kingaroy-vlarge2.txt", strict=False)
|
2020-04-14 01:38:30 -03:00
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def Soaring(self):
|
|
|
|
'''Test Soaring feature'''
|
2020-04-11 07:18:20 -03:00
|
|
|
|
2021-02-11 22:44:28 -04:00
|
|
|
model = "plane-soaring"
|
2020-04-21 04:30:17 -03:00
|
|
|
|
2021-02-11 22:44:28 -04:00
|
|
|
self.customise_SITL_commandline(
|
|
|
|
[],
|
|
|
|
model=model,
|
2021-06-08 06:49:31 -03:00
|
|
|
defaults_filepath=self.model_defaults_filepath(model),
|
2021-02-11 22:44:28 -04:00
|
|
|
wipe=True)
|
2020-04-11 07:18:20 -03:00
|
|
|
|
2021-02-24 21:02:57 -04:00
|
|
|
self.load_mission('CMAC-soar.txt', strict=False)
|
2020-04-11 07:18:20 -03:00
|
|
|
|
|
|
|
# Enable thermalling RC
|
2020-07-13 10:10:19 -03:00
|
|
|
rc_chan = 0
|
|
|
|
for i in range(8):
|
|
|
|
rcx_option = self.get_parameter('RC{0}_OPTION'.format(i+1))
|
2021-02-11 22:44:28 -04:00
|
|
|
if rcx_option == 88:
|
|
|
|
rc_chan = i+1
|
2020-07-13 10:10:19 -03:00
|
|
|
break
|
|
|
|
|
2021-02-11 22:44:28 -04:00
|
|
|
if rc_chan == 0:
|
2020-07-13 10:10:19 -03:00
|
|
|
raise NotAchievedException("Did not find soaring enable channel option.")
|
|
|
|
|
2020-12-28 21:30:53 -04:00
|
|
|
self.set_rc_from_map({
|
|
|
|
rc_chan: 1900,
|
2021-02-11 22:44:28 -04:00
|
|
|
})
|
2020-09-07 08:52:58 -03:00
|
|
|
|
2023-09-08 05:05:28 -03:00
|
|
|
self.set_parameters({
|
|
|
|
"SOAR_VSPEED": 0.55,
|
|
|
|
"SOAR_MIN_THML_S": 25,
|
|
|
|
})
|
|
|
|
|
|
|
|
self.set_current_waypoint(1)
|
|
|
|
self.change_mode('AUTO')
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
|
|
|
|
2020-04-11 07:18:20 -03:00
|
|
|
# Wait to detect thermal
|
|
|
|
self.progress("Waiting for thermal")
|
2021-02-11 22:44:28 -04:00
|
|
|
self.wait_mode('THERMAL', timeout=600)
|
2020-04-11 07:18:20 -03:00
|
|
|
|
|
|
|
# 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)
|
|
|
|
|
2020-09-10 06:24:53 -03:00
|
|
|
# Wait to descend to SOAR_ALT_MIN
|
2020-04-11 07:18:20 -03:00
|
|
|
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")
|
2022-12-01 18:05:41 -04:00
|
|
|
self.wait_servo_channel_value(3, 1200, timeout=5, comparator=operator.gt)
|
2020-04-11 07:18:20 -03:00
|
|
|
|
|
|
|
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)
|
|
|
|
|
2020-09-10 06:24:53 -03:00
|
|
|
# Allow time to suppress throttle and start descent.
|
2020-09-07 08:52:58 -03:00
|
|
|
self.delay_sim_time(20)
|
|
|
|
|
2020-04-11 07:18:20 -03:00
|
|
|
# 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)
|
|
|
|
|
2021-02-11 22:44:28 -04:00
|
|
|
# And reenable. This should force throttle-down
|
2020-04-11 07:18:20 -03:00
|
|
|
self.set_parameter("SOAR_ENABLE", 1)
|
|
|
|
self.delay_sim_time(10)
|
|
|
|
|
2020-09-07 08:52:58 -03:00
|
|
|
# Now wait for descent and check throttle up
|
2020-04-11 07:18:20 -03:00
|
|
|
self.wait_altitude(alt_min-10, alt_min, timeout=600, relative=True)
|
|
|
|
|
2020-09-10 06:24:53 -03:00
|
|
|
self.progress("Waiting for climb")
|
2020-09-07 08:52:58 -03:00
|
|
|
self.wait_altitude(alt_ctf-10, alt_ctf, timeout=600, relative=True)
|
2020-04-11 07:18:20 -03:00
|
|
|
|
|
|
|
# Back to auto
|
|
|
|
self.change_mode('AUTO')
|
|
|
|
|
|
|
|
# Reenable thermals
|
|
|
|
self.set_parameter("SIM_THML_SCENARI", 1)
|
|
|
|
|
|
|
|
# Disable soaring using RC channel.
|
2020-12-28 21:30:53 -04:00
|
|
|
self.set_rc(rc_chan, 1100)
|
2020-04-11 07:18:20 -03:00
|
|
|
|
|
|
|
# Wait to get back to waypoint before thermal.
|
|
|
|
self.progress("Waiting to get back to position")
|
2021-02-11 22:44:28 -04:00
|
|
|
self.wait_current_waypoint(3, timeout=1200)
|
2020-04-11 07:18:20 -03:00
|
|
|
|
|
|
|
# Enable soaring with mode changes suppressed)
|
2020-12-28 21:30:53 -04:00
|
|
|
self.set_rc(rc_chan, 1500)
|
2020-04-11 07:18:20 -03:00
|
|
|
|
|
|
|
# Make sure this causes throttle down.
|
2022-06-29 12:16:27 -03:00
|
|
|
self.wait_servo_channel_value(3, 1200, timeout=3, comparator=operator.lt)
|
2020-04-11 07:18:20 -03:00
|
|
|
|
2020-09-24 06:18:38 -03:00
|
|
|
self.progress("Waiting for next WP with no thermalling")
|
2021-02-11 22:44:28 -04:00
|
|
|
self.wait_waypoint(4, 4, timeout=1200, max_dist=120)
|
2020-04-11 07:18:20 -03:00
|
|
|
|
|
|
|
# Disarm
|
2022-03-08 17:15:15 -04:00
|
|
|
self.disarm_vehicle_expect_fail()
|
2020-04-11 07:18:20 -03:00
|
|
|
|
|
|
|
self.progress("Mission OK")
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def SpeedToFly(self):
|
|
|
|
'''Test soaring speed-to-fly'''
|
2021-06-07 07:42:11 -03:00
|
|
|
|
|
|
|
model = "plane-soaring"
|
|
|
|
|
|
|
|
self.customise_SITL_commandline(
|
|
|
|
[],
|
|
|
|
model=model,
|
|
|
|
defaults_filepath=self.model_defaults_filepath(model),
|
|
|
|
wipe=True)
|
|
|
|
|
|
|
|
self.load_mission('CMAC-soar.txt', strict=False)
|
|
|
|
|
2022-08-26 07:45:12 -03:00
|
|
|
self.set_parameters({
|
|
|
|
"SIM_THML_SCENARI": 0, # Turn off environmental thermals.
|
|
|
|
"SOAR_ALT_MAX": 1000, # remove source of random failure
|
|
|
|
})
|
2021-06-07 07:42:11 -03:00
|
|
|
|
|
|
|
# Get thermalling RC channel
|
|
|
|
rc_chan = 0
|
|
|
|
for i in range(8):
|
|
|
|
rcx_option = self.get_parameter('RC{0}_OPTION'.format(i+1))
|
|
|
|
if rcx_option == 88:
|
|
|
|
rc_chan = i+1
|
|
|
|
break
|
|
|
|
|
|
|
|
if rc_chan == 0:
|
|
|
|
raise NotAchievedException("Did not find soaring enable channel option.")
|
|
|
|
|
|
|
|
# Disable soaring
|
|
|
|
self.set_rc(rc_chan, 1100)
|
|
|
|
|
|
|
|
self.set_current_waypoint(1)
|
|
|
|
self.change_mode('AUTO')
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
|
|
|
|
|
|
|
# Wait for to 400m before starting.
|
|
|
|
self.wait_altitude(390, 400, timeout=600, relative=True)
|
|
|
|
|
|
|
|
# Wait 10s to stabilize.
|
|
|
|
self.delay_sim_time(30)
|
|
|
|
|
|
|
|
# Enable soaring (no automatic thermalling)
|
|
|
|
self.set_rc(rc_chan, 1500)
|
|
|
|
|
2022-07-05 00:29:25 -03:00
|
|
|
self.set_parameters({
|
|
|
|
"SOAR_CRSE_ARSPD": -1, # Enable speed to fly.
|
|
|
|
"SOAR_VSPEED": 1, # Set appropriate McCready.
|
|
|
|
"SIM_WIND_SPD": 0,
|
|
|
|
})
|
2021-06-07 07:42:11 -03:00
|
|
|
|
2022-07-05 00:29:25 -03:00
|
|
|
self.progress('Waiting a few seconds before determining the "trim" airspeed.')
|
2021-06-07 07:42:11 -03:00
|
|
|
self.delay_sim_time(20)
|
2022-08-26 07:45:12 -03:00
|
|
|
m = self.assert_receive_message('VFR_HUD')
|
2021-06-07 07:42:11 -03:00
|
|
|
trim_airspeed = m.airspeed
|
2022-07-05 00:29:25 -03:00
|
|
|
self.progress("Using trim_airspeed=%f" % (trim_airspeed,))
|
2021-06-07 07:42:11 -03:00
|
|
|
|
|
|
|
min_airspeed = self.get_parameter("ARSPD_FBW_MIN")
|
|
|
|
max_airspeed = self.get_parameter("ARSPD_FBW_MAX")
|
|
|
|
|
2022-07-05 00:29:25 -03:00
|
|
|
if trim_airspeed > max_airspeed:
|
|
|
|
raise NotAchievedException("trim airspeed > max_airspeed (%f>%f)" %
|
|
|
|
(trim_airspeed, max_airspeed))
|
|
|
|
if trim_airspeed < min_airspeed:
|
|
|
|
raise NotAchievedException("trim airspeed < min_airspeed (%f<%f)" %
|
|
|
|
(trim_airspeed, min_airspeed))
|
2021-06-07 07:42:11 -03:00
|
|
|
|
2022-07-05 00:29:25 -03:00
|
|
|
self.progress("Adding updraft")
|
|
|
|
self.set_parameters({
|
|
|
|
"SIM_WIND_SPD": 1,
|
|
|
|
'SIM_WIND_DIR_Z': 90,
|
|
|
|
})
|
|
|
|
self.progress("Waiting for vehicle to move slower in updraft")
|
|
|
|
self.wait_airspeed(0, trim_airspeed-0.5, minimum_duration=10, timeout=120)
|
2021-06-07 07:42:11 -03:00
|
|
|
|
2022-07-05 00:29:25 -03:00
|
|
|
self.progress("Adding downdraft")
|
2021-06-07 07:42:11 -03:00
|
|
|
self.set_parameter('SIM_WIND_DIR_Z', -90)
|
2022-07-05 00:29:25 -03:00
|
|
|
self.progress("Waiting for vehicle to move faster in downdraft")
|
|
|
|
self.wait_airspeed(trim_airspeed+0.5, trim_airspeed+100, minimum_duration=10, timeout=120)
|
2021-06-07 07:42:11 -03:00
|
|
|
|
2022-07-05 00:29:25 -03:00
|
|
|
self.progress("Zeroing wind and increasing McCready")
|
|
|
|
self.set_parameters({
|
|
|
|
"SIM_WIND_SPD": 0,
|
|
|
|
"SOAR_VSPEED": 2,
|
|
|
|
})
|
|
|
|
self.progress("Waiting for airspeed to increase with higher VSPEED")
|
|
|
|
self.wait_airspeed(trim_airspeed+0.5, trim_airspeed+100, minimum_duration=10, timeout=120)
|
2021-06-07 07:42:11 -03:00
|
|
|
|
2022-08-26 07:45:12 -03:00
|
|
|
# mcReady tests don't work ATM, so just return early:
|
|
|
|
# takes too long to land, so just make it all go away:
|
|
|
|
self.disarm_vehicle(force=True)
|
|
|
|
self.reboot_sitl()
|
|
|
|
return
|
|
|
|
|
|
|
|
self.start_subtest('Test McReady values')
|
|
|
|
# Disable soaring
|
|
|
|
self.set_rc(rc_chan, 1100)
|
|
|
|
|
|
|
|
# Wait for to 400m before starting.
|
|
|
|
self.wait_altitude(390, 400, timeout=600, relative=True)
|
|
|
|
|
|
|
|
# Enable soaring
|
|
|
|
self.set_rc(rc_chan, 2000)
|
|
|
|
|
|
|
|
self.progress("Find airspeed with 1m/s updraft and mcready=1")
|
|
|
|
self.set_parameters({
|
|
|
|
"SOAR_VSPEED": 1,
|
|
|
|
"SIM_WIND_SPD": 1,
|
|
|
|
})
|
|
|
|
self.delay_sim_time(20)
|
|
|
|
m = self.assert_receive_message('VFR_HUD')
|
|
|
|
mcready1_speed = m.airspeed
|
|
|
|
self.progress("airspeed is %f" % mcready1_speed)
|
|
|
|
|
2022-07-05 00:29:25 -03:00
|
|
|
self.progress("Reducing McCready")
|
2022-08-26 07:45:12 -03:00
|
|
|
self.set_parameters({
|
|
|
|
"SOAR_VSPEED": 0.5,
|
|
|
|
})
|
|
|
|
self.progress("Waiting for airspeed to decrease with lower McReady")
|
|
|
|
self.wait_airspeed(0, mcready1_speed-0.5, minimum_duration=10, timeout=120)
|
|
|
|
|
|
|
|
self.progress("Increasing McCready")
|
|
|
|
self.set_parameters({
|
|
|
|
"SOAR_VSPEED": 1.5,
|
|
|
|
})
|
|
|
|
self.progress("Waiting for airspeed to decrease with lower McReady")
|
|
|
|
self.wait_airspeed(mcready1_speed+0.5, mcready1_speed+100, minimum_duration=10, timeout=120)
|
2021-06-07 07:42:11 -03:00
|
|
|
|
2022-07-05 00:29:25 -03:00
|
|
|
# takes too long to land, so just make it all go away:
|
|
|
|
self.disarm_vehicle(force=True)
|
|
|
|
self.reboot_sitl()
|
2021-06-07 07:42:11 -03:00
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def AirspeedDrivers(self):
|
|
|
|
'''Test AirSpeed drivers'''
|
2021-07-11 22:55:36 -03:00
|
|
|
airspeed_sensors = [
|
|
|
|
("MS5525", 3, 1),
|
|
|
|
("DLVR", 7, 2),
|
2022-05-24 02:08:07 -03:00
|
|
|
("SITL", 100, 0),
|
2021-07-11 22:55:36 -03:00
|
|
|
]
|
|
|
|
for (name, t, bus) in airspeed_sensors:
|
|
|
|
self.context_push()
|
|
|
|
if bus is not None:
|
|
|
|
self.set_parameter("ARSPD2_BUS", bus)
|
|
|
|
self.set_parameter("ARSPD2_TYPE", t)
|
|
|
|
self.reboot_sitl()
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
|
|
|
|
|
|
|
# insert listener to compare airspeeds:
|
|
|
|
airspeed = [None, None]
|
2022-06-11 01:10:09 -03:00
|
|
|
# don't start testing until we've seen real speed from
|
|
|
|
# both sensors. This gets us out of the noise area.
|
|
|
|
global initial_airspeed_threshold_reached
|
|
|
|
initial_airspeed_threshold_reached = False
|
2021-07-11 22:55:36 -03:00
|
|
|
|
|
|
|
def check_airspeeds(mav, m):
|
2022-06-11 01:10:09 -03:00
|
|
|
global initial_airspeed_threshold_reached
|
2021-07-11 22:55:36 -03:00
|
|
|
m_type = m.get_type()
|
|
|
|
if (m_type == 'NAMED_VALUE_FLOAT' and
|
|
|
|
m.name == 'AS2'):
|
|
|
|
airspeed[1] = m.value
|
|
|
|
elif m_type == 'VFR_HUD':
|
|
|
|
airspeed[0] = m.airspeed
|
|
|
|
else:
|
|
|
|
return
|
|
|
|
if airspeed[0] is None or airspeed[1] is None:
|
|
|
|
return
|
2022-08-28 20:55:41 -03:00
|
|
|
if airspeed[0] < 2 or airspeed[1] < 2:
|
|
|
|
# this mismatch can occur on takeoff, or when we
|
|
|
|
# smack into the ground at the end of the mission
|
|
|
|
return
|
2022-06-11 01:10:09 -03:00
|
|
|
if not initial_airspeed_threshold_reached:
|
2022-08-28 20:55:41 -03:00
|
|
|
if not (airspeed[0] > 10 or airspeed[1] > 10):
|
2022-06-11 01:10:09 -03:00
|
|
|
return
|
|
|
|
initial_airspeed_threshold_reached = True
|
2021-07-11 22:55:36 -03:00
|
|
|
delta = abs(airspeed[0] - airspeed[1])
|
|
|
|
if delta > 2:
|
|
|
|
raise NotAchievedException("Airspeed mismatch (as1=%f as2=%f)" % (airspeed[0], airspeed[1]))
|
|
|
|
self.install_message_hook_context(check_airspeeds)
|
|
|
|
self.fly_mission("ap1.txt", strict=False)
|
|
|
|
if airspeed[0] is None:
|
|
|
|
raise NotAchievedException("Never saw an airspeed1")
|
|
|
|
if airspeed[1] is None:
|
|
|
|
raise NotAchievedException("Never saw an airspeed2")
|
|
|
|
self.context_pop()
|
2020-12-16 04:03:53 -04:00
|
|
|
self.reboot_sitl()
|
|
|
|
|
2022-02-17 00:16:47 -04:00
|
|
|
def TerrainMission(self):
|
2022-09-09 22:24:28 -03:00
|
|
|
'''Test terrain following in mission'''
|
2022-08-01 02:00:22 -03:00
|
|
|
self.install_terrain_handlers_context()
|
2022-08-01 05:49:40 -03:00
|
|
|
|
|
|
|
num_wp = self.load_mission("ap-terrain.txt")
|
|
|
|
|
2022-08-01 02:00:22 -03:00
|
|
|
self.wait_ready_to_arm()
|
2020-07-04 14:57:49 -03:00
|
|
|
self.arm_vehicle()
|
|
|
|
|
2022-08-01 05:49:40 -03:00
|
|
|
global max_alt
|
|
|
|
max_alt = 0
|
|
|
|
|
|
|
|
def record_maxalt(mav, m):
|
|
|
|
global max_alt
|
|
|
|
if m.get_type() != 'GLOBAL_POSITION_INT':
|
|
|
|
return
|
|
|
|
if m.relative_alt/1000.0 > max_alt:
|
|
|
|
max_alt = m.relative_alt/1000.0
|
|
|
|
|
|
|
|
self.install_message_hook(record_maxalt)
|
|
|
|
|
|
|
|
self.fly_mission_waypoints(num_wp-1, mission_timeout=600)
|
|
|
|
|
|
|
|
if max_alt < 200:
|
|
|
|
raise NotAchievedException("Did not follow terrain")
|
2020-07-04 14:57:49 -03:00
|
|
|
|
2022-02-17 00:59:08 -04:00
|
|
|
def Terrain(self):
|
|
|
|
'''test AP_Terrain'''
|
|
|
|
self.reboot_sitl() # we know the terrain height at CMAC
|
|
|
|
|
2022-08-01 02:00:22 -03:00
|
|
|
self.install_terrain_handlers_context()
|
2022-02-17 00:59:08 -04:00
|
|
|
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
loc = self.mav.location()
|
|
|
|
|
|
|
|
lng_int = int(loc.lng * 1e7)
|
|
|
|
lat_int = int(loc.lat * 1e7)
|
|
|
|
|
|
|
|
# FIXME: once we have a pre-populated terrain cache this
|
|
|
|
# should require an instantly correct report to pass
|
|
|
|
tstart = self.get_sim_time_cached()
|
2022-06-11 02:26:53 -03:00
|
|
|
last_terrain_report_pending = -1
|
2022-02-17 00:59:08 -04:00
|
|
|
while True:
|
2022-06-11 02:26:53 -03:00
|
|
|
now = self.get_sim_time_cached()
|
|
|
|
if now - tstart > 60:
|
2022-02-17 00:59:08 -04:00
|
|
|
raise NotAchievedException("Did not get correct terrain report")
|
|
|
|
|
|
|
|
self.mav.mav.terrain_check_send(lat_int, lng_int)
|
|
|
|
|
|
|
|
report = self.mav.recv_match(type='TERRAIN_REPORT', blocking=True, timeout=60)
|
|
|
|
self.progress(self.dump_message_verbose(report))
|
|
|
|
if report.spacing != 0:
|
|
|
|
break
|
|
|
|
|
2022-06-11 02:26:53 -03:00
|
|
|
# we will keep trying to long as the number of pending
|
|
|
|
# tiles is dropping:
|
|
|
|
if last_terrain_report_pending == -1:
|
|
|
|
last_terrain_report_pending = report.pending
|
|
|
|
elif report.pending < last_terrain_report_pending:
|
|
|
|
last_terrain_report_pending = report.pending
|
|
|
|
tstart = now
|
|
|
|
|
2022-02-17 00:59:08 -04:00
|
|
|
self.delay_sim_time(1)
|
|
|
|
|
|
|
|
self.progress(self.dump_message_verbose(report))
|
|
|
|
|
|
|
|
expected_terrain_height = 583.5
|
|
|
|
if abs(report.terrain_height - expected_terrain_height) > 0.5:
|
|
|
|
raise NotAchievedException("Expected terrain height=%f got=%f" %
|
|
|
|
(expected_terrain_height, report.terrain_height))
|
|
|
|
|
2022-08-16 01:27:07 -03:00
|
|
|
def TerrainLoiter(self):
|
2022-09-09 22:24:28 -03:00
|
|
|
'''Test terrain following in loiter'''
|
2022-08-16 01:27:07 -03:00
|
|
|
self.context_push()
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"TERRAIN_FOLLOW": 1, # enable terrain following in loiter
|
|
|
|
"WP_LOITER_RAD": 2000, # set very large loiter rad to get some terrain changes
|
|
|
|
})
|
2021-04-04 16:34:45 -03:00
|
|
|
alt = 200
|
|
|
|
self.takeoff(alt*0.9, alt*1.1)
|
|
|
|
self.set_rc(3, 1500)
|
|
|
|
self.change_mode("LOITER")
|
|
|
|
self.progress("loitering at %um" % alt)
|
|
|
|
tstart = self.get_sim_time()
|
2022-08-16 01:27:07 -03:00
|
|
|
timeout = 60*15 # enough time to do one and a bit circles
|
2022-07-17 09:09:33 -03:00
|
|
|
max_delta = 0
|
2021-04-04 16:34:45 -03:00
|
|
|
while True:
|
|
|
|
now = self.get_sim_time_cached()
|
2022-08-16 01:27:07 -03:00
|
|
|
if now - tstart > timeout:
|
2021-04-04 16:34:45 -03:00
|
|
|
break
|
2022-07-17 09:09:33 -03:00
|
|
|
gpi = self.assert_receive_message('GLOBAL_POSITION_INT')
|
2022-08-16 01:27:07 -03:00
|
|
|
terrain = self.assert_receive_message('TERRAIN_REPORT')
|
2021-04-04 16:34:45 -03:00
|
|
|
rel_alt = terrain.current_height
|
2022-07-17 09:09:33 -03:00
|
|
|
self.progress("%um above terrain (%um bove home)" %
|
|
|
|
(rel_alt, gpi.relative_alt/1000.0))
|
2021-04-04 16:34:45 -03:00
|
|
|
if rel_alt > alt*1.2 or rel_alt < alt * 0.8:
|
|
|
|
raise NotAchievedException("Not terrain following")
|
2022-07-17 09:09:33 -03:00
|
|
|
delta = abs(rel_alt - gpi.relative_alt/1000.0)
|
|
|
|
if delta > max_delta:
|
|
|
|
max_delta = delta
|
|
|
|
want_max_delta = 30
|
|
|
|
if max_delta < want_max_delta:
|
|
|
|
raise NotAchievedException(
|
|
|
|
"Expected terrain and home alts to vary more than they did (max=%u want=%u)" %
|
|
|
|
(max_delta, want_max_delta))
|
2022-08-16 01:27:07 -03:00
|
|
|
self.context_pop()
|
2021-04-04 16:34:45 -03:00
|
|
|
self.progress("Returning home")
|
|
|
|
self.fly_home_land_and_disarm(240)
|
|
|
|
|
2021-09-30 05:35:51 -03:00
|
|
|
def fly_external_AHRS(self, sim, eahrs_type, mission):
|
2021-01-01 02:24:58 -04:00
|
|
|
"""Fly with external AHRS (VectorNav)"""
|
2021-09-30 05:35:51 -03:00
|
|
|
self.customise_SITL_commandline(["--uartE=sim:%s" % sim])
|
2021-01-01 02:24:58 -04:00
|
|
|
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"EAHRS_TYPE": eahrs_type,
|
|
|
|
"SERIAL4_PROTOCOL": 36,
|
|
|
|
"SERIAL4_BAUD": 230400,
|
|
|
|
"GPS_TYPE": 21,
|
|
|
|
"AHRS_EKF_TYPE": 11,
|
|
|
|
"INS_GYR_CAL": 1,
|
|
|
|
})
|
2021-01-01 02:24:58 -04:00
|
|
|
self.reboot_sitl()
|
2022-09-07 21:53:38 -03:00
|
|
|
self.delay_sim_time(5)
|
2021-01-01 02:24:58 -04:00
|
|
|
self.progress("Running accelcal")
|
2023-07-15 09:40:01 -03:00
|
|
|
self.run_cmd(
|
|
|
|
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
|
|
|
|
p5=4,
|
|
|
|
timeout=5,
|
|
|
|
)
|
2021-01-01 02:24:58 -04:00
|
|
|
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
2021-09-30 05:35:51 -03:00
|
|
|
self.fly_mission(mission)
|
|
|
|
|
2022-10-10 00:47:57 -03:00
|
|
|
def wait_and_maintain_wind_estimate(
|
|
|
|
self,
|
|
|
|
want_speed,
|
|
|
|
want_dir,
|
|
|
|
timeout=10,
|
|
|
|
speed_tolerance=0.5,
|
|
|
|
dir_tolerance=5,
|
|
|
|
**kwargs):
|
|
|
|
'''wait for wind estimate to reach speed and direction'''
|
|
|
|
|
|
|
|
def validator(last, _min, _max):
|
|
|
|
'''returns false of spd or direction is too-far wrong'''
|
|
|
|
(spd, di) = last
|
|
|
|
_min_spd, _min_dir = _min
|
|
|
|
_max_spd, _max_dir = _max
|
|
|
|
if spd < _min_spd or spd > _max_spd:
|
|
|
|
return False
|
|
|
|
# my apologies to whoever is staring at this and wondering
|
|
|
|
# why we're not wrapping angles here...
|
|
|
|
if di < _min_dir or di > _max_dir:
|
|
|
|
return False
|
|
|
|
return True
|
|
|
|
|
|
|
|
def value_getter():
|
|
|
|
'''returns a tuple of (wind_speed, wind_dir), where wind_dir is 45 if
|
|
|
|
wind is coming from NE'''
|
|
|
|
m = self.assert_receive_message("WIND")
|
|
|
|
return (m.speed, m.direction)
|
|
|
|
|
|
|
|
class ValueAverager(object):
|
|
|
|
def __init__(self):
|
|
|
|
self.speed_average = -1
|
|
|
|
self.dir_average = -1
|
|
|
|
self.count = 0.0
|
|
|
|
|
|
|
|
def add_value(self, value):
|
|
|
|
(spd, di) = value
|
|
|
|
if self.speed_average == -1:
|
|
|
|
self.speed_average = spd
|
|
|
|
self.dir_average = di
|
|
|
|
else:
|
|
|
|
self.speed_average += spd
|
|
|
|
self.di_average += spd
|
|
|
|
self.count += 1
|
|
|
|
return (self.speed_average/self.count, self.dir_average/self.count)
|
|
|
|
|
|
|
|
def reset(self):
|
|
|
|
self.count = 0
|
|
|
|
self.speed_average = -1
|
|
|
|
self.dir_average = -1
|
|
|
|
|
|
|
|
self.wait_and_maintain_range(
|
|
|
|
value_name="WindEstimates",
|
|
|
|
minimum=(want_speed-speed_tolerance, want_dir-dir_tolerance),
|
|
|
|
maximum=(want_speed+speed_tolerance, want_dir+dir_tolerance),
|
|
|
|
current_value_getter=value_getter,
|
|
|
|
value_averager=ValueAverager(),
|
|
|
|
validator=lambda last, _min, _max: validator(last, _min, _max),
|
|
|
|
timeout=timeout,
|
|
|
|
**kwargs
|
|
|
|
)
|
|
|
|
|
|
|
|
def WindEstimates(self):
|
|
|
|
'''fly non-external AHRS, ensure wind estimate correct'''
|
|
|
|
self.set_parameters({
|
|
|
|
"SIM_WIND_SPD": 5,
|
|
|
|
"SIM_WIND_DIR": 45,
|
|
|
|
})
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.takeoff(70) # default wind sim wind is a sqrt function up to 60m
|
|
|
|
self.change_mode('LOITER')
|
|
|
|
# use default estimator to determine when to check others:
|
|
|
|
self.wait_and_maintain_wind_estimate(5, 45, timeout=120)
|
|
|
|
|
|
|
|
for ahrs_type in 0, 2, 3, 10:
|
|
|
|
self.start_subtest("Checking AHRS_EKF_TYPE=%u" % ahrs_type)
|
|
|
|
self.set_parameter("AHRS_EKF_TYPE", ahrs_type)
|
2023-01-04 22:55:45 -04:00
|
|
|
self.wait_and_maintain_wind_estimate(
|
|
|
|
5, 45,
|
|
|
|
speed_tolerance=1,
|
2023-08-16 00:47:09 -03:00
|
|
|
timeout=30
|
2023-01-04 22:55:45 -04:00
|
|
|
)
|
2022-10-10 00:47:57 -03:00
|
|
|
self.fly_home_land_and_disarm()
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def VectorNavEAHRS(self):
|
|
|
|
'''Test VectorNav EAHRS support'''
|
2021-09-30 05:35:51 -03:00
|
|
|
self.fly_external_AHRS("VectorNav", 1, "ap1.txt")
|
|
|
|
|
2023-08-27 19:42:56 -03:00
|
|
|
def MicroStrainEAHRS5(self):
|
|
|
|
'''Test MicroStrain EAHRS series 5 support'''
|
|
|
|
self.fly_external_AHRS("MicroStrain5", 2, "ap1.txt")
|
2021-01-01 02:24:58 -04:00
|
|
|
|
2021-01-09 06:04:29 -04:00
|
|
|
def get_accelvec(self, m):
|
|
|
|
return Vector3(m.xacc, m.yacc, m.zacc) * 0.001 * 9.81
|
|
|
|
|
|
|
|
def get_gyrovec(self, m):
|
|
|
|
return Vector3(m.xgyro, m.ygyro, m.zgyro) * 0.001 * math.degrees(1)
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def IMUTempCal(self):
|
|
|
|
'''Test IMU temperature calibration'''
|
2021-01-13 21:16:39 -04:00
|
|
|
self.progress("Setting up SITL temperature profile")
|
|
|
|
self.set_parameters({
|
|
|
|
"SIM_IMUT1_ENABLE" : 1,
|
2021-01-09 06:04:29 -04:00
|
|
|
"SIM_IMUT1_ACC1_X" : 120000.000000,
|
|
|
|
"SIM_IMUT1_ACC1_Y" : -190000.000000,
|
|
|
|
"SIM_IMUT1_ACC1_Z" : 1493.864746,
|
|
|
|
"SIM_IMUT1_ACC2_X" : -51.624416,
|
|
|
|
"SIM_IMUT1_ACC2_Y" : 10.364172,
|
|
|
|
"SIM_IMUT1_ACC2_Z" : -7878.000000,
|
|
|
|
"SIM_IMUT1_ACC3_X" : -0.514242,
|
|
|
|
"SIM_IMUT1_ACC3_Y" : 0.862218,
|
|
|
|
"SIM_IMUT1_ACC3_Z" : -234.000000,
|
|
|
|
"SIM_IMUT1_GYR1_X" : -5122.513817,
|
|
|
|
"SIM_IMUT1_GYR1_Y" : -3250.470428,
|
|
|
|
"SIM_IMUT1_GYR1_Z" : -2136.346676,
|
|
|
|
"SIM_IMUT1_GYR2_X" : 30.720505,
|
|
|
|
"SIM_IMUT1_GYR2_Y" : 17.778447,
|
|
|
|
"SIM_IMUT1_GYR2_Z" : 0.765997,
|
|
|
|
"SIM_IMUT1_GYR3_X" : -0.003572,
|
|
|
|
"SIM_IMUT1_GYR3_Y" : 0.036346,
|
|
|
|
"SIM_IMUT1_GYR3_Z" : 0.015457,
|
2021-01-17 20:41:42 -04:00
|
|
|
"SIM_IMUT1_TMAX" : 70.0,
|
|
|
|
"SIM_IMUT1_TMIN" : -20.000000,
|
2021-01-13 21:16:39 -04:00
|
|
|
"SIM_IMUT2_ENABLE" : 1,
|
2021-01-09 06:04:29 -04:00
|
|
|
"SIM_IMUT2_ACC1_X" : -160000.000000,
|
|
|
|
"SIM_IMUT2_ACC1_Y" : 198730.000000,
|
|
|
|
"SIM_IMUT2_ACC1_Z" : 27812.000000,
|
|
|
|
"SIM_IMUT2_ACC2_X" : 30.658159,
|
|
|
|
"SIM_IMUT2_ACC2_Y" : 32.085022,
|
|
|
|
"SIM_IMUT2_ACC2_Z" : 1572.000000,
|
|
|
|
"SIM_IMUT2_ACC3_X" : 0.102912,
|
|
|
|
"SIM_IMUT2_ACC3_Y" : 0.229734,
|
|
|
|
"SIM_IMUT2_ACC3_Z" : 172.000000,
|
|
|
|
"SIM_IMUT2_GYR1_X" : 3173.925644,
|
|
|
|
"SIM_IMUT2_GYR1_Y" : -2368.312836,
|
|
|
|
"SIM_IMUT2_GYR1_Z" : -1796.497177,
|
|
|
|
"SIM_IMUT2_GYR2_X" : 13.029696,
|
|
|
|
"SIM_IMUT2_GYR2_Y" : -10.349280,
|
|
|
|
"SIM_IMUT2_GYR2_Z" : -15.082653,
|
|
|
|
"SIM_IMUT2_GYR3_X" : 0.004831,
|
|
|
|
"SIM_IMUT2_GYR3_Y" : -0.020528,
|
|
|
|
"SIM_IMUT2_GYR3_Z" : 0.009469,
|
2021-01-17 20:41:42 -04:00
|
|
|
"SIM_IMUT2_TMAX" : 70.000000,
|
|
|
|
"SIM_IMUT2_TMIN" : -20.000000,
|
2021-01-09 06:04:29 -04:00
|
|
|
"SIM_IMUT_END" : 45.000000,
|
|
|
|
"SIM_IMUT_START" : 3.000000,
|
|
|
|
"SIM_IMUT_TCONST" : 75.000000,
|
|
|
|
"SIM_DRIFT_SPEED" : 0,
|
2021-01-18 03:47:37 -04:00
|
|
|
"INS_GYR_CAL" : 0,
|
2021-01-13 21:16:39 -04:00
|
|
|
})
|
2021-01-09 06:04:29 -04:00
|
|
|
|
2021-01-18 03:47:37 -04:00
|
|
|
self.set_parameter("SIM_IMUT_FIXED", 12)
|
|
|
|
self.progress("Running accel cal")
|
2023-07-15 09:40:01 -03:00
|
|
|
self.run_cmd(
|
|
|
|
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
|
|
|
|
p5=4,
|
|
|
|
timeout=5,
|
|
|
|
)
|
2021-01-18 03:47:37 -04:00
|
|
|
self.progress("Running gyro cal")
|
2023-07-15 09:40:01 -03:00
|
|
|
self.run_cmd(
|
|
|
|
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
|
|
|
|
p5=1,
|
|
|
|
timeout=5,
|
|
|
|
)
|
2021-01-19 23:52:58 -04:00
|
|
|
self.set_parameters({
|
2021-02-11 22:44:28 -04:00
|
|
|
"SIM_IMUT_FIXED": 0,
|
|
|
|
"INS_TCAL1_ENABLE": 2,
|
|
|
|
"INS_TCAL1_TMAX": 42,
|
|
|
|
"INS_TCAL2_ENABLE": 2,
|
|
|
|
"INS_TCAL2_TMAX": 42,
|
|
|
|
"SIM_SPEEDUP": 200,
|
|
|
|
})
|
2021-01-09 06:04:29 -04:00
|
|
|
self.set_parameter("LOG_DISARMED", 1)
|
|
|
|
self.reboot_sitl()
|
|
|
|
|
|
|
|
self.progress("Waiting for IMU temperature")
|
2021-01-19 23:52:58 -04:00
|
|
|
self.assert_reach_imu_temperature(43, timeout=600)
|
2021-01-09 06:04:29 -04:00
|
|
|
|
|
|
|
if self.get_parameter("INS_TCAL1_ENABLE") != 1.0:
|
|
|
|
raise NotAchievedException("TCAL1 did not complete")
|
|
|
|
if self.get_parameter("INS_TCAL2_ENABLE") != 1.0:
|
|
|
|
raise NotAchievedException("TCAL2 did not complete")
|
|
|
|
|
2021-01-19 23:52:58 -04:00
|
|
|
self.progress("Logging with calibration enabled")
|
2021-01-09 06:04:29 -04:00
|
|
|
self.reboot_sitl()
|
|
|
|
|
2021-01-19 23:52:58 -04:00
|
|
|
self.assert_reach_imu_temperature(43, timeout=600)
|
2021-01-09 06:04:29 -04:00
|
|
|
|
|
|
|
self.progress("Testing with compensation enabled")
|
|
|
|
|
2021-02-11 22:44:28 -04:00
|
|
|
test_temperatures = range(10, 45, 5)
|
2021-01-17 20:41:42 -04:00
|
|
|
corrected = {}
|
|
|
|
uncorrected = {}
|
|
|
|
|
|
|
|
for temp in test_temperatures:
|
2021-01-09 06:04:29 -04:00
|
|
|
self.progress("Testing temperature %.1f" % temp)
|
|
|
|
self.set_parameter("SIM_IMUT_FIXED", temp)
|
2021-01-20 01:18:55 -04:00
|
|
|
self.delay_sim_time(2)
|
2021-01-09 06:04:29 -04:00
|
|
|
for msg in ['RAW_IMU', 'SCALED_IMU2']:
|
2022-02-09 20:59:34 -04:00
|
|
|
m = self.assert_receive_message(msg, timeout=2)
|
2021-01-09 06:04:29 -04:00
|
|
|
temperature = m.temperature*0.01
|
|
|
|
|
|
|
|
if abs(temperature - temp) > 0.2:
|
|
|
|
raise NotAchievedException("incorrect %s temperature %.1f should be %.1f" % (msg, temperature, temp))
|
|
|
|
|
|
|
|
accel = self.get_accelvec(m)
|
|
|
|
gyro = self.get_gyrovec(m)
|
2021-02-11 22:44:28 -04:00
|
|
|
accel2 = accel + Vector3(0, 0, 9.81)
|
2021-01-09 06:04:29 -04:00
|
|
|
|
2021-01-17 20:41:42 -04:00
|
|
|
corrected[temperature] = (accel2, gyro)
|
2021-01-09 06:04:29 -04:00
|
|
|
|
|
|
|
self.progress("Testing with compensation disabled")
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"INS_TCAL1_ENABLE": 0,
|
|
|
|
"INS_TCAL2_ENABLE": 0,
|
|
|
|
})
|
2021-01-09 06:04:29 -04:00
|
|
|
|
2021-01-20 01:35:10 -04:00
|
|
|
gyro_threshold = 0.2
|
|
|
|
accel_threshold = 0.2
|
|
|
|
|
2021-01-17 20:41:42 -04:00
|
|
|
for temp in test_temperatures:
|
2021-01-09 06:04:29 -04:00
|
|
|
self.progress("Testing temperature %.1f" % temp)
|
|
|
|
self.set_parameter("SIM_IMUT_FIXED", temp)
|
|
|
|
self.wait_heartbeat()
|
|
|
|
self.wait_heartbeat()
|
|
|
|
for msg in ['RAW_IMU', 'SCALED_IMU2']:
|
2022-02-09 20:59:34 -04:00
|
|
|
m = self.assert_receive_message(msg, timeout=2)
|
2021-01-09 06:04:29 -04:00
|
|
|
temperature = m.temperature*0.01
|
|
|
|
|
|
|
|
if abs(temperature - temp) > 0.2:
|
|
|
|
raise NotAchievedException("incorrect %s temperature %.1f should be %.1f" % (msg, temperature, temp))
|
|
|
|
|
|
|
|
accel = self.get_accelvec(m)
|
|
|
|
gyro = self.get_gyrovec(m)
|
|
|
|
|
2021-02-11 22:44:28 -04:00
|
|
|
accel2 = accel + Vector3(0, 0, 9.81)
|
2021-01-17 20:41:42 -04:00
|
|
|
uncorrected[temperature] = (accel2, gyro)
|
|
|
|
|
|
|
|
for temp in test_temperatures:
|
|
|
|
(accel, gyro) = corrected[temp]
|
|
|
|
self.progress("Corrected gyro at %.1f %s" % (temp, gyro))
|
|
|
|
self.progress("Corrected accel at %.1f %s" % (temp, accel))
|
|
|
|
|
|
|
|
for temp in test_temperatures:
|
|
|
|
(accel, gyro) = uncorrected[temp]
|
|
|
|
self.progress("Uncorrected gyro at %.1f %s" % (temp, gyro))
|
|
|
|
self.progress("Uncorrected accel at %.1f %s" % (temp, accel))
|
2021-02-11 22:44:28 -04:00
|
|
|
|
2021-01-17 20:41:42 -04:00
|
|
|
bad_value = False
|
|
|
|
for temp in test_temperatures:
|
|
|
|
(accel, gyro) = corrected[temp]
|
|
|
|
if gyro.length() > gyro_threshold:
|
|
|
|
raise NotAchievedException("incorrect corrected at %.1f gyro %s" % (temp, gyro))
|
|
|
|
|
|
|
|
if accel.length() > accel_threshold:
|
|
|
|
raise NotAchievedException("incorrect corrected at %.1f accel %s" % (temp, accel))
|
|
|
|
|
|
|
|
(accel, gyro) = uncorrected[temp]
|
|
|
|
if gyro.length() > gyro_threshold*2:
|
|
|
|
bad_value = True
|
|
|
|
|
|
|
|
if accel.length() > accel_threshold*2:
|
|
|
|
bad_value = True
|
2021-01-09 06:04:29 -04:00
|
|
|
|
|
|
|
if not bad_value:
|
|
|
|
raise NotAchievedException("uncompensated IMUs did not vary enough")
|
|
|
|
|
2021-06-08 23:07:51 -03:00
|
|
|
# the above tests change the internal persistent state of the
|
|
|
|
# vehicle in ways that autotest doesn't track (magically set
|
|
|
|
# parameters). So wipe the vehicle's eeprom:
|
|
|
|
self.reset_SITL_commandline()
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def EKFlaneswitch(self):
|
|
|
|
'''Test EKF3 Affinity and Lane Switching'''
|
2020-07-16 07:17:54 -03:00
|
|
|
|
|
|
|
self.context_push()
|
|
|
|
ex = None
|
|
|
|
|
|
|
|
# new lane swtich available only with EK3
|
2021-01-17 21:41:39 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"EK3_ENABLE": 1,
|
|
|
|
"EK2_ENABLE": 0,
|
|
|
|
"AHRS_EKF_TYPE": 3,
|
|
|
|
"EK3_AFFINITY": 15, # enable affinity for all sensors
|
|
|
|
"EK3_IMU_MASK": 3, # use only 2 IMUs
|
|
|
|
"GPS_TYPE2": 1,
|
|
|
|
"SIM_GPS2_DISABLE": 0,
|
|
|
|
"SIM_BARO_COUNT": 2,
|
|
|
|
"SIM_BAR2_DISABLE": 0,
|
|
|
|
"ARSPD2_TYPE": 2,
|
|
|
|
"ARSPD2_USE": 1,
|
|
|
|
"ARSPD2_PIN": 2,
|
|
|
|
})
|
2020-07-16 07:17:54 -03:00
|
|
|
|
|
|
|
# some parameters need reboot to take effect
|
|
|
|
self.reboot_sitl()
|
|
|
|
|
|
|
|
self.lane_switches = []
|
2021-02-11 22:44:28 -04:00
|
|
|
|
2020-07-16 07:17:54 -03:00
|
|
|
# add an EKF lane switch hook
|
|
|
|
def statustext_hook(mav, message):
|
|
|
|
if message.get_type() != 'STATUSTEXT':
|
|
|
|
return
|
|
|
|
# example msg: EKF3 lane switch 1
|
|
|
|
if not message.text.startswith("EKF3 lane switch "):
|
|
|
|
return
|
|
|
|
newlane = int(message.text[-1])
|
2021-02-11 22:44:28 -04:00
|
|
|
self.lane_switches.append(newlane)
|
2020-07-16 07:17:54 -03:00
|
|
|
self.install_message_hook(statustext_hook)
|
|
|
|
|
|
|
|
# get flying
|
|
|
|
self.takeoff(alt=50)
|
|
|
|
self.change_mode('CIRCLE')
|
|
|
|
|
|
|
|
try:
|
2021-02-11 22:44:28 -04:00
|
|
|
###################################################################
|
2020-07-16 07:17:54 -03:00
|
|
|
self.progress("Checking EKF3 Lane Switching trigger from all sensors")
|
2021-02-11 22:44:28 -04:00
|
|
|
###################################################################
|
2020-07-16 07:17:54 -03:00
|
|
|
self.start_subtest("ACCELEROMETER: Change z-axis offset")
|
|
|
|
# create an accelerometer error by changing the Z-axis offset
|
2020-09-10 16:56:56 -03:00
|
|
|
self.context_collect("STATUSTEXT")
|
2020-07-16 07:17:54 -03:00
|
|
|
old_parameter = self.get_parameter("INS_ACCOFFS_Z")
|
2021-02-11 22:44:28 -04:00
|
|
|
self.wait_statustext(
|
|
|
|
text="EKF3 lane switch",
|
|
|
|
timeout=30,
|
|
|
|
the_function=self.set_parameter("INS_ACCOFFS_Z", old_parameter + 5),
|
|
|
|
check_context=True)
|
2020-07-16 07:17:54 -03:00
|
|
|
if self.lane_switches != [1]:
|
|
|
|
raise NotAchievedException("Expected lane switch 1, got %s" % str(self.lane_switches[-1]))
|
|
|
|
# Cleanup
|
|
|
|
self.set_parameter("INS_ACCOFFS_Z", old_parameter)
|
2020-09-10 16:56:56 -03:00
|
|
|
self.context_clear_collection("STATUSTEXT")
|
2020-07-16 07:17:54 -03:00
|
|
|
self.wait_heading(0, accuracy=10, timeout=60)
|
|
|
|
self.wait_heading(180, accuracy=10, timeout=60)
|
2021-02-11 22:44:28 -04:00
|
|
|
###################################################################
|
2020-07-16 07:17:54 -03:00
|
|
|
self.start_subtest("BAROMETER: Freeze to last measured value")
|
2020-09-10 16:56:56 -03:00
|
|
|
self.context_collect("STATUSTEXT")
|
2020-07-16 07:17:54 -03:00
|
|
|
# create a barometer error by inhibiting any pressure change while changing altitude
|
2020-11-24 21:28:26 -04:00
|
|
|
old_parameter = self.get_parameter("SIM_BAR2_FREEZE")
|
|
|
|
self.set_parameter("SIM_BAR2_FREEZE", 1)
|
2021-02-11 22:44:28 -04:00
|
|
|
self.wait_statustext(
|
|
|
|
text="EKF3 lane switch",
|
|
|
|
timeout=30,
|
|
|
|
the_function=lambda: self.set_rc(2, 2000),
|
|
|
|
check_context=True)
|
2020-07-16 07:17:54 -03:00
|
|
|
if self.lane_switches != [1, 0]:
|
|
|
|
raise NotAchievedException("Expected lane switch 0, got %s" % str(self.lane_switches[-1]))
|
|
|
|
# Cleanup
|
|
|
|
self.set_rc(2, 1500)
|
2020-11-24 21:28:26 -04:00
|
|
|
self.set_parameter("SIM_BAR2_FREEZE", old_parameter)
|
2020-09-10 16:56:56 -03:00
|
|
|
self.context_clear_collection("STATUSTEXT")
|
2020-07-16 07:17:54 -03:00
|
|
|
self.wait_heading(0, accuracy=10, timeout=60)
|
|
|
|
self.wait_heading(180, accuracy=10, timeout=60)
|
2021-02-11 22:44:28 -04:00
|
|
|
###################################################################
|
2020-07-16 07:17:54 -03:00
|
|
|
self.start_subtest("GPS: Apply GPS Velocity Error in NED")
|
|
|
|
self.context_push()
|
2020-09-10 16:56:56 -03:00
|
|
|
self.context_collect("STATUSTEXT")
|
2021-02-11 22:44:28 -04:00
|
|
|
|
|
|
|
# create a GPS velocity error by adding a random 2m/s
|
|
|
|
# noise on each axis
|
2020-09-10 16:56:56 -03:00
|
|
|
def sim_gps_verr():
|
2021-01-17 21:41:39 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"SIM_GPS_VERR_X": self.get_parameter("SIM_GPS_VERR_X") + 2,
|
|
|
|
"SIM_GPS_VERR_Y": self.get_parameter("SIM_GPS_VERR_Y") + 2,
|
|
|
|
"SIM_GPS_VERR_Z": self.get_parameter("SIM_GPS_VERR_Z") + 2,
|
|
|
|
})
|
|
|
|
self.wait_statustext(text="EKF3 lane switch", timeout=30, the_function=sim_gps_verr, check_context=True)
|
2020-07-16 07:17:54 -03:00
|
|
|
if self.lane_switches != [1, 0, 1]:
|
|
|
|
raise NotAchievedException("Expected lane switch 1, got %s" % str(self.lane_switches[-1]))
|
|
|
|
# Cleanup
|
|
|
|
self.context_pop()
|
2020-09-10 16:56:56 -03:00
|
|
|
self.context_clear_collection("STATUSTEXT")
|
2020-07-16 07:17:54 -03:00
|
|
|
self.wait_heading(0, accuracy=10, timeout=60)
|
|
|
|
self.wait_heading(180, accuracy=10, timeout=60)
|
2021-02-11 22:44:28 -04:00
|
|
|
###################################################################
|
2020-07-16 07:17:54 -03:00
|
|
|
self.start_subtest("MAGNETOMETER: Change X-Axis Offset")
|
2020-09-10 16:56:56 -03:00
|
|
|
self.context_collect("STATUSTEXT")
|
2020-07-16 07:17:54 -03:00
|
|
|
# create a magnetometer error by changing the X-axis offset
|
2020-09-10 16:56:56 -03:00
|
|
|
old_parameter = self.get_parameter("SIM_MAG2_OFS_X")
|
2021-02-11 22:44:28 -04:00
|
|
|
self.wait_statustext(
|
|
|
|
text="EKF3 lane switch",
|
|
|
|
timeout=30,
|
|
|
|
the_function=self.set_parameter("SIM_MAG2_OFS_X", old_parameter + 150),
|
|
|
|
check_context=True)
|
2020-07-16 07:17:54 -03:00
|
|
|
if self.lane_switches != [1, 0, 1, 0]:
|
|
|
|
raise NotAchievedException("Expected lane switch 0, got %s" % str(self.lane_switches[-1]))
|
|
|
|
# Cleanup
|
|
|
|
self.set_parameter("SIM_MAG2_OFS_X", old_parameter)
|
2020-09-10 16:56:56 -03:00
|
|
|
self.context_clear_collection("STATUSTEXT")
|
2020-07-16 07:17:54 -03:00
|
|
|
self.wait_heading(0, accuracy=10, timeout=60)
|
|
|
|
self.wait_heading(180, accuracy=10, timeout=60)
|
2021-02-11 22:44:28 -04:00
|
|
|
###################################################################
|
2020-07-16 07:17:54 -03:00
|
|
|
self.start_subtest("AIRSPEED: Fail to constant value")
|
|
|
|
self.context_push()
|
2020-09-10 16:56:56 -03:00
|
|
|
self.context_collect("STATUSTEXT")
|
2021-07-19 02:38:51 -03:00
|
|
|
|
2020-07-16 07:17:54 -03:00
|
|
|
old_parameter = self.get_parameter("SIM_ARSPD_FAIL")
|
2021-02-11 22:44:28 -04:00
|
|
|
|
2021-07-19 02:38:51 -03:00
|
|
|
def fail_speed():
|
2020-09-10 16:56:56 -03:00
|
|
|
self.change_mode("GUIDED")
|
2021-07-19 02:38:51 -03:00
|
|
|
loc = self.mav.location()
|
2020-09-10 16:56:56 -03:00
|
|
|
self.run_cmd_int(
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
|
2023-07-15 09:40:01 -03:00
|
|
|
p5=int(loc.lat * 1e7),
|
|
|
|
p6=int(loc.lng * 1e7),
|
|
|
|
p7=50, # alt
|
2020-09-10 16:56:56 -03:00
|
|
|
)
|
|
|
|
self.delay_sim_time(5)
|
2021-07-19 02:38:51 -03:00
|
|
|
# create an airspeed sensor error by freezing to the
|
|
|
|
# current airspeed then changing the airspeed demand
|
|
|
|
# to a higher value and waiting for the TECS speed
|
|
|
|
# loop to diverge
|
|
|
|
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
|
|
|
|
self.set_parameter("SIM_ARSPD_FAIL", m.airspeed)
|
2020-09-10 16:56:56 -03:00
|
|
|
self.run_cmd(
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
|
2023-07-15 09:40:01 -03:00
|
|
|
p1=0, # airspeed
|
|
|
|
p2=30,
|
|
|
|
p3=-1, # throttle / no change
|
|
|
|
p4=0, # absolute values
|
2020-09-10 16:56:56 -03:00
|
|
|
)
|
2021-07-19 02:38:51 -03:00
|
|
|
self.wait_statustext(text="EKF3 lane switch", timeout=30, the_function=fail_speed, check_context=True)
|
2020-07-16 07:17:54 -03:00
|
|
|
if self.lane_switches != [1, 0, 1, 0, 1]:
|
|
|
|
raise NotAchievedException("Expected lane switch 1, got %s" % str(self.lane_switches[-1]))
|
|
|
|
# Cleanup
|
2021-07-19 02:38:51 -03:00
|
|
|
self.set_parameter("SIM_ARSPD_FAIL", old_parameter)
|
2020-07-16 07:17:54 -03:00
|
|
|
self.change_mode('CIRCLE')
|
2020-09-10 16:56:56 -03:00
|
|
|
self.context_pop()
|
|
|
|
self.context_clear_collection("STATUSTEXT")
|
2020-07-16 07:17:54 -03:00
|
|
|
self.wait_heading(0, accuracy=10, timeout=60)
|
|
|
|
self.wait_heading(180, accuracy=10, timeout=60)
|
2021-02-11 22:44:28 -04:00
|
|
|
###################################################################
|
2020-07-16 07:17:54 -03:00
|
|
|
self.progress("GYROSCOPE: Change Y-Axis Offset")
|
2020-09-10 16:56:56 -03:00
|
|
|
self.context_collect("STATUSTEXT")
|
2020-07-16 07:17:54 -03:00
|
|
|
# create a gyroscope error by changing the Y-axis offset
|
|
|
|
old_parameter = self.get_parameter("INS_GYR2OFFS_Y")
|
2021-02-11 22:44:28 -04:00
|
|
|
self.wait_statustext(
|
|
|
|
text="EKF3 lane switch",
|
|
|
|
timeout=30,
|
|
|
|
the_function=self.set_parameter("INS_GYR2OFFS_Y", old_parameter + 1),
|
|
|
|
check_context=True)
|
2020-07-16 07:17:54 -03:00
|
|
|
if self.lane_switches != [1, 0, 1, 0, 1, 0]:
|
|
|
|
raise NotAchievedException("Expected lane switch 0, got %s" % str(self.lane_switches[-1]))
|
|
|
|
# Cleanup
|
|
|
|
self.set_parameter("INS_GYR2OFFS_Y", old_parameter)
|
2020-09-10 16:56:56 -03:00
|
|
|
self.context_clear_collection("STATUSTEXT")
|
2021-02-11 22:44:28 -04:00
|
|
|
###################################################################
|
2020-07-16 07:17:54 -03:00
|
|
|
|
2022-03-08 17:15:15 -04:00
|
|
|
self.disarm_vehicle(force=True)
|
2021-02-11 22:44:28 -04:00
|
|
|
|
2020-07-16 07:17:54 -03:00
|
|
|
except Exception as e:
|
2021-02-12 22:38:42 -04:00
|
|
|
self.print_exception_caught(e)
|
2020-07-16 07:17:54 -03:00
|
|
|
ex = e
|
|
|
|
|
2020-09-08 19:38:25 -03:00
|
|
|
self.remove_message_hook(statustext_hook)
|
|
|
|
|
2020-07-16 07:17:54 -03:00
|
|
|
self.context_pop()
|
2021-11-23 20:53:47 -04:00
|
|
|
|
|
|
|
# some parameters need reboot to take effect
|
|
|
|
self.reboot_sitl()
|
|
|
|
|
2020-07-16 07:17:54 -03:00
|
|
|
if ex is not None:
|
|
|
|
raise ex
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def FenceAltCeilFloor(self):
|
|
|
|
'''Tests the fence ceiling and floor'''
|
2020-12-18 05:14:42 -04:00
|
|
|
fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"FENCE_TYPE": 9, # Set fence type to max and min alt
|
|
|
|
"FENCE_ACTION": 0, # Set action to report
|
|
|
|
"FENCE_ALT_MAX": 200,
|
|
|
|
"FENCE_ALT_MIN": 100,
|
|
|
|
})
|
2020-09-08 03:58:23 -03:00
|
|
|
|
2020-12-18 05:14:42 -04:00
|
|
|
# Grab Home Position
|
|
|
|
self.mav.recv_match(type='HOME_POSITION', blocking=True)
|
|
|
|
self.homeloc = self.mav.location()
|
|
|
|
|
|
|
|
cruise_alt = 150
|
|
|
|
self.takeoff(cruise_alt)
|
|
|
|
|
|
|
|
self.do_fence_enable()
|
|
|
|
|
|
|
|
self.progress("Fly above ceiling and check for breach")
|
|
|
|
self.change_altitude(self.homeloc.alt + cruise_alt + 80)
|
|
|
|
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
|
2021-01-07 19:27:27 -04:00
|
|
|
self.progress("Got (%s)" % str(m))
|
2020-12-18 05:14:42 -04:00
|
|
|
if ((m.onboard_control_sensors_health & fence_bit)):
|
|
|
|
raise NotAchievedException("Fence Ceiling did not breach")
|
|
|
|
|
|
|
|
self.progress("Return to cruise alt and check for breach clear")
|
|
|
|
self.change_altitude(self.homeloc.alt + cruise_alt)
|
|
|
|
|
|
|
|
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
|
2021-01-07 19:27:27 -04:00
|
|
|
self.progress("Got (%s)" % str(m))
|
2020-12-18 05:14:42 -04:00
|
|
|
if (not (m.onboard_control_sensors_health & fence_bit)):
|
|
|
|
raise NotAchievedException("Fence breach did not clear")
|
|
|
|
|
|
|
|
self.progress("Fly below floor and check for breach")
|
|
|
|
self.change_altitude(self.homeloc.alt + cruise_alt - 80)
|
|
|
|
|
|
|
|
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
|
2021-01-07 19:27:27 -04:00
|
|
|
self.progress("Got (%s)" % str(m))
|
2020-12-18 05:14:42 -04:00
|
|
|
if ((m.onboard_control_sensors_health & fence_bit)):
|
|
|
|
raise NotAchievedException("Fence Floor did not breach")
|
|
|
|
|
|
|
|
self.do_fence_disable()
|
2021-02-18 01:49:25 -04:00
|
|
|
|
2020-12-18 05:14:42 -04:00
|
|
|
self.fly_home_land_and_disarm(timeout=150)
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def FenceBreachedChangeMode(self):
|
|
|
|
'''Tests manual mode change after fence breach, as set with FENCE_OPTIONS'''
|
2021-03-03 22:22:49 -04:00
|
|
|
""" Attempts to change mode while a fence is breached.
|
2022-08-12 17:04:46 -03:00
|
|
|
mode should change should fail if fence option bit is set"""
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"FENCE_ACTION": 1,
|
|
|
|
"FENCE_TYPE": 4,
|
|
|
|
})
|
2021-03-03 22:22:49 -04:00
|
|
|
home_loc = self.mav.location()
|
|
|
|
locs = [
|
|
|
|
mavutil.location(home_loc.lat - 0.001, home_loc.lng - 0.001, 0, 0),
|
|
|
|
mavutil.location(home_loc.lat - 0.001, home_loc.lng + 0.001, 0, 0),
|
|
|
|
mavutil.location(home_loc.lat + 0.001, home_loc.lng + 0.001, 0, 0),
|
|
|
|
mavutil.location(home_loc.lat + 0.001, home_loc.lng - 0.001, 0, 0),
|
|
|
|
]
|
|
|
|
self.upload_fences_from_locations(
|
|
|
|
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,
|
|
|
|
[
|
|
|
|
locs
|
|
|
|
]
|
|
|
|
)
|
|
|
|
self.delay_sim_time(1)
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.takeoff(alt=50)
|
|
|
|
self.change_mode("CRUISE")
|
2022-08-12 17:04:46 -03:00
|
|
|
self.wait_distance(250, accuracy=15)
|
2021-03-03 22:22:49 -04:00
|
|
|
|
|
|
|
self.progress("Enable fence and initiate fence action")
|
|
|
|
self.do_fence_enable()
|
|
|
|
self.assert_fence_enabled()
|
|
|
|
self.wait_mode("RTL") # We should RTL because of fence breach
|
|
|
|
|
|
|
|
self.progress("User mode change to cruise should retrigger fence action")
|
2022-08-12 17:04:46 -03:00
|
|
|
try:
|
|
|
|
# mode change should time out, 'WaitModeTimeout' exception is the desired resut
|
|
|
|
# cant wait too long or the vehicle will be inside fence and allow the mode change
|
|
|
|
self.change_mode("CRUISE", timeout=10)
|
|
|
|
raise NotAchievedException("Should not change mode in fence breach")
|
|
|
|
except WaitModeTimeout:
|
|
|
|
pass
|
|
|
|
except Exception as e:
|
|
|
|
raise e
|
|
|
|
|
|
|
|
# enable mode change
|
|
|
|
self.set_parameter("FENCE_OPTIONS", 0)
|
|
|
|
self.progress("Check user mode change to LOITER is allowed")
|
|
|
|
self.change_mode("LOITER")
|
|
|
|
|
|
|
|
# Fly for 20 seconds and make sure still in LOITER mode
|
|
|
|
self.delay_sim_time(20)
|
|
|
|
if not self.mode_is("LOITER"):
|
|
|
|
raise NotAchievedException("Fence should not re-trigger")
|
|
|
|
|
|
|
|
# reset options parameter
|
|
|
|
self.set_parameter("FENCE_OPTIONS", 1)
|
2021-03-03 22:22:49 -04:00
|
|
|
|
|
|
|
self.progress("Test complete, disable fence and come home")
|
|
|
|
self.do_fence_disable()
|
|
|
|
self.fly_home_land_and_disarm()
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def FenceNoFenceReturnPoint(self):
|
|
|
|
'''Tests calculated return point during fence breach when no fence return point present'''
|
2021-03-03 22:22:49 -04:00
|
|
|
""" Attempts to change mode while a fence is breached.
|
|
|
|
This should revert to the mode specified by the fence action. """
|
|
|
|
want_radius = 100 # Fence Return Radius
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"FENCE_ACTION": 6,
|
|
|
|
"FENCE_TYPE": 4,
|
|
|
|
"RTL_RADIUS": want_radius,
|
|
|
|
"NAVL1_LIM_BANK": 60,
|
|
|
|
})
|
2021-03-03 22:22:49 -04:00
|
|
|
home_loc = self.mav.location()
|
|
|
|
locs = [
|
|
|
|
mavutil.location(home_loc.lat - 0.003, home_loc.lng - 0.001, 0, 0),
|
|
|
|
mavutil.location(home_loc.lat - 0.003, home_loc.lng + 0.003, 0, 0),
|
|
|
|
mavutil.location(home_loc.lat + 0.001, home_loc.lng + 0.003, 0, 0),
|
|
|
|
mavutil.location(home_loc.lat + 0.001, home_loc.lng - 0.001, 0, 0),
|
|
|
|
]
|
|
|
|
self.upload_fences_from_locations(
|
|
|
|
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,
|
|
|
|
[
|
|
|
|
locs
|
|
|
|
]
|
|
|
|
)
|
|
|
|
self.delay_sim_time(1)
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.takeoff(alt=50)
|
|
|
|
self.change_mode("CRUISE")
|
|
|
|
self.wait_distance(150, accuracy=20)
|
|
|
|
|
|
|
|
self.progress("Enable fence and initiate fence action")
|
|
|
|
self.do_fence_enable()
|
|
|
|
self.assert_fence_enabled()
|
2021-04-29 06:57:02 -03:00
|
|
|
self.wait_mode("GUIDED", timeout=120) # We should RTL because of fence breach
|
|
|
|
self.delay_sim_time(60)
|
2021-03-03 22:22:49 -04:00
|
|
|
|
|
|
|
items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
|
|
|
|
if len(items) != 4:
|
|
|
|
raise NotAchievedException("Unexpected fencepoint count (want=%u got=%u)" % (4, len(items)))
|
|
|
|
|
|
|
|
# Check there are no fence return points specified still
|
|
|
|
for fence_loc in items:
|
|
|
|
if fence_loc.command == mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT:
|
|
|
|
raise NotAchievedException(
|
|
|
|
"Unexpected fence return point found (%u) got %u" %
|
|
|
|
(fence_loc.command,
|
|
|
|
mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT))
|
|
|
|
|
|
|
|
# Work out the approximate return point when no fence return point present
|
|
|
|
# Logic taken from AC_PolyFence_loader.cpp
|
|
|
|
min_loc = self.mav.location()
|
|
|
|
max_loc = self.mav.location()
|
|
|
|
for new_loc in locs:
|
|
|
|
if new_loc.lat < min_loc.lat:
|
|
|
|
min_loc.lat = new_loc.lat
|
|
|
|
if new_loc.lng < min_loc.lng:
|
|
|
|
min_loc.lng = new_loc.lng
|
|
|
|
if new_loc.lat > max_loc.lat:
|
|
|
|
max_loc.lat = new_loc.lat
|
|
|
|
if new_loc.lng > max_loc.lng:
|
|
|
|
max_loc.lng = new_loc.lng
|
|
|
|
|
|
|
|
# Generate the return location based on min and max locs
|
|
|
|
ret_lat = (min_loc.lat + max_loc.lat) / 2
|
|
|
|
ret_lng = (min_loc.lng + max_loc.lng) / 2
|
|
|
|
ret_loc = mavutil.location(ret_lat, ret_lng, 0, 0)
|
|
|
|
self.progress("Return loc: (%s)" % str(ret_loc))
|
|
|
|
|
|
|
|
# Wait for guided return to vehicle calculated fence return location
|
2021-02-23 12:32:06 -04:00
|
|
|
self.wait_distance_to_location(ret_loc, 90, 110)
|
|
|
|
self.wait_circling_point_with_radius(ret_loc, 92)
|
2021-03-03 22:22:49 -04:00
|
|
|
|
|
|
|
self.progress("Test complete, disable fence and come home")
|
|
|
|
self.do_fence_disable()
|
|
|
|
self.fly_home_land_and_disarm()
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def FenceNoFenceReturnPointInclusion(self):
|
|
|
|
'''Tests using home as fence return point when none is present, and no inclusion fence is uploaded'''
|
2021-04-29 06:57:02 -03:00
|
|
|
""" Test result when a breach occurs and No fence return point is present and
|
|
|
|
no inclusion fence is present and exclusion fence is present """
|
|
|
|
want_radius = 100 # Fence Return Radius
|
|
|
|
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"FENCE_ACTION": 6,
|
|
|
|
"FENCE_TYPE": 2,
|
|
|
|
"FENCE_RADIUS": 300,
|
|
|
|
"RTL_RADIUS": want_radius,
|
|
|
|
"NAVL1_LIM_BANK": 60,
|
|
|
|
})
|
2021-04-29 06:57:02 -03:00
|
|
|
|
2021-05-03 23:08:40 -03:00
|
|
|
self.clear_fence()
|
|
|
|
|
2021-04-29 06:57:02 -03:00
|
|
|
self.delay_sim_time(1)
|
|
|
|
self.wait_ready_to_arm()
|
2021-05-03 23:08:40 -03:00
|
|
|
home_loc = self.mav.location()
|
2021-04-29 06:57:02 -03:00
|
|
|
self.takeoff(alt=50)
|
|
|
|
self.change_mode("CRUISE")
|
|
|
|
self.wait_distance(150, accuracy=20)
|
|
|
|
|
|
|
|
self.progress("Enable fence and initiate fence action")
|
|
|
|
self.do_fence_enable()
|
|
|
|
self.assert_fence_enabled()
|
|
|
|
self.wait_mode("GUIDED") # We should RTL because of fence breach
|
|
|
|
self.delay_sim_time(30)
|
|
|
|
|
|
|
|
items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
|
2021-05-03 23:08:40 -03:00
|
|
|
if len(items) != 0:
|
|
|
|
raise NotAchievedException("Unexpected fencepoint count (want=%u got=%u)" % (0, len(items)))
|
2021-04-29 06:57:02 -03:00
|
|
|
|
|
|
|
# Check there are no fence return points specified still
|
|
|
|
for fence_loc in items:
|
|
|
|
if fence_loc.command == mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT:
|
|
|
|
raise NotAchievedException(
|
|
|
|
"Unexpected fence return point found (%u) got %u" %
|
|
|
|
(fence_loc.command,
|
|
|
|
mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT))
|
|
|
|
|
|
|
|
# Wait for guided return to vehicle calculated fence return location
|
|
|
|
self.wait_distance_to_location(home_loc, 90, 110)
|
|
|
|
self.wait_circling_point_with_radius(home_loc, 92)
|
|
|
|
|
|
|
|
self.progress("Test complete, disable fence and come home")
|
|
|
|
self.do_fence_disable()
|
|
|
|
self.fly_home_land_and_disarm()
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def FenceDisableUnderAction(self):
|
|
|
|
'''Tests Disabling fence while undergoing action caused by breach'''
|
2021-02-16 04:32:54 -04:00
|
|
|
""" Fence breach will cause the vehicle to enter guided mode.
|
2021-02-15 23:20:56 -04:00
|
|
|
Upon breach clear, check the vehicle is in the expected mode"""
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"FENCE_ALT_MIN": 50, # Sets the fence floor
|
|
|
|
"FENCE_TYPE": 8, # Only use fence floor for breaches
|
|
|
|
})
|
2021-02-15 23:20:56 -04:00
|
|
|
self.wait_ready_to_arm()
|
|
|
|
|
|
|
|
def attempt_fence_breached_disable(start_mode, end_mode, expected_mode, action):
|
|
|
|
self.set_parameter("FENCE_ACTION", action) # Set Fence Action to Guided
|
|
|
|
self.change_mode(start_mode)
|
|
|
|
self.arm_vehicle()
|
|
|
|
self.do_fence_enable()
|
|
|
|
self.assert_fence_enabled()
|
|
|
|
self.wait_mode(expected_mode)
|
|
|
|
self.do_fence_disable()
|
|
|
|
self.assert_fence_disabled()
|
|
|
|
self.wait_mode(end_mode)
|
|
|
|
self.disarm_vehicle(force=True)
|
|
|
|
|
|
|
|
attempt_fence_breached_disable(start_mode="FBWA", end_mode="RTL", expected_mode="RTL", action=1)
|
|
|
|
attempt_fence_breached_disable(start_mode="FBWA", end_mode="FBWA", expected_mode="GUIDED", action=6)
|
2021-03-02 23:10:47 -04:00
|
|
|
attempt_fence_breached_disable(start_mode="FBWA", end_mode="FBWA", expected_mode="GUIDED", action=7)
|
2020-12-18 05:14:42 -04:00
|
|
|
|
2023-10-03 04:04:47 -03:00
|
|
|
def _MAV_CMD_DO_AUX_FUNCTION(self, run_cmd):
|
2022-09-09 22:24:28 -03:00
|
|
|
'''Test triggering Auxiliary Functions via mavlink'''
|
2021-02-17 21:00:26 -04:00
|
|
|
self.context_collect('STATUSTEXT')
|
2023-10-03 04:04:47 -03:00
|
|
|
self.run_auxfunc(64, 2, run_cmd=run_cmd) # 64 == reverse throttle
|
2021-02-17 21:00:26 -04:00
|
|
|
self.wait_statustext("RevThrottle: ENABLE", check_context=True)
|
2023-10-03 04:04:47 -03:00
|
|
|
self.run_auxfunc(64, 0, run_cmd=run_cmd)
|
2021-02-17 21:00:26 -04:00
|
|
|
self.wait_statustext("RevThrottle: DISABLE", check_context=True)
|
2023-10-03 04:04:47 -03:00
|
|
|
self.run_auxfunc(65, 2, run_cmd=run_cmd) # 65 == GPS_DISABLE
|
2021-02-17 21:00:26 -04:00
|
|
|
|
2021-02-24 05:49:12 -04:00
|
|
|
self.start_subtest("Bad auxfunc")
|
|
|
|
self.run_auxfunc(
|
|
|
|
65231,
|
|
|
|
2,
|
2023-10-03 04:04:47 -03:00
|
|
|
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
|
|
|
|
run_cmd=run_cmd,
|
2021-02-24 05:49:12 -04:00
|
|
|
)
|
|
|
|
|
|
|
|
self.start_subtest("Bad switchpos")
|
|
|
|
self.run_auxfunc(
|
|
|
|
62,
|
|
|
|
17,
|
2023-10-03 04:04:47 -03:00
|
|
|
want_result=mavutil.mavlink.MAV_RESULT_DENIED,
|
|
|
|
run_cmd=run_cmd,
|
2021-02-24 05:49:12 -04:00
|
|
|
)
|
|
|
|
|
2023-10-03 04:04:47 -03:00
|
|
|
def MAV_CMD_DO_AUX_FUNCTION(self):
|
|
|
|
'''Test triggering Auxiliary Functions via mavlink'''
|
|
|
|
self._MAV_CMD_DO_AUX_FUNCTION(run_cmd=self.run_cmd)
|
|
|
|
self._MAV_CMD_DO_AUX_FUNCTION(run_cmd=self.run_cmd_int)
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def FlyEachFrame(self):
|
|
|
|
'''Fly each supported internal frame'''
|
2021-06-20 22:33:12 -03:00
|
|
|
vinfo = vehicleinfo.VehicleInfo()
|
|
|
|
vinfo_options = vinfo.options[self.vehicleinfo_key()]
|
|
|
|
known_broken_frames = {
|
|
|
|
"firefly": "falls out of sky after transition",
|
|
|
|
"plane-tailsitter": "does not take off; immediately emits 'AP: Transition VTOL done' while on ground",
|
|
|
|
"quadplane-cl84": "falls out of sky instead of transitioning",
|
|
|
|
"quadplane-tilttri": "falls out of sky instead of transitioning",
|
|
|
|
"quadplane-tilttrivec": "loses attitude control and crashes",
|
2022-10-05 21:39:24 -03:00
|
|
|
"plane-ice" : "needs ICE control channel for ignition",
|
|
|
|
"quadplane-ice" : "needs ICE control channel for ignition",
|
2023-08-21 00:16:12 -03:00
|
|
|
"quadplane-can" : "needs CAN periph",
|
2021-06-20 22:33:12 -03:00
|
|
|
}
|
|
|
|
for frame in sorted(vinfo_options["frames"].keys()):
|
|
|
|
self.start_subtest("Testing frame (%s)" % str(frame))
|
|
|
|
if frame in known_broken_frames:
|
|
|
|
self.progress("Actually, no I'm not - it is known-broken (%s)" %
|
|
|
|
(known_broken_frames[frame]))
|
|
|
|
continue
|
|
|
|
frame_bits = vinfo_options["frames"][frame]
|
|
|
|
print("frame_bits: %s" % str(frame_bits))
|
|
|
|
if frame_bits.get("external", False):
|
|
|
|
self.progress("Actually, no I'm not - it is an external simulation")
|
|
|
|
continue
|
|
|
|
model = frame_bits.get("model", frame)
|
|
|
|
# the model string for Callisto has crap in it.... we
|
|
|
|
# should really have another entry in the vehicleinfo data
|
|
|
|
# to carry the path to the JSON.
|
|
|
|
actual_model = model.split(":")[0]
|
|
|
|
defaults = self.model_defaults_filepath(actual_model)
|
2023-08-31 18:45:12 -03:00
|
|
|
if not isinstance(defaults, list):
|
2021-06-20 22:33:12 -03:00
|
|
|
defaults = [defaults]
|
|
|
|
self.customise_SITL_commandline(
|
|
|
|
["--defaults", ','.join(defaults), ],
|
|
|
|
model=model,
|
|
|
|
wipe=True,
|
|
|
|
)
|
|
|
|
mission_file = "basic.txt"
|
|
|
|
quadplane = self.get_parameter('Q_ENABLE')
|
|
|
|
if quadplane:
|
|
|
|
mission_file = "basic-quadplane.txt"
|
2021-10-24 21:36:05 -03:00
|
|
|
tailsitter = self.get_parameter('Q_TAILSIT_ENABLE')
|
|
|
|
if tailsitter:
|
|
|
|
# tailsitter needs extra re-boot to pick up the rotated AHRS view
|
|
|
|
self.reboot_sitl()
|
2021-06-20 22:33:12 -03:00
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
2021-04-25 19:21:53 -03:00
|
|
|
self.fly_mission(mission_file, strict=False, quadplane=quadplane, mission_timeout=400.0)
|
2021-06-20 22:33:12 -03:00
|
|
|
self.wait_disarmed()
|
|
|
|
|
2021-06-17 03:03:36 -03:00
|
|
|
def RCDisableAirspeedUse(self):
|
2022-09-09 22:24:28 -03:00
|
|
|
'''Test RC DisableAirspeedUse option'''
|
2021-06-17 03:03:36 -03:00
|
|
|
self.set_parameter("RC9_OPTION", 106)
|
|
|
|
self.delay_sim_time(5)
|
|
|
|
self.set_rc(9, 1000)
|
|
|
|
self.wait_sensor_state(
|
|
|
|
mavutil.mavlink.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE,
|
|
|
|
True,
|
|
|
|
True,
|
|
|
|
True)
|
|
|
|
self.set_rc(9, 2000)
|
|
|
|
self.wait_sensor_state(
|
|
|
|
mavutil.mavlink.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE,
|
|
|
|
True,
|
|
|
|
False,
|
|
|
|
True)
|
|
|
|
self.set_rc(9, 1000)
|
|
|
|
self.wait_sensor_state(
|
|
|
|
mavutil.mavlink.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE,
|
|
|
|
True,
|
|
|
|
True,
|
|
|
|
True)
|
|
|
|
|
2021-07-31 00:55:49 -03:00
|
|
|
def WatchdogHome(self):
|
2022-09-09 22:24:28 -03:00
|
|
|
'''Ensure home is restored after watchdog reset'''
|
2021-07-31 00:55:49 -03:00
|
|
|
if self.gdb:
|
|
|
|
# we end up signalling the wrong process. I think.
|
|
|
|
# Probably need to have a "sitl_pid()" method to get the
|
|
|
|
# ardupilot process's PID.
|
|
|
|
self.progress("######## Skipping WatchdogHome test under GDB")
|
|
|
|
return
|
|
|
|
|
|
|
|
ex = None
|
|
|
|
try:
|
|
|
|
self.progress("Enabling watchdog")
|
|
|
|
self.set_parameter("BRD_OPTIONS", 1 << 0)
|
|
|
|
self.reboot_sitl()
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.progress("Explicitly setting home to a known location")
|
|
|
|
orig_home = self.poll_home_position()
|
|
|
|
new_home = orig_home
|
|
|
|
new_home.latitude = new_home.latitude + 1000
|
|
|
|
new_home.longitude = new_home.longitude + 2000
|
|
|
|
new_home.altitude = new_home.altitude + 300000 # 300 metres
|
|
|
|
self.run_cmd_int(
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
|
2023-07-15 09:40:01 -03:00
|
|
|
p5=new_home.latitude,
|
|
|
|
p6=new_home.longitude,
|
|
|
|
p7=new_home.altitude/1000.0, # mm => m
|
2021-07-31 00:55:49 -03:00
|
|
|
)
|
|
|
|
old_bootcount = self.get_parameter('STAT_BOOTCNT')
|
|
|
|
self.progress("Forcing watchdog reset")
|
|
|
|
os.kill(self.sitl.pid, signal.SIGALRM)
|
|
|
|
self.detect_and_handle_reboot(old_bootcount)
|
|
|
|
self.wait_statustext("WDG:")
|
|
|
|
self.wait_statustext("IMU1 is using GPS") # won't be come armable
|
|
|
|
self.progress("Verifying home position")
|
|
|
|
post_reboot_home = self.poll_home_position()
|
|
|
|
delta = self.get_distance_int(new_home, post_reboot_home)
|
|
|
|
max_delta = 1
|
|
|
|
if delta > max_delta:
|
|
|
|
raise NotAchievedException(
|
|
|
|
"New home not where it should be (dist=%f) (want=%s) (got=%s)" %
|
|
|
|
(delta, str(new_home), str(post_reboot_home)))
|
|
|
|
except Exception as e:
|
|
|
|
self.print_exception_caught(e)
|
|
|
|
ex = e
|
|
|
|
|
|
|
|
self.reboot_sitl()
|
|
|
|
|
|
|
|
if ex is not None:
|
|
|
|
raise ex
|
|
|
|
|
2021-10-09 21:07:48 -03:00
|
|
|
def AUTOTUNE(self):
|
2022-09-09 22:24:28 -03:00
|
|
|
'''Test AutoTune mode'''
|
2021-10-09 21:07:48 -03:00
|
|
|
self.takeoff(100)
|
|
|
|
self.change_mode('AUTOTUNE')
|
|
|
|
self.context_collect('STATUSTEXT')
|
|
|
|
tstart = self.get_sim_time()
|
|
|
|
axis = "Roll"
|
|
|
|
rc_value = 1000
|
|
|
|
while True:
|
|
|
|
timeout = 600
|
|
|
|
if self.get_sim_time() - tstart > timeout:
|
|
|
|
raise NotAchievedException("Did not complete within %u seconds" % timeout)
|
|
|
|
try:
|
|
|
|
m = self.wait_statustext("%s: Finished" % axis, check_context=True, timeout=0.1)
|
|
|
|
self.progress("Got %s" % str(m))
|
|
|
|
if axis == "Roll":
|
|
|
|
axis = "Pitch"
|
|
|
|
elif axis == "Pitch":
|
|
|
|
break
|
|
|
|
else:
|
|
|
|
raise ValueError("Bug: %s" % axis)
|
|
|
|
except AutoTestTimeoutException:
|
|
|
|
pass
|
|
|
|
self.delay_sim_time(1)
|
|
|
|
|
|
|
|
if rc_value == 1000:
|
|
|
|
rc_value = 2000
|
|
|
|
elif rc_value == 2000:
|
|
|
|
rc_value = 1000
|
|
|
|
elif rc_value == 1000:
|
|
|
|
rc_value = 2000
|
|
|
|
else:
|
|
|
|
raise ValueError("Bug")
|
|
|
|
|
|
|
|
if axis == "Roll":
|
|
|
|
self.set_rc(1, rc_value)
|
|
|
|
self.set_rc(2, 1500)
|
|
|
|
elif axis == "Pitch":
|
|
|
|
self.set_rc(1, 1500)
|
|
|
|
self.set_rc(2, rc_value)
|
|
|
|
else:
|
|
|
|
raise ValueError("Bug")
|
|
|
|
|
|
|
|
tdelta = self.get_sim_time() - tstart
|
|
|
|
self.progress("Finished in %0.1f seconds" % (tdelta,))
|
|
|
|
|
|
|
|
self.set_rc(1, 1500)
|
|
|
|
self.set_rc(2, 1500)
|
|
|
|
|
|
|
|
self.change_mode('FBWA')
|
|
|
|
self.fly_home_land_and_disarm(timeout=tdelta+240)
|
|
|
|
|
2023-07-19 10:10:03 -03:00
|
|
|
def AutotuneFiltering(self):
|
|
|
|
'''Test AutoTune mode with filter updates disabled'''
|
|
|
|
self.set_parameters({
|
|
|
|
"AUTOTUNE_OPTIONS": 3,
|
|
|
|
# some filtering is required for autotune to complete
|
|
|
|
"RLL_RATE_FLTD": 10,
|
|
|
|
"PTCH_RATE_FLTD": 10,
|
|
|
|
"RLL_RATE_FLTT": 20,
|
|
|
|
"PTCH_RATE_FLTT": 20,
|
|
|
|
})
|
|
|
|
self.AUTOTUNE()
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def LandingDrift(self):
|
|
|
|
'''Circuit with baro drift'''
|
2020-12-01 03:14:34 -04:00
|
|
|
self.customise_SITL_commandline([], wipe=True)
|
|
|
|
|
2021-11-10 08:41:16 -04:00
|
|
|
self.set_analog_rangefinder_parameters()
|
|
|
|
|
2020-12-01 03:14:34 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"SIM_BARO_DRIFT": -0.02,
|
|
|
|
"SIM_TERRAIN": 0,
|
|
|
|
"RNGFND_LANDING": 1,
|
|
|
|
"LAND_SLOPE_RCALC": 2,
|
2021-11-10 08:41:16 -04:00
|
|
|
"LAND_ABORT_DEG": 1,
|
2020-12-01 03:14:34 -04:00
|
|
|
})
|
|
|
|
|
|
|
|
self.reboot_sitl()
|
|
|
|
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
|
|
|
|
2022-01-30 15:51:39 -04:00
|
|
|
# Load and start mission
|
|
|
|
self.load_mission("ap-circuit.txt", strict=True)
|
|
|
|
self.set_current_waypoint(1, check_afterwards=True)
|
|
|
|
self.change_mode('AUTO')
|
|
|
|
self.wait_current_waypoint(1, timeout=5)
|
|
|
|
self.wait_groundspeed(0, 10, timeout=5)
|
|
|
|
|
|
|
|
# Wait for landing waypoint
|
|
|
|
self.wait_current_waypoint(9, timeout=1200)
|
|
|
|
|
|
|
|
# Wait for landing restart
|
|
|
|
self.wait_current_waypoint(5, timeout=60)
|
|
|
|
|
|
|
|
# Wait for landing waypoint (second attempt)
|
|
|
|
self.wait_current_waypoint(9, timeout=1200)
|
|
|
|
|
2022-02-08 18:09:35 -04:00
|
|
|
self.wait_disarmed(timeout=180)
|
2020-12-01 03:14:34 -04:00
|
|
|
|
2021-10-05 06:16:49 -03:00
|
|
|
def DCMFallback(self):
|
2022-09-09 22:24:28 -03:00
|
|
|
'''Really annoy the EKF and force fallback'''
|
2021-10-17 08:51:15 -03:00
|
|
|
self.reboot_sitl()
|
|
|
|
self.delay_sim_time(30)
|
2021-10-05 06:16:49 -03:00
|
|
|
|
|
|
|
self.takeoff(50)
|
2021-10-17 08:51:15 -03:00
|
|
|
self.change_mode('CIRCLE')
|
2023-02-05 20:39:50 -04:00
|
|
|
self.context_push()
|
2021-10-05 06:16:49 -03:00
|
|
|
self.context_collect('STATUSTEXT')
|
2021-11-23 21:22:21 -04:00
|
|
|
self.set_parameters({
|
|
|
|
"EK3_POS_I_GATE": 0,
|
|
|
|
"SIM_GPS_HZ": 1,
|
2022-01-05 23:28:55 -04:00
|
|
|
"SIM_GPS_LAG_MS": 1000,
|
2021-11-23 21:22:21 -04:00
|
|
|
})
|
2021-10-17 08:51:15 -03:00
|
|
|
self.wait_statustext("DCM Active", check_context=True, timeout=60)
|
2021-10-05 06:16:49 -03:00
|
|
|
self.wait_statustext("EKF3 Active", check_context=True)
|
|
|
|
self.wait_statustext("DCM Active", check_context=True)
|
|
|
|
self.wait_statustext("EKF3 Active", check_context=True)
|
|
|
|
self.wait_statustext("DCM Active", check_context=True)
|
|
|
|
self.wait_statustext("EKF3 Active", check_context=True)
|
|
|
|
self.context_stop_collecting('STATUSTEXT')
|
|
|
|
|
|
|
|
self.fly_home_land_and_disarm()
|
2023-02-05 20:39:50 -04:00
|
|
|
self.context_pop()
|
|
|
|
self.reboot_sitl()
|
2021-10-05 06:16:49 -03:00
|
|
|
|
2021-09-26 03:37:04 -03:00
|
|
|
def ForcedDCM(self):
|
2022-09-09 22:24:28 -03:00
|
|
|
'''Switch to DCM mid-flight'''
|
2021-09-26 03:37:04 -03:00
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
|
|
|
|
|
|
|
self.takeoff(50)
|
|
|
|
self.context_collect('STATUSTEXT')
|
|
|
|
self.set_parameter("AHRS_EKF_TYPE", 0)
|
|
|
|
self.wait_statustext("DCM Active", check_context=True)
|
|
|
|
self.context_stop_collecting('STATUSTEXT')
|
|
|
|
|
|
|
|
self.fly_home_land_and_disarm()
|
|
|
|
|
2021-10-10 22:06:48 -03:00
|
|
|
def MegaSquirt(self):
|
2022-09-09 22:24:28 -03:00
|
|
|
'''Test MegaSquirt EFI'''
|
2021-10-10 22:06:48 -03:00
|
|
|
self.assert_not_receiving_message('EFI_STATUS')
|
|
|
|
self.set_parameters({
|
|
|
|
'SIM_EFI_TYPE': 1,
|
|
|
|
'EFI_TYPE': 1,
|
|
|
|
'SERIAL5_PROTOCOL': 24,
|
|
|
|
})
|
|
|
|
self.customise_SITL_commandline(["--uartF=sim:megasquirt"])
|
|
|
|
self.delay_sim_time(5)
|
|
|
|
m = self.assert_receive_message('EFI_STATUS')
|
|
|
|
mavutil.dump_message_verbose(sys.stdout, m)
|
|
|
|
if m.throttle_out != 0:
|
|
|
|
raise NotAchievedException("Expected zero throttle")
|
|
|
|
if m.health != 1:
|
|
|
|
raise NotAchievedException("Not healthy")
|
|
|
|
if m.intake_manifold_temperature < 20:
|
|
|
|
raise NotAchievedException("Bad intake manifold temperature")
|
|
|
|
|
2022-09-09 22:24:28 -03:00
|
|
|
def GlideSlopeThresh(self):
|
|
|
|
'''Test rebuild glide slope if above and climbing'''
|
2021-12-15 06:36:41 -04:00
|
|
|
|
|
|
|
# Test that GLIDE_SLOPE_THRESHOLD correctly controls re-planning glide slope
|
|
|
|
# in the scenario that aircraft is above planned slope and slope is positive (climbing).
|
|
|
|
#
|
|
|
|
#
|
|
|
|
# Behaviour with GLIDE_SLOPE_THRESH = 0 (no slope replanning)
|
|
|
|
# (2).. __(4)
|
|
|
|
# | \..__/
|
|
|
|
# | __/
|
|
|
|
# (3)
|
|
|
|
#
|
|
|
|
# Behaviour with GLIDE_SLOPE_THRESH = 5 (slope replanning when >5m error)
|
|
|
|
# (2)........__(4)
|
|
|
|
# | __/
|
|
|
|
# | __/
|
|
|
|
# (3)
|
|
|
|
# Solid is plan, dots are actual flightpath.
|
|
|
|
|
|
|
|
self.load_mission('rapid-descent-then-climb.txt', strict=False)
|
|
|
|
|
|
|
|
self.set_current_waypoint(1)
|
|
|
|
self.change_mode('AUTO')
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
|
|
|
|
|
|
|
#
|
|
|
|
# Initial run with GLIDE_SLOPE_THR = 5 (default).
|
|
|
|
#
|
|
|
|
self.set_parameter("GLIDE_SLOPE_THR", 5)
|
|
|
|
|
|
|
|
# Wait for waypoint commanding rapid descent, followed by climb.
|
|
|
|
self.wait_current_waypoint(5, timeout=1200)
|
|
|
|
|
|
|
|
# Altitude should not descend significantly below the initial altitude
|
|
|
|
init_altitude = self.get_altitude(relative=True, timeout=2)
|
|
|
|
timeout = 600
|
|
|
|
wpnum = 7
|
|
|
|
tstart = self.get_sim_time()
|
|
|
|
while True:
|
|
|
|
if self.get_sim_time() - tstart > timeout:
|
|
|
|
raise AutoTestTimeoutException("Did not get wanted current waypoint")
|
|
|
|
|
|
|
|
if (self.get_altitude(relative=True, timeout=2) - init_altitude) < -10:
|
|
|
|
raise NotAchievedException("Descended >10m before reaching desired waypoint,\
|
|
|
|
indicating slope was not replanned")
|
|
|
|
|
|
|
|
seq = self.mav.waypoint_current()
|
|
|
|
self.progress("Waiting for wp=%u current=%u" % (wpnum, seq))
|
|
|
|
if seq == wpnum:
|
|
|
|
break
|
|
|
|
|
|
|
|
self.set_current_waypoint(2)
|
|
|
|
|
|
|
|
#
|
|
|
|
# Second run with GLIDE_SLOPE_THR = 0 (no re-plan).
|
|
|
|
#
|
|
|
|
self.set_parameter("GLIDE_SLOPE_THR", 0)
|
|
|
|
|
|
|
|
# Wait for waypoint commanding rapid descent, followed by climb.
|
|
|
|
self.wait_current_waypoint(5, timeout=1200)
|
|
|
|
|
|
|
|
# This time altitude should descend significantly below the initial altitude
|
|
|
|
init_altitude = self.get_altitude(relative=True, timeout=2)
|
|
|
|
timeout = 600
|
|
|
|
wpnum = 7
|
|
|
|
tstart = self.get_sim_time()
|
|
|
|
while True:
|
|
|
|
if self.get_sim_time() - tstart > timeout:
|
|
|
|
raise AutoTestTimeoutException("Did not get wanted altitude")
|
|
|
|
|
|
|
|
seq = self.mav.waypoint_current()
|
|
|
|
self.progress("Waiting for wp=%u current=%u" % (wpnum, seq))
|
|
|
|
if seq == wpnum:
|
|
|
|
raise NotAchievedException("Reached desired waypoint without first decending 10m,\
|
|
|
|
indicating slope was replanned unexpectedly")
|
|
|
|
|
|
|
|
if (self.get_altitude(relative=True, timeout=2) - init_altitude) < -10:
|
|
|
|
break
|
|
|
|
|
|
|
|
# Disarm
|
|
|
|
self.wait_disarmed(timeout=600)
|
|
|
|
|
|
|
|
self.progress("Mission OK")
|
|
|
|
|
2022-05-11 00:40:10 -03:00
|
|
|
def MAV_CMD_NAV_LOITER_TURNS(self, target_system=1, target_component=1):
|
|
|
|
'''test MAV_CMD_NAV_LOITER_TURNS mission item'''
|
2022-08-18 21:19:57 -03:00
|
|
|
alt = 100
|
2022-05-11 00:40:10 -03:00
|
|
|
seq = 0
|
|
|
|
items = []
|
|
|
|
tests = [
|
|
|
|
(self.home_relative_loc_ne(50, -50), 100),
|
|
|
|
(self.home_relative_loc_ne(100, 50), 1005),
|
|
|
|
]
|
|
|
|
# add a home position:
|
|
|
|
items.append(self.mav.mav.mission_item_int_encode(
|
|
|
|
target_system,
|
|
|
|
target_component,
|
|
|
|
seq, # seq
|
|
|
|
mavutil.mavlink.MAV_FRAME_GLOBAL,
|
|
|
|
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
|
|
|
|
0, # current
|
|
|
|
0, # autocontinue
|
|
|
|
0, # p1
|
|
|
|
0, # p2
|
|
|
|
0, # p3
|
|
|
|
0, # p4
|
|
|
|
0, # latitude
|
|
|
|
0, # longitude
|
|
|
|
0, # altitude
|
|
|
|
mavutil.mavlink.MAV_MISSION_TYPE_MISSION))
|
|
|
|
seq += 1
|
|
|
|
|
|
|
|
# add takeoff
|
|
|
|
items.append(self.mav.mav.mission_item_int_encode(
|
|
|
|
target_system,
|
|
|
|
target_component,
|
|
|
|
seq, # seq
|
|
|
|
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
|
|
|
|
mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
|
|
|
|
0, # current
|
|
|
|
0, # autocontinue
|
|
|
|
0, # p1
|
|
|
|
0, # p2
|
|
|
|
0, # p3
|
|
|
|
0, # p4
|
|
|
|
0, # latitude
|
|
|
|
0, # longitude
|
|
|
|
alt, # altitude
|
|
|
|
mavutil.mavlink.MAV_MISSION_TYPE_MISSION))
|
|
|
|
seq += 1
|
|
|
|
|
|
|
|
# add circles
|
|
|
|
for (loc, radius) in tests:
|
|
|
|
items.append(self.mav.mav.mission_item_int_encode(
|
|
|
|
target_system,
|
|
|
|
target_component,
|
|
|
|
seq, # seq
|
|
|
|
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
|
|
|
|
mavutil.mavlink.MAV_CMD_NAV_LOITER_TURNS,
|
|
|
|
0, # current
|
|
|
|
0, # autocontinue
|
|
|
|
3, # p1
|
|
|
|
0, # p2
|
|
|
|
radius, # p3
|
|
|
|
0, # p4
|
|
|
|
int(loc.lat*1e7), # latitude
|
|
|
|
int(loc.lng*1e7), # longitude
|
|
|
|
alt, # altitude
|
|
|
|
mavutil.mavlink.MAV_MISSION_TYPE_MISSION))
|
|
|
|
seq += 1
|
|
|
|
|
|
|
|
# add an RTL
|
|
|
|
items.append(self.mav.mav.mission_item_int_encode(
|
|
|
|
target_system,
|
|
|
|
target_component,
|
|
|
|
seq, # seq
|
|
|
|
mavutil.mavlink.MAV_FRAME_GLOBAL,
|
|
|
|
mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH,
|
|
|
|
0, # current
|
|
|
|
0, # autocontinue
|
|
|
|
0, # p1
|
|
|
|
0, # p2
|
|
|
|
0, # p3
|
|
|
|
0, # p4
|
|
|
|
0, # latitude
|
|
|
|
0, # longitude
|
|
|
|
0, # altitude
|
|
|
|
mavutil.mavlink.MAV_MISSION_TYPE_MISSION))
|
|
|
|
seq += 1
|
|
|
|
|
|
|
|
self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION, items)
|
|
|
|
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
|
|
|
|
ofs = 2
|
|
|
|
self.progress("Checking downloaded mission is as expected")
|
|
|
|
for (loc, radius) in tests:
|
|
|
|
downloaded = downloaded_items[ofs]
|
|
|
|
if radius > 255:
|
|
|
|
# ArduPilot only stores % 10
|
|
|
|
radius = radius - radius % 10
|
|
|
|
if downloaded.param3 != radius:
|
|
|
|
raise NotAchievedException(
|
|
|
|
"Did not get expected radius for item %u; want=%f got=%f" %
|
|
|
|
(ofs, radius, downloaded.param3))
|
|
|
|
ofs += 1
|
|
|
|
|
|
|
|
self.change_mode('AUTO')
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
2022-05-16 19:31:04 -03:00
|
|
|
self.set_parameter("NAVL1_LIM_BANK", 50)
|
2022-05-11 00:40:10 -03:00
|
|
|
|
|
|
|
self.wait_current_waypoint(2)
|
|
|
|
|
|
|
|
for (loc, expected_radius) in tests:
|
|
|
|
self.wait_circling_point_with_radius(
|
|
|
|
loc,
|
2022-05-16 19:31:04 -03:00
|
|
|
expected_radius,
|
|
|
|
epsilon=20.0,
|
2022-05-11 00:40:10 -03:00
|
|
|
timeout=240,
|
|
|
|
)
|
|
|
|
self.set_current_waypoint(self.current_waypoint()+1)
|
|
|
|
|
|
|
|
self.fly_home_land_and_disarm(timeout=180)
|
|
|
|
|
2021-10-19 02:46:41 -03:00
|
|
|
def MidAirDisarmDisallowed(self):
|
2022-09-09 22:24:28 -03:00
|
|
|
'''Ensure mid-air disarm is not possible'''
|
2021-10-19 02:46:41 -03:00
|
|
|
self.takeoff(50)
|
|
|
|
disarmed = False
|
|
|
|
try:
|
|
|
|
self.disarm_vehicle()
|
|
|
|
disarmed = True
|
|
|
|
except ValueError as e:
|
|
|
|
self.progress("Got %s" % repr(e))
|
|
|
|
if "Expected MAV_RESULT_ACCEPTED got MAV_RESULT_FAILED" not in str(e):
|
|
|
|
raise e
|
|
|
|
if disarmed:
|
|
|
|
raise NotAchievedException("Disarmed when we shouldn't have")
|
|
|
|
# should still be able to force-disarm:
|
|
|
|
self.disarm_vehicle(force=True)
|
|
|
|
self.reboot_sitl()
|
|
|
|
|
2022-11-09 19:07:43 -04:00
|
|
|
def AerobaticsScripting(self):
|
|
|
|
'''Fixed Wing Aerobatics'''
|
|
|
|
applet_script = "Aerobatics/FixedWing/plane_aerobatics.lua"
|
2022-11-27 16:32:32 -04:00
|
|
|
airshow = "Aerobatics/FixedWing/Schedules/AirShow.txt"
|
|
|
|
trick72 = "trick72.txt"
|
2022-11-09 19:07:43 -04:00
|
|
|
|
|
|
|
model = "plane-3d"
|
|
|
|
|
|
|
|
self.customise_SITL_commandline(
|
|
|
|
[],
|
|
|
|
model=model,
|
|
|
|
defaults_filepath="",
|
|
|
|
wipe=True)
|
|
|
|
|
|
|
|
self.context_push()
|
|
|
|
self.install_applet_script(applet_script)
|
2022-11-27 16:32:32 -04:00
|
|
|
self.install_applet_script(airshow, install_name=trick72)
|
2022-11-09 19:07:43 -04:00
|
|
|
self.context_collect('STATUSTEXT')
|
|
|
|
self.reboot_sitl()
|
|
|
|
|
|
|
|
self.set_parameter("TRIK_ENABLE", 1)
|
|
|
|
self.set_rc(7, 1000) # disable tricks
|
|
|
|
|
|
|
|
self.scripting_restart()
|
|
|
|
self.wait_text("Enabled 3 aerobatic tricks", check_context=True)
|
|
|
|
self.set_parameters({
|
|
|
|
"TRIK1_ID": 72,
|
|
|
|
"RC7_OPTION" : 300, # activation switch
|
|
|
|
"RC9_OPTION" : 301, # selection switch
|
2022-11-11 19:28:34 -04:00
|
|
|
"SIM_SPEEDUP": 5, # need to give some cycles to lua
|
2022-11-09 19:07:43 -04:00
|
|
|
})
|
|
|
|
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.change_mode("TAKEOFF")
|
|
|
|
self.arm_vehicle()
|
|
|
|
self.wait_altitude(30, 40, timeout=30, relative=True)
|
|
|
|
self.change_mode("CRUISE")
|
|
|
|
|
|
|
|
self.set_rc(9, 1000) # select first trick
|
|
|
|
self.delay_sim_time(1)
|
|
|
|
self.set_rc(7, 1500) # show selected trick
|
|
|
|
|
|
|
|
self.wait_text("Trick 1 selected (SuperAirShow)", check_context=True)
|
|
|
|
self.set_rc(7, 2000) # activate trick
|
|
|
|
self.wait_text("Trick 1 started (SuperAirShow)", check_context=True)
|
|
|
|
|
|
|
|
highest_error = 0
|
|
|
|
while True:
|
|
|
|
m = self.mav.recv_match(type='NAMED_VALUE_FLOAT', blocking=True, timeout=2)
|
|
|
|
if not m:
|
|
|
|
break
|
|
|
|
if m.name != 'PERR':
|
|
|
|
continue
|
|
|
|
highest_error = max(highest_error, m.value)
|
2022-11-11 06:51:29 -04:00
|
|
|
if highest_error > 15:
|
|
|
|
raise NotAchievedException("path error %.1f" % highest_error)
|
2022-11-09 19:07:43 -04:00
|
|
|
|
|
|
|
if highest_error == 0:
|
|
|
|
raise NotAchievedException("path error not reported")
|
|
|
|
self.progress("Finished trick, max error=%.1fm" % highest_error)
|
|
|
|
self.disarm_vehicle(force=True)
|
|
|
|
|
2023-02-15 21:49:16 -04:00
|
|
|
self.remove_installed_script(applet_script)
|
|
|
|
self.remove_installed_script(trick72)
|
2022-11-09 19:07:43 -04:00
|
|
|
messages = self.context_collection('STATUSTEXT')
|
|
|
|
self.context_pop()
|
|
|
|
self.reboot_sitl()
|
|
|
|
|
|
|
|
# check all messages to see if we got all tricks
|
|
|
|
tricks = ["Loop", "HalfReverseCubanEight", "ScaleFigureEight", "Immelmann",
|
|
|
|
"Split-S", "RollingCircle", "HumptyBump", "HalfCubanEight",
|
2022-11-25 20:36:33 -04:00
|
|
|
"BarrelRoll", "CrossBoxTopHat", "TriangularLoop",
|
2022-11-09 19:07:43 -04:00
|
|
|
"Finishing SuperAirShow!"]
|
|
|
|
texts = [m.text for m in messages]
|
|
|
|
for t in tricks:
|
|
|
|
if t in texts:
|
|
|
|
self.progress("Completed trick %s" % t)
|
|
|
|
else:
|
|
|
|
raise NotAchievedException("Missing trick %s" % t)
|
|
|
|
|
2023-02-14 21:11:32 -04:00
|
|
|
def SDCardWPTest(self):
|
|
|
|
'''test BRD_SD_MISSION support'''
|
|
|
|
spiral_script = "mission_spiral.lua"
|
|
|
|
|
|
|
|
self.context_push()
|
|
|
|
self.install_example_script(spiral_script)
|
|
|
|
self.context_collect('STATUSTEXT')
|
|
|
|
self.set_parameters({
|
|
|
|
"BRD_SD_MISSION" : 64,
|
|
|
|
"SCR_ENABLE" : 1,
|
|
|
|
"SCR_VM_I_COUNT" : 1000000
|
|
|
|
})
|
|
|
|
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.reboot_sitl()
|
|
|
|
|
|
|
|
self.wait_text("Loaded spiral mission creator", check_context=True)
|
|
|
|
self.set_parameters({
|
|
|
|
"SCR_USER2": 19, # radius
|
|
|
|
"SCR_USER3": -35.36322, # lat
|
|
|
|
"SCR_USER4": 149.16525, # lon
|
|
|
|
"SCR_USER5": 684.13, # alt
|
|
|
|
})
|
|
|
|
|
|
|
|
count = (65536 // 15) - 1
|
|
|
|
|
|
|
|
self.progress("Creating spiral mission of size %s" % count)
|
|
|
|
self.set_parameter("SCR_USER1", count)
|
|
|
|
|
2023-03-10 21:23:13 -04:00
|
|
|
self.wait_text("Created spiral of size %u" % count, check_context=True)
|
2023-02-14 21:11:32 -04:00
|
|
|
|
|
|
|
self.progress("Checking spiral before reboot")
|
|
|
|
self.set_parameter("SCR_USER6", count)
|
2023-03-10 21:23:13 -04:00
|
|
|
self.wait_text("Compared spiral of size %u OK" % count, check_context=True)
|
2023-02-14 21:11:32 -04:00
|
|
|
self.set_parameter("SCR_USER6", 0)
|
|
|
|
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.reboot_sitl()
|
|
|
|
self.progress("Checking spiral after reboot")
|
|
|
|
self.set_parameter("SCR_USER6", count)
|
2023-03-10 21:23:13 -04:00
|
|
|
self.wait_text("Compared spiral of size %u OK" % count, check_context=True)
|
2023-02-14 21:11:32 -04:00
|
|
|
|
|
|
|
self.remove_installed_script(spiral_script)
|
|
|
|
|
|
|
|
self.context_pop()
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.reboot_sitl()
|
|
|
|
|
2022-11-22 20:04:52 -04:00
|
|
|
def MANUAL_CONTROL(self):
|
|
|
|
'''test MANUAL_CONTROL mavlink message'''
|
|
|
|
self.set_parameter("SYSID_MYGCS", self.mav.source_system)
|
|
|
|
|
|
|
|
self.progress("Takeoff")
|
|
|
|
self.takeoff(alt=50)
|
|
|
|
|
|
|
|
self.change_mode('FBWA')
|
|
|
|
|
|
|
|
tstart = self.get_sim_time_cached()
|
|
|
|
roll_input = -500
|
|
|
|
want_roll_degrees = -12
|
|
|
|
while True:
|
|
|
|
if self.get_sim_time_cached() - tstart > 10:
|
|
|
|
raise AutoTestTimeoutException("Did not reach roll")
|
|
|
|
self.progress("Sending roll-left")
|
|
|
|
self.mav.mav.manual_control_send(
|
|
|
|
1, # target system
|
|
|
|
32767, # x (pitch)
|
|
|
|
roll_input, # y (roll)
|
|
|
|
32767, # z (thrust)
|
|
|
|
32767, # r (yaw)
|
|
|
|
0) # button mask
|
|
|
|
m = self.mav.recv_match(type='ATTITUDE', blocking=True, timeout=1)
|
|
|
|
print("m=%s" % str(m))
|
|
|
|
if m is None:
|
|
|
|
continue
|
|
|
|
p = math.degrees(m.roll)
|
|
|
|
self.progress("roll=%f want<=%f" % (p, want_roll_degrees))
|
|
|
|
if p <= want_roll_degrees:
|
|
|
|
break
|
|
|
|
self.mav.mav.manual_control_send(
|
|
|
|
1, # target system
|
|
|
|
32767, # x (pitch)
|
|
|
|
32767, # y (roll)
|
|
|
|
32767, # z (thrust)
|
|
|
|
32767, # r (yaw)
|
|
|
|
0) # button mask
|
|
|
|
self.fly_home_land_and_disarm()
|
|
|
|
|
2023-02-14 23:05:19 -04:00
|
|
|
def mission_home_point(self, target_system=1, target_component=1):
|
|
|
|
'''just an empty-ish item-int to store home'''
|
|
|
|
return self.mav.mav.mission_item_int_encode(
|
|
|
|
target_system,
|
|
|
|
target_component,
|
|
|
|
0, # seq
|
|
|
|
mavutil.mavlink.MAV_FRAME_GLOBAL,
|
|
|
|
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
|
|
|
|
0, # current
|
|
|
|
0, # autocontinue
|
|
|
|
0, # p1
|
|
|
|
0, # p2
|
|
|
|
0, # p3
|
|
|
|
0, # p4
|
|
|
|
0, # latitude
|
|
|
|
0, # longitude
|
|
|
|
0, # altitude
|
|
|
|
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
|
|
|
|
|
|
|
|
def mission_jump_tag(self, tag, target_system=1, target_component=1):
|
|
|
|
'''create a jump tag mission item'''
|
|
|
|
return self.mav.mav.mission_item_int_encode(
|
|
|
|
target_system,
|
|
|
|
target_component,
|
|
|
|
0, # seq
|
|
|
|
mavutil.mavlink.MAV_FRAME_GLOBAL,
|
|
|
|
mavutil.mavlink.MAV_CMD_JUMP_TAG,
|
|
|
|
0, # current
|
|
|
|
0, # autocontinue
|
|
|
|
tag, # p1
|
|
|
|
0, # p2
|
|
|
|
0, # p3
|
|
|
|
0, # p4
|
|
|
|
0, # latitude
|
|
|
|
0, # longitude
|
|
|
|
0, # altitude
|
|
|
|
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
|
|
|
|
|
2023-02-14 23:21:36 -04:00
|
|
|
def mission_do_jump_tag(self, tag, target_system=1, target_component=1):
|
|
|
|
'''create a jump tag mission item'''
|
|
|
|
return self.mav.mav.mission_item_int_encode(
|
|
|
|
target_system,
|
|
|
|
target_component,
|
|
|
|
0, # seq
|
|
|
|
mavutil.mavlink.MAV_FRAME_GLOBAL,
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_JUMP_TAG,
|
|
|
|
0, # current
|
|
|
|
0, # autocontinue
|
|
|
|
tag, # p1
|
|
|
|
0, # p2
|
|
|
|
0, # p3
|
|
|
|
0, # p4
|
|
|
|
0, # latitude
|
|
|
|
0, # longitude
|
|
|
|
0, # altitude
|
|
|
|
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
|
|
|
|
|
2023-02-14 23:05:19 -04:00
|
|
|
def mission_anonymous_waypoint(self, target_system=1, target_component=1):
|
|
|
|
'''just a boring waypoint'''
|
|
|
|
return self.mav.mav.mission_item_int_encode(
|
|
|
|
target_system,
|
|
|
|
target_component,
|
|
|
|
0, # seq
|
|
|
|
mavutil.mavlink.MAV_FRAME_GLOBAL,
|
|
|
|
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
|
|
|
|
0, # current
|
|
|
|
0, # autocontinue
|
|
|
|
0, # p1
|
|
|
|
0, # p2
|
|
|
|
0, # p3
|
|
|
|
0, # p4
|
|
|
|
1, # latitude
|
|
|
|
1, # longitude
|
|
|
|
1, # altitude
|
|
|
|
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
|
|
|
|
|
|
|
|
def renumber_mission_items(self, mission):
|
|
|
|
count = 0
|
|
|
|
for item in mission:
|
|
|
|
item.seq = count
|
|
|
|
count += 1
|
|
|
|
|
|
|
|
def MissionJumpTags_missing_jump_target(self, target_system=1, target_component=1):
|
|
|
|
self.start_subtest("Check missing-jump-tag behaviour")
|
|
|
|
jump_target = 2
|
|
|
|
mission = [
|
|
|
|
self.mission_home_point(),
|
2023-02-21 16:20:10 -04:00
|
|
|
self.mission_anonymous_waypoint(),
|
|
|
|
self.mission_anonymous_waypoint(),
|
2023-02-14 23:05:19 -04:00
|
|
|
self.mission_jump_tag(jump_target),
|
|
|
|
self.mission_anonymous_waypoint(),
|
2023-02-21 16:20:10 -04:00
|
|
|
self.mission_anonymous_waypoint(),
|
2023-02-14 23:05:19 -04:00
|
|
|
]
|
|
|
|
self.renumber_mission_items(mission)
|
|
|
|
self.check_mission_upload_download(mission)
|
|
|
|
self.progress("Checking incorrect tag behaviour")
|
|
|
|
self.run_cmd(
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_JUMP_TAG,
|
2023-07-15 09:40:01 -03:00
|
|
|
p1=jump_target + 1,
|
2023-02-14 23:05:19 -04:00
|
|
|
want_result=mavutil.mavlink.MAV_RESULT_FAILED
|
|
|
|
)
|
|
|
|
self.progress("Checking correct tag behaviour")
|
|
|
|
self.run_cmd(
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_JUMP_TAG,
|
2023-07-15 09:40:01 -03:00
|
|
|
p1=jump_target,
|
2023-02-14 23:05:19 -04:00
|
|
|
)
|
2023-02-21 16:20:10 -04:00
|
|
|
self.assert_current_waypoint(4)
|
2023-02-14 23:05:19 -04:00
|
|
|
|
2023-02-14 23:21:36 -04:00
|
|
|
def MissionJumpTags_do_jump_to_bad_tag(self, target_system=1, target_component=1):
|
|
|
|
mission = [
|
|
|
|
self.mission_home_point(),
|
|
|
|
self.mission_anonymous_waypoint(),
|
|
|
|
self.mission_do_jump_tag(17),
|
|
|
|
self.mission_anonymous_waypoint(),
|
|
|
|
]
|
|
|
|
self.renumber_mission_items(mission)
|
|
|
|
self.check_mission_upload_download(mission)
|
|
|
|
self.change_mode('AUTO')
|
|
|
|
self.arm_vehicle()
|
|
|
|
self.set_current_waypoint(2, check_afterwards=False)
|
|
|
|
self.assert_mode('RTL')
|
|
|
|
self.disarm_vehicle()
|
|
|
|
|
|
|
|
def MissionJumpTags_jump_tag_at_end_of_mission(self, target_system=1, target_component=1):
|
|
|
|
mission = [
|
|
|
|
self.mission_home_point(),
|
|
|
|
self.mission_anonymous_waypoint(),
|
|
|
|
self.mission_jump_tag(17),
|
|
|
|
]
|
2023-02-21 16:20:10 -04:00
|
|
|
# Jumping to an end of a mission, either DO_JUMP or DO_JUMP_TAG will result in a failed attempt.
|
|
|
|
# The failure is from mission::set_current_cmd() returning false if it can not find any NAV
|
|
|
|
# commands on or after the index. Two scenarios:
|
|
|
|
# 1) AUTO mission triggered: The the set_command will fail and it will cause an RTL event
|
|
|
|
# (Harder to test, need vehicle to actually reach the waypoint)
|
|
|
|
# 2) GCS/MAVLink: It will return MAV_RESULT_FAILED and there's on change to the mission. (Easy to test)
|
2023-02-14 23:21:36 -04:00
|
|
|
self.renumber_mission_items(mission)
|
|
|
|
self.check_mission_upload_download(mission)
|
|
|
|
self.progress("Checking correct tag behaviour")
|
|
|
|
self.change_mode('AUTO')
|
|
|
|
self.arm_vehicle()
|
|
|
|
self.run_cmd(
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_JUMP_TAG,
|
2023-07-15 09:40:01 -03:00
|
|
|
p1=17,
|
2023-02-21 16:20:10 -04:00
|
|
|
want_result=mavutil.mavlink.MAV_RESULT_FAILED
|
2023-02-14 23:21:36 -04:00
|
|
|
)
|
|
|
|
self.disarm_vehicle()
|
|
|
|
|
2023-02-14 23:05:19 -04:00
|
|
|
def MissionJumpTags(self):
|
|
|
|
'''test MAV_CMD_JUMP_TAG'''
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.MissionJumpTags_missing_jump_target()
|
2023-02-14 23:21:36 -04:00
|
|
|
self.MissionJumpTags_do_jump_to_bad_tag()
|
|
|
|
self.MissionJumpTags_jump_tag_at_end_of_mission()
|
2023-02-14 23:05:19 -04:00
|
|
|
|
2023-02-16 16:58:53 -04:00
|
|
|
def AltResetBadGPS(self):
|
|
|
|
'''Tests the handling of poor GPS lock pre-arm alt resets'''
|
|
|
|
self.set_parameters({
|
|
|
|
"SIM_GPS_GLITCH_Z": 0,
|
|
|
|
"SIM_GPS_ACC": 0.3,
|
|
|
|
})
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
|
|
|
|
m = self.assert_receive_message('GLOBAL_POSITION_INT')
|
|
|
|
relalt = m.relative_alt*0.001
|
|
|
|
if abs(relalt) > 3:
|
|
|
|
raise NotAchievedException("Bad relative alt %.1f" % relalt)
|
|
|
|
|
|
|
|
self.progress("Setting low accuracy, glitching GPS")
|
|
|
|
self.set_parameter("SIM_GPS_ACC", 40)
|
|
|
|
self.set_parameter("SIM_GPS_GLITCH_Z", -47)
|
|
|
|
|
|
|
|
self.progress("Waiting 10s for height update")
|
|
|
|
self.delay_sim_time(10)
|
|
|
|
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
|
|
|
|
|
|
|
m = self.assert_receive_message('GLOBAL_POSITION_INT')
|
|
|
|
relalt = m.relative_alt*0.001
|
|
|
|
if abs(relalt) > 3:
|
|
|
|
raise NotAchievedException("Bad glitching relative alt %.1f" % relalt)
|
|
|
|
|
|
|
|
self.disarm_vehicle()
|
|
|
|
# reboot to clear potentially bad state
|
2023-01-30 03:42:44 -04:00
|
|
|
|
|
|
|
def trigger_airspeed_cal(self):
|
2023-07-15 09:40:01 -03:00
|
|
|
self.run_cmd(
|
|
|
|
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
|
|
|
|
p3=1,
|
|
|
|
)
|
2023-01-30 03:42:44 -04:00
|
|
|
|
|
|
|
def AirspeedCal(self):
|
|
|
|
'''test Airspeed calibration'''
|
|
|
|
|
|
|
|
self.start_subtest('1 airspeed sensor')
|
|
|
|
self.context_push()
|
|
|
|
self.context_collect('STATUSTEXT')
|
|
|
|
self.trigger_airspeed_cal()
|
|
|
|
self.wait_statustext('Airspeed 1 calibrated', check_context=True)
|
|
|
|
self.context_pop()
|
|
|
|
|
|
|
|
self.context_push()
|
|
|
|
self.context_collect('STATUSTEXT')
|
|
|
|
self.start_subtest('0 airspeed sensors')
|
|
|
|
self.set_parameter('ARSPD_TYPE', 0)
|
|
|
|
self.reboot_sitl()
|
2023-05-08 04:57:24 -03:00
|
|
|
self.wait_statustext('No airspeed sensor', check_context=True)
|
2023-01-30 03:42:44 -04:00
|
|
|
self.trigger_airspeed_cal()
|
|
|
|
self.delay_sim_time(5)
|
|
|
|
if self.statustext_in_collections('Airspeed 1 calibrated'):
|
|
|
|
raise NotAchievedException("Did not disable airspeed sensor?!")
|
|
|
|
self.context_pop()
|
|
|
|
|
|
|
|
self.start_subtest('2 airspeed sensors')
|
|
|
|
self.set_parameter('ARSPD_TYPE', 100)
|
|
|
|
self.set_parameter('ARSPD2_TYPE', 100)
|
|
|
|
self.reboot_sitl()
|
|
|
|
self.context_push()
|
|
|
|
self.context_collect('STATUSTEXT')
|
|
|
|
self.trigger_airspeed_cal()
|
|
|
|
self.wait_statustext('Airspeed 1 calibrated', check_context=True)
|
|
|
|
self.wait_statustext('Airspeed 2 calibrated', check_context=True)
|
|
|
|
self.context_pop()
|
|
|
|
|
2023-02-16 16:58:53 -04:00
|
|
|
self.reboot_sitl()
|
|
|
|
|
2023-07-29 00:04:29 -03:00
|
|
|
def RunMissionScript(self):
|
|
|
|
'''Test run_mission.py script'''
|
|
|
|
script = os.path.join('Tools', 'autotest', 'run_mission.py')
|
|
|
|
self.stop_SITL()
|
|
|
|
util.run_cmd([
|
|
|
|
util.reltopdir(script),
|
|
|
|
self.binary,
|
|
|
|
'plane',
|
|
|
|
self.generic_mission_filepath_for_filename("flaps.txt"),
|
|
|
|
])
|
|
|
|
self.start_SITL()
|
|
|
|
|
2023-08-07 19:45:25 -03:00
|
|
|
def MAV_CMD_GUIDED_CHANGE_ALTITUDE(self):
|
|
|
|
'''test handling of MAV_CMD_GUIDED_CHANGE_ALTITUDE'''
|
|
|
|
self.takeoff(30, relative=True)
|
|
|
|
self.change_mode('GUIDED')
|
|
|
|
for alt in 50, 70:
|
|
|
|
self.run_cmd_int(
|
|
|
|
mavutil.mavlink.MAV_CMD_GUIDED_CHANGE_ALTITUDE,
|
|
|
|
p7=alt,
|
|
|
|
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
|
|
|
|
)
|
|
|
|
self.wait_altitude(alt-1, alt+1, timeout=30, relative=True)
|
|
|
|
|
|
|
|
# test for #24535
|
|
|
|
self.change_mode('LOITER')
|
|
|
|
self.delay_sim_time(5)
|
|
|
|
self.change_mode('GUIDED')
|
|
|
|
self.wait_altitude(
|
|
|
|
alt-3, # NOTE: reuse of alt from above loop!
|
|
|
|
alt+3,
|
|
|
|
minimum_duration=10,
|
|
|
|
timeout=30,
|
|
|
|
relative=True,
|
|
|
|
)
|
|
|
|
self.fly_home_land_and_disarm()
|
|
|
|
|
2023-09-07 06:22:43 -03:00
|
|
|
def _MAV_CMD_PREFLIGHT_CALIBRATION(self, command):
|
|
|
|
self.context_push()
|
|
|
|
self.start_subtest("Denied when armed")
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
|
|
|
command(
|
|
|
|
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
|
|
|
|
p1=1,
|
|
|
|
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
|
|
|
|
)
|
|
|
|
self.disarm_vehicle()
|
|
|
|
|
|
|
|
self.context_collect('STATUSTEXT')
|
|
|
|
|
|
|
|
self.start_subtest("gyro cal")
|
|
|
|
command(
|
|
|
|
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
|
|
|
|
p1=1,
|
|
|
|
)
|
|
|
|
|
|
|
|
self.start_subtest("baro cal")
|
|
|
|
command(
|
|
|
|
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
|
|
|
|
p3=1,
|
|
|
|
)
|
|
|
|
self.wait_statustext('Barometer calibration complete', check_context=True)
|
|
|
|
|
|
|
|
# accelcal skipped here, it is checked elsewhere
|
|
|
|
|
|
|
|
self.start_subtest("ins trim")
|
|
|
|
command(
|
|
|
|
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
|
|
|
|
p5=2,
|
|
|
|
)
|
|
|
|
|
|
|
|
# enforced delay between cals:
|
|
|
|
self.delay_sim_time(5)
|
|
|
|
|
|
|
|
self.start_subtest("simple accel cal")
|
|
|
|
command(
|
|
|
|
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
|
|
|
|
p5=4,
|
|
|
|
)
|
2023-09-11 09:34:42 -03:00
|
|
|
# simple gyro cal makes the GPS units go unhealthy as they are
|
|
|
|
# not maintaining their update rate (gyro cal is synchronous
|
|
|
|
# in the main loop). Usually ~30 seconds to recover...
|
|
|
|
self.wait_gps_sys_status_not_present_or_enabled_and_healthy(timeout=60)
|
2023-09-07 06:22:43 -03:00
|
|
|
|
|
|
|
self.start_subtest("force save accels")
|
|
|
|
command(
|
|
|
|
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
|
|
|
|
p5=76,
|
|
|
|
)
|
|
|
|
|
|
|
|
self.start_subtest("force save compasses")
|
|
|
|
command(
|
|
|
|
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
|
|
|
|
p2=76,
|
|
|
|
)
|
|
|
|
|
|
|
|
self.context_pop()
|
|
|
|
|
|
|
|
def MAV_CMD_PREFLIGHT_CALIBRATION(self):
|
|
|
|
'''test MAV_CMD_PREFLIGHT_CALIBRATION mavlink handling'''
|
|
|
|
self._MAV_CMD_PREFLIGHT_CALIBRATION(self.run_cmd)
|
|
|
|
self._MAV_CMD_PREFLIGHT_CALIBRATION(self.run_cmd_int)
|
|
|
|
|
2023-09-16 19:10:05 -03:00
|
|
|
def MAV_CMD_DO_INVERTED_FLIGHT(self):
|
|
|
|
'''fly upside-down mission item'''
|
|
|
|
alt = 30
|
|
|
|
wps = self.create_simple_relhome_mission([
|
|
|
|
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, alt),
|
|
|
|
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 400, 0, alt),
|
|
|
|
self.create_MISSION_ITEM_INT(
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_INVERTED_FLIGHT,
|
|
|
|
p1=1,
|
|
|
|
),
|
|
|
|
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 0, alt),
|
|
|
|
self.create_MISSION_ITEM_INT(
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_INVERTED_FLIGHT,
|
|
|
|
p1=0,
|
|
|
|
),
|
|
|
|
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1200, 0, alt),
|
|
|
|
(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),
|
|
|
|
])
|
|
|
|
self.check_mission_upload_download(wps)
|
|
|
|
|
|
|
|
self.change_mode('AUTO')
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
|
|
|
|
self.arm_vehicle()
|
|
|
|
|
|
|
|
self.wait_current_waypoint(2) # upright flight
|
|
|
|
self.wait_message_field_values("NAV_CONTROLLER_OUTPUT", {
|
|
|
|
"nav_roll": 0,
|
|
|
|
"nav_pitch": 0,
|
2023-09-18 05:04:50 -03:00
|
|
|
}, epsilon=10)
|
2023-09-16 19:10:05 -03:00
|
|
|
|
|
|
|
def check_altitude(mav, m):
|
|
|
|
global initial_airspeed_threshold_reached
|
|
|
|
m_type = m.get_type()
|
|
|
|
if m_type != 'GLOBAL_POSITION_INT':
|
|
|
|
return
|
|
|
|
if abs(30 - m.relative_alt * 0.001) > 15:
|
|
|
|
raise NotAchievedException("Bad altitude while flying inverted")
|
|
|
|
|
|
|
|
self.context_push()
|
|
|
|
self.install_message_hook_context(check_altitude)
|
|
|
|
|
|
|
|
self.wait_current_waypoint(4) # inverted flight
|
|
|
|
self.wait_message_field_values("NAV_CONTROLLER_OUTPUT", {
|
|
|
|
"nav_roll": 180,
|
|
|
|
"nav_pitch": 9,
|
|
|
|
}, epsilon=10,)
|
|
|
|
|
|
|
|
self.wait_current_waypoint(6) # upright flight
|
|
|
|
self.wait_message_field_values("NAV_CONTROLLER_OUTPUT", {
|
|
|
|
"nav_roll": 0,
|
|
|
|
"nav_pitch": 0,
|
2023-09-18 05:04:50 -03:00
|
|
|
}, epsilon=10)
|
2023-09-16 19:10:05 -03:00
|
|
|
|
|
|
|
self.context_pop() # remove the check_altitude call
|
|
|
|
|
|
|
|
self.wait_current_waypoint(7)
|
|
|
|
|
|
|
|
self.fly_home_land_and_disarm()
|
|
|
|
|
2023-09-20 06:04:40 -03:00
|
|
|
def MAV_CMD_DO_AUTOTUNE_ENABLE(self):
|
|
|
|
'''test enabling autotune via mavlink'''
|
|
|
|
self.context_collect('STATUSTEXT')
|
|
|
|
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_AUTOTUNE_ENABLE, p1=1)
|
|
|
|
self.wait_statustext('Started autotune', check_context=True)
|
|
|
|
self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_AUTOTUNE_ENABLE, p1=0)
|
|
|
|
self.wait_statustext('Stopped autotune', check_context=True)
|
|
|
|
|
2023-09-19 05:37:31 -03:00
|
|
|
def DO_PARACHUTE(self):
|
|
|
|
'''test triggering parachute via mavlink'''
|
|
|
|
self.set_parameters({
|
|
|
|
"CHUTE_ENABLED": 1,
|
|
|
|
"CHUTE_TYPE": 10,
|
|
|
|
"SERVO9_FUNCTION": 27,
|
|
|
|
"SIM_PARA_ENABLE": 1,
|
|
|
|
"SIM_PARA_PIN": 9,
|
|
|
|
"FS_LONG_ACTN": 3,
|
|
|
|
})
|
|
|
|
for command in self.run_cmd, self.run_cmd_int:
|
|
|
|
self.wait_servo_channel_value(9, 1100)
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
|
|
|
command(
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_PARACHUTE,
|
|
|
|
p1=mavutil.mavlink.PARACHUTE_RELEASE,
|
|
|
|
)
|
|
|
|
self.wait_servo_channel_value(9, 1300)
|
|
|
|
self.disarm_vehicle()
|
|
|
|
self.reboot_sitl()
|
|
|
|
|
2023-09-26 02:58:40 -03:00
|
|
|
def _MAV_CMD_DO_GO_AROUND(self, command):
|
|
|
|
self.load_mission("mission.txt")
|
|
|
|
self.set_parameter("RTL_AUTOLAND", 3)
|
|
|
|
self.change_mode('AUTO')
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
|
|
|
self.wait_current_waypoint(6)
|
|
|
|
command(mavutil.mavlink.MAV_CMD_DO_GO_AROUND, p1=150)
|
|
|
|
self.wait_current_waypoint(5)
|
|
|
|
self.wait_altitude(135, 165, relative=True)
|
|
|
|
self.wait_disarmed(timeout=300)
|
|
|
|
|
|
|
|
def MAV_CMD_DO_GO_AROUND(self):
|
|
|
|
'''test MAV_CMD_DO_GO_AROUND as a mavlink command'''
|
|
|
|
self._MAV_CMD_DO_GO_AROUND(self.run_cmd)
|
|
|
|
self._MAV_CMD_DO_GO_AROUND(self.run_cmd_int)
|
|
|
|
|
2023-09-26 03:25:02 -03:00
|
|
|
def _MAV_CMD_DO_FLIGHTTERMINATION(self, command):
|
|
|
|
self.set_parameters({
|
|
|
|
"AFS_ENABLE": 1,
|
|
|
|
"SYSID_MYGCS": self.mav.source_system,
|
|
|
|
"AFS_TERM_ACTION": 42,
|
|
|
|
})
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
self.arm_vehicle()
|
|
|
|
self.context_collect('STATUSTEXT')
|
|
|
|
command(mavutil.mavlink.MAV_CMD_DO_FLIGHTTERMINATION, p1=1)
|
|
|
|
self.wait_disarmed()
|
|
|
|
self.wait_text('Terminating due to GCS request', check_context=True)
|
|
|
|
self.reboot_sitl()
|
|
|
|
|
|
|
|
def MAV_CMD_DO_FLIGHTTERMINATION(self):
|
|
|
|
'''test MAV_CMD_DO_FLIGHTTERMINATION works on Plane'''
|
|
|
|
self._MAV_CMD_DO_FLIGHTTERMINATION(self.run_cmd)
|
|
|
|
self._MAV_CMD_DO_FLIGHTTERMINATION(self.run_cmd_int)
|
|
|
|
|
2023-09-28 04:15:08 -03:00
|
|
|
def MAV_CMD_DO_LAND_START(self):
|
|
|
|
'''test MAV_CMD_DO_LAND_START as mavlink command'''
|
|
|
|
self.set_parameters({
|
|
|
|
"RTL_AUTOLAND": 3,
|
|
|
|
})
|
|
|
|
self.upload_simple_relhome_mission([
|
|
|
|
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
|
|
|
|
(mavutil.mavlink.MAV_CMD_NAV_LOITER_UNLIM, 0, 0, 30),
|
|
|
|
self.create_MISSION_ITEM_INT(
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_LAND_START,
|
|
|
|
),
|
|
|
|
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 0, 0),
|
|
|
|
])
|
|
|
|
|
|
|
|
self.change_mode('AUTO')
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
|
|
|
|
self.arm_vehicle()
|
|
|
|
|
|
|
|
self.start_subtest("DO_LAND_START as COMMAND_LONG")
|
|
|
|
self.wait_current_waypoint(2)
|
|
|
|
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_LAND_START)
|
|
|
|
self.wait_current_waypoint(4)
|
|
|
|
|
|
|
|
self.start_subtest("DO_LAND_START as COMMAND_INT")
|
|
|
|
self.set_current_waypoint(2)
|
|
|
|
self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_LAND_START)
|
|
|
|
self.wait_current_waypoint(4)
|
|
|
|
|
|
|
|
self.fly_home_land_and_disarm()
|
|
|
|
|
2023-10-05 19:10:31 -03:00
|
|
|
def start_flying_simple_rehome_mission(self, items):
|
|
|
|
'''uploads items, changes mode to auto, waits ready to arm and arms
|
|
|
|
vehicle. If the first item it a takeoff you can expect the
|
|
|
|
vehicle to fly after this method returns
|
|
|
|
'''
|
|
|
|
|
|
|
|
self.upload_simple_relhome_mission(items)
|
|
|
|
|
|
|
|
self.change_mode('AUTO')
|
|
|
|
self.wait_ready_to_arm()
|
|
|
|
|
|
|
|
self.arm_vehicle()
|
|
|
|
|
|
|
|
def InteractTest(self):
|
|
|
|
'''just takeoff'''
|
|
|
|
|
|
|
|
if self.mavproxy is None:
|
|
|
|
raise NotAchievedException("Must be started with --map")
|
|
|
|
|
|
|
|
self.start_flying_simple_rehome_mission([
|
|
|
|
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
|
|
|
|
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 0, 0),
|
|
|
|
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 800, 0),
|
|
|
|
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 400, 0),
|
|
|
|
])
|
|
|
|
|
|
|
|
self.wait_current_waypoint(4)
|
|
|
|
|
|
|
|
self.set_parameter('SIM_SPEEDUP', 1)
|
|
|
|
|
|
|
|
self.mavproxy.interact()
|
|
|
|
|
2023-10-04 09:34:42 -03:00
|
|
|
def MAV_CMD_MISSION_START(self):
|
|
|
|
'''test MAV_CMD_MISSION_START starts AUTO'''
|
|
|
|
self.upload_simple_relhome_mission([
|
|
|
|
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 0, 0),
|
|
|
|
])
|
|
|
|
for run_cmd in self.run_cmd, self.run_cmd_int:
|
|
|
|
self.change_mode('LOITER')
|
|
|
|
run_cmd(mavutil.mavlink.MAV_CMD_MISSION_START)
|
|
|
|
self.wait_mode('AUTO')
|
|
|
|
|
2023-10-11 08:20:45 -03:00
|
|
|
def MAV_CMD_NAV_LOITER_UNLIM(self):
|
|
|
|
'''test receiving MAV_CMD_NAV_LOITER_UNLIM from GCS'''
|
|
|
|
self.takeoff(10)
|
|
|
|
self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_LOITER_UNLIM)
|
|
|
|
self.wait_mode('LOITER')
|
|
|
|
self.change_mode('GUIDED')
|
|
|
|
self.run_cmd_int(mavutil.mavlink.MAV_CMD_NAV_LOITER_UNLIM)
|
|
|
|
self.wait_mode('LOITER')
|
|
|
|
self.fly_home_land_and_disarm()
|
|
|
|
|
|
|
|
def MAV_CMD_NAV_RETURN_TO_LAUNCH(self):
|
|
|
|
'''test receiving MAV_CMD_NAV_RETURN_TO_LAUNCH from GCS'''
|
|
|
|
self.set_parameter('RTL_AUTOLAND', 1)
|
|
|
|
self.start_flying_simple_rehome_mission([
|
|
|
|
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
|
|
|
|
(mavutil.mavlink.MAV_CMD_NAV_LOITER_UNLIM, 0, 0, 30),
|
|
|
|
self.create_MISSION_ITEM_INT(
|
|
|
|
mavutil.mavlink.MAV_CMD_DO_LAND_START,
|
|
|
|
),
|
|
|
|
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 0, 0),
|
|
|
|
])
|
|
|
|
|
|
|
|
for i in self.run_cmd, self.run_cmd_int:
|
|
|
|
self.wait_current_waypoint(2)
|
|
|
|
self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH)
|
|
|
|
self.wait_current_waypoint(4)
|
|
|
|
self.set_current_waypoint(2)
|
|
|
|
self.fly_home_land_and_disarm()
|
|
|
|
|
2023-10-20 01:56:40 -03:00
|
|
|
def location_from_ADSB_VEHICLE(self, m):
|
|
|
|
'''return a mavutil.location extracted from an ADSB_VEHICLE mavlink
|
|
|
|
message'''
|
|
|
|
if m.altitude_type != mavutil.mavlink.ADSB_ALTITUDE_TYPE_GEOMETRIC:
|
|
|
|
raise ValueError("Expected geometric alt")
|
|
|
|
return mavutil.location(
|
|
|
|
m.lat*1e-7,
|
|
|
|
m.lon*1e-7,
|
|
|
|
m.altitude/1000.0585, # mm -> m
|
|
|
|
m.heading * 0.01 # centidegrees -> degrees
|
|
|
|
)
|
|
|
|
|
|
|
|
def SagetechMXS(self):
|
|
|
|
'''test Sagetech MXS ADSB device driver'''
|
|
|
|
sim_name = "sagetech_mxs"
|
|
|
|
self.set_parameters({
|
|
|
|
"SERIAL5_PROTOCOL": 35,
|
|
|
|
"ADSB_TYPE": 4, # Sagetech-MXS
|
|
|
|
"SIM_ADSB_TYPES": 8, # Sagetech-MXS
|
|
|
|
"SIM_ADSB_COUNT": 5,
|
|
|
|
})
|
|
|
|
self.customise_SITL_commandline(["--serial5=sim:%s" % sim_name])
|
|
|
|
m = self.assert_receive_message("ADSB_VEHICLE")
|
|
|
|
adsb_vehicle_loc = self.location_from_ADSB_VEHICLE(m)
|
|
|
|
self.progress("ADSB Vehicle at loc %s" % str(adsb_vehicle_loc))
|
|
|
|
home = self.home_position_as_mav_location()
|
|
|
|
self.assert_distance(home, adsb_vehicle_loc, 0, 10000)
|
|
|
|
|
2018-12-16 18:54:05 -04:00
|
|
|
def tests(self):
|
|
|
|
'''return list of all tests'''
|
|
|
|
ret = super(AutoTestPlane, self).tests()
|
|
|
|
ret.extend([
|
2022-09-09 22:24:28 -03:00
|
|
|
self.AuxModeSwitch,
|
|
|
|
self.TestRCCamera,
|
|
|
|
self.TestRCRelay,
|
|
|
|
self.ThrottleFailsafe,
|
|
|
|
self.NeedEKFToArm,
|
|
|
|
self.ThrottleFailsafeFence,
|
|
|
|
self.TestFlaps,
|
|
|
|
self.DO_CHANGE_SPEED,
|
|
|
|
self.DO_REPOSITION,
|
|
|
|
self.GuidedRequest,
|
|
|
|
self.MainFlight,
|
|
|
|
self.TestGripperMission,
|
|
|
|
self.Parachute,
|
|
|
|
self.ParachuteSinkRate,
|
2023-09-19 05:37:31 -03:00
|
|
|
self.DO_PARACHUTE,
|
2022-07-03 02:46:32 -03:00
|
|
|
self.PitotBlockage,
|
2022-09-09 22:24:28 -03:00
|
|
|
self.AIRSPEED_AUTOCAL,
|
|
|
|
self.RangeFinder,
|
|
|
|
self.FenceStatic,
|
|
|
|
self.FenceRTL,
|
|
|
|
self.FenceRTLRally,
|
|
|
|
self.FenceRetRally,
|
|
|
|
self.FenceAltCeilFloor,
|
|
|
|
self.FenceBreachedChangeMode,
|
|
|
|
self.FenceNoFenceReturnPoint,
|
|
|
|
self.FenceNoFenceReturnPointInclusion,
|
|
|
|
self.FenceDisableUnderAction,
|
|
|
|
self.ADSB,
|
|
|
|
self.SimADSB,
|
|
|
|
self.Button,
|
|
|
|
self.FRSkySPort,
|
|
|
|
self.FRSkyPassThroughStatustext,
|
|
|
|
self.FRSkyPassThroughSensorIDs,
|
|
|
|
self.FRSkyMAVlite,
|
|
|
|
self.FRSkyD,
|
|
|
|
self.LTM,
|
|
|
|
self.DEVO,
|
|
|
|
self.AdvancedFailsafe,
|
|
|
|
self.LOITER,
|
|
|
|
self.MAV_CMD_NAV_LOITER_TURNS,
|
|
|
|
self.DeepStall,
|
|
|
|
self.WatchdogHome,
|
|
|
|
self.LargeMissions,
|
|
|
|
self.Soaring,
|
|
|
|
self.Terrain,
|
|
|
|
self.TerrainMission,
|
|
|
|
self.TerrainLoiter,
|
|
|
|
self.VectorNavEAHRS,
|
2023-08-27 19:42:56 -03:00
|
|
|
self.MicroStrainEAHRS5,
|
2022-09-09 22:24:28 -03:00
|
|
|
self.Deadreckoning,
|
|
|
|
self.DeadreckoningNoAirSpeed,
|
|
|
|
self.EKFlaneswitch,
|
|
|
|
self.AirspeedDrivers,
|
|
|
|
self.RTL_CLIMB_MIN,
|
|
|
|
self.ClimbBeforeTurn,
|
|
|
|
self.IMUTempCal,
|
2023-10-03 04:04:47 -03:00
|
|
|
self.MAV_CMD_DO_AUX_FUNCTION,
|
2022-09-09 22:24:28 -03:00
|
|
|
self.SmartBattery,
|
|
|
|
self.FlyEachFrame,
|
|
|
|
self.RCDisableAirspeedUse,
|
|
|
|
self.AHRS_ORIENTATION,
|
|
|
|
self.AHRSTrim,
|
|
|
|
self.LandingDrift,
|
|
|
|
self.ForcedDCM,
|
|
|
|
self.DCMFallback,
|
|
|
|
self.MAVFTP,
|
|
|
|
self.AUTOTUNE,
|
2023-07-19 10:10:03 -03:00
|
|
|
self.AutotuneFiltering,
|
2022-09-09 22:24:28 -03:00
|
|
|
self.MegaSquirt,
|
|
|
|
self.MSP_DJI,
|
|
|
|
self.SpeedToFly,
|
|
|
|
self.GlideSlopeThresh,
|
|
|
|
self.HIGH_LATENCY2,
|
|
|
|
self.MidAirDisarmDisallowed,
|
2022-10-06 01:46:02 -03:00
|
|
|
self.EmbeddedParamParser,
|
2022-11-09 19:07:43 -04:00
|
|
|
self.AerobaticsScripting,
|
2022-11-22 20:04:52 -04:00
|
|
|
self.MANUAL_CONTROL,
|
2023-07-29 00:04:29 -03:00
|
|
|
self.RunMissionScript,
|
2022-10-10 00:47:57 -03:00
|
|
|
self.WindEstimates,
|
2023-02-16 16:58:53 -04:00
|
|
|
self.AltResetBadGPS,
|
2023-01-30 03:42:44 -04:00
|
|
|
self.AirspeedCal,
|
2023-02-14 23:05:19 -04:00
|
|
|
self.MissionJumpTags,
|
2023-07-27 23:20:58 -03:00
|
|
|
Test(self.GCSFailsafe, speedup=8),
|
2023-02-14 21:11:32 -04:00
|
|
|
self.SDCardWPTest,
|
2023-04-12 02:23:26 -03:00
|
|
|
self.NoArmWithoutMissionItems,
|
2022-07-13 22:09:08 -03:00
|
|
|
self.MODE_SWITCH_RESET,
|
2023-06-05 18:16:25 -03:00
|
|
|
self.ExternalPositionEstimate,
|
2023-10-20 01:56:40 -03:00
|
|
|
self.SagetechMXS,
|
2023-08-07 19:45:25 -03:00
|
|
|
self.MAV_CMD_GUIDED_CHANGE_ALTITUDE,
|
2023-09-07 06:22:43 -03:00
|
|
|
self.MAV_CMD_PREFLIGHT_CALIBRATION,
|
2023-09-16 19:10:05 -03:00
|
|
|
self.MAV_CMD_DO_INVERTED_FLIGHT,
|
2023-09-20 06:04:40 -03:00
|
|
|
self.MAV_CMD_DO_AUTOTUNE_ENABLE,
|
2023-09-26 02:58:40 -03:00
|
|
|
self.MAV_CMD_DO_GO_AROUND,
|
2023-09-26 03:25:02 -03:00
|
|
|
self.MAV_CMD_DO_FLIGHTTERMINATION,
|
2023-09-28 04:15:08 -03:00
|
|
|
self.MAV_CMD_DO_LAND_START,
|
2023-10-05 19:10:31 -03:00
|
|
|
self.InteractTest,
|
2023-10-04 09:34:42 -03:00
|
|
|
self.MAV_CMD_MISSION_START,
|
2023-10-12 19:54:15 -03:00
|
|
|
self.TerrainRally,
|
2023-10-11 08:20:45 -03:00
|
|
|
self.MAV_CMD_NAV_LOITER_UNLIM,
|
|
|
|
self.MAV_CMD_NAV_RETURN_TO_LAUNCH,
|
2018-12-16 18:54:05 -04:00
|
|
|
])
|
|
|
|
return ret
|
2020-09-07 02:17:41 -03:00
|
|
|
|
|
|
|
def disabled_tests(self):
|
2021-01-19 17:17:57 -04:00
|
|
|
return {
|
2022-09-09 22:24:28 -03:00
|
|
|
"LandingDrift": "Flapping test. See https://github.com/ArduPilot/ardupilot/issues/20054",
|
2023-10-05 19:10:31 -03:00
|
|
|
"InteractTest": "requires user interaction",
|
2021-01-19 17:17:57 -04:00
|
|
|
}
|