autotest: add test for Plane MAV_CMD_DO_VTOL_TRANSITION mission item
This commit is contained in:
parent
63136e9060
commit
f2f7f7de3b
6
Tools/autotest/Generic_Missions/QuadPlaneDalbyRTL.txt
Normal file
6
Tools/autotest/Generic_Missions/QuadPlaneDalbyRTL.txt
Normal file
@ -0,0 +1,6 @@
|
||||
QGC WPL 110
|
||||
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -27.274439 151.290064 343.209991 1
|
||||
1 0 3 189 0.000000 0.000000 0.000000 0.000000 -27.270617 151.283268 28.590000 1
|
||||
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -27.272859 151.286018 28.789999 1
|
||||
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -27.273316 151.288023 30.000000 1
|
||||
4 0 3 85 0.000000 0.000000 0.000000 0.000000 -27.273771 151.289905 0.000000 1
|
@ -3731,6 +3731,13 @@ class AutoTest(ABC):
|
||||
self.set_rc(ch, 1000)
|
||||
self.delay_sim_time(1)
|
||||
|
||||
def correct_wp_seq_numbers(self, wps):
|
||||
# renumber the items:
|
||||
count = 0
|
||||
for item in wps:
|
||||
item.seq = count
|
||||
count += 1
|
||||
|
||||
def create_simple_relhome_mission(self, items_in, target_system=1, target_component=1):
|
||||
'''takes a list of (type, n, e, alt) items. Creates a mission in
|
||||
absolute frame using alt as relative-to-home and n and e as
|
||||
@ -3741,34 +3748,24 @@ class AutoTest(ABC):
|
||||
items.extend(items_in)
|
||||
seq = 0
|
||||
ret = []
|
||||
for (t, n, e, alt) in items:
|
||||
for item in items:
|
||||
if not isinstance(item, tuple):
|
||||
# hope this is a mission item...
|
||||
item.seq = seq
|
||||
seq += 1
|
||||
ret.append(item)
|
||||
continue
|
||||
(t, n, e, alt) = item
|
||||
lat = 0
|
||||
lng = 0
|
||||
if n != 0 or e != 0:
|
||||
loc = self.home_relative_loc_ne(n, e)
|
||||
lat = loc.lat
|
||||
lng = loc.lng
|
||||
p1 = 0
|
||||
frame = mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT
|
||||
if not self.ardupilot_stores_frame_for_cmd(t):
|
||||
frame = mavutil.mavlink.MAV_FRAME_GLOBAL
|
||||
ret.append(self.mav.mav.mission_item_int_encode(
|
||||
target_system,
|
||||
target_component,
|
||||
seq, # seq
|
||||
frame,
|
||||
t,
|
||||
0, # current
|
||||
0, # autocontinue
|
||||
p1, # p1
|
||||
0, # p2
|
||||
0, # p3
|
||||
0, # p4
|
||||
int(lat*1e7), # latitude
|
||||
int(lng*1e7), # longitude
|
||||
alt, # altitude
|
||||
mavutil.mavlink.MAV_MISSION_TYPE_MISSION),
|
||||
)
|
||||
ret.append(self.create_MISSION_ITEM_INT(t, seq=seq, frame=frame, x=int(lat*1e7), y=int(lng*1e7), z=alt))
|
||||
seq += 1
|
||||
|
||||
return ret
|
||||
@ -5635,6 +5632,42 @@ class AutoTest(ABC):
|
||||
def sysid_thismav(self):
|
||||
return 1
|
||||
|
||||
def create_MISSION_ITEM_INT(
|
||||
self,
|
||||
t,
|
||||
p1=0,
|
||||
p2=0,
|
||||
p3=0,
|
||||
p4=0,
|
||||
x=0,
|
||||
y=0,
|
||||
z=0,
|
||||
frame=mavutil.mavlink.MAV_FRAME_GLOBAL,
|
||||
autocontinue=1,
|
||||
current=0,
|
||||
target_system=1,
|
||||
target_component=1,
|
||||
seq=0,
|
||||
mission_type=mavutil.mavlink.MAV_MISSION_TYPE_MISSION,
|
||||
):
|
||||
return self.mav.mav.mission_item_int_encode(
|
||||
target_system,
|
||||
target_component,
|
||||
seq, # seq
|
||||
frame,
|
||||
t,
|
||||
0, # current
|
||||
0, # autocontinue
|
||||
p1, # p1
|
||||
0, # p2
|
||||
0, # p3
|
||||
0, # p4
|
||||
x, # latitude
|
||||
y, # longitude
|
||||
z, # altitude
|
||||
mission_type
|
||||
)
|
||||
|
||||
def run_cmd_int(self,
|
||||
command,
|
||||
p1=0,
|
||||
|
@ -556,11 +556,7 @@ class AutoTestHelicopter(AutoTestCopter):
|
||||
copy.copy(wp5_by_three),
|
||||
self.mission_item_rtl(target_system=target_system, target_component=target_component),
|
||||
])
|
||||
# renumber the items:
|
||||
count = 0
|
||||
for item in ret:
|
||||
item.seq = count
|
||||
count += 1
|
||||
self.correct_wp_seq_numbers(ret)
|
||||
return ret
|
||||
|
||||
def scurve_nasty_up_mission(self, target_system=1, target_component=1):
|
||||
@ -633,11 +629,7 @@ class AutoTestHelicopter(AutoTestCopter):
|
||||
wp7,
|
||||
self.mission_item_rtl(target_system=target_system, target_component=target_component),
|
||||
])
|
||||
# renumber the items:
|
||||
count = 0
|
||||
for item in ret:
|
||||
item.seq = count
|
||||
count += 1
|
||||
self.correct_wp_seq_numbers(ret)
|
||||
return ret
|
||||
|
||||
def fly_mission_points(self, points):
|
||||
|
@ -416,13 +416,19 @@ class AutoTestQuadPlane(AutoTest):
|
||||
self.zero_throttle()
|
||||
|
||||
def fly_home_land_and_disarm(self, timeout=30):
|
||||
self.set_parameter("LAND_TYPE", 0)
|
||||
filename = "flaps.txt"
|
||||
self.change_mode('LOITER')
|
||||
self.set_parameter('RTL_AUTOLAND', 1)
|
||||
filename = "QuadPlaneDalbyRTL.txt"
|
||||
self.progress("Using %s to fly home" % filename)
|
||||
self.load_mission(filename)
|
||||
self.change_mode("AUTO")
|
||||
self.set_current_waypoint(7)
|
||||
self.load_generic_mission(filename)
|
||||
self.change_mode("RTL")
|
||||
self.wait_current_waypoint(4)
|
||||
self.wait_statustext('Land descend started')
|
||||
self.wait_statustext('Land final started', timeout=60)
|
||||
self.wait_disarmed(timeout=timeout)
|
||||
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
|
||||
# the following command is accepted, but doesn't actually
|
||||
# work! Should be able to remove check_afterwards!
|
||||
self.set_current_waypoint(0, check_afterwards=False)
|
||||
|
||||
def wait_level_flight(self, accuracy=5, timeout=30):
|
||||
@ -1299,6 +1305,36 @@ class AutoTestQuadPlane(AutoTest):
|
||||
self.context_pop()
|
||||
self.reboot_sitl()
|
||||
|
||||
def mission_MAV_CMD_DO_VTOL_TRANSITION(self):
|
||||
'''mission item forces transition'''
|
||||
wps = self.create_simple_relhome_mission([
|
||||
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
|
||||
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 200, 0, 30),
|
||||
self.create_MISSION_ITEM_INT(
|
||||
mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION,
|
||||
p1=mavutil.mavlink.MAV_VTOL_STATE_MC
|
||||
),
|
||||
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 300, 200, 30),
|
||||
self.create_MISSION_ITEM_INT(
|
||||
mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION,
|
||||
p1=mavutil.mavlink.MAV_VTOL_STATE_FW
|
||||
),
|
||||
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 100, 200, 30),
|
||||
(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(4)
|
||||
self.wait_servo_channel_value(5, 1200, comparator=operator.gt)
|
||||
self.wait_current_waypoint(6)
|
||||
self.wait_servo_channel_value(5, 1000, comparator=operator.eq, timeout=90)
|
||||
|
||||
self.fly_home_land_and_disarm()
|
||||
|
||||
def tests(self):
|
||||
'''return list of all tests'''
|
||||
|
||||
@ -1327,5 +1363,6 @@ class AutoTestQuadPlane(AutoTest):
|
||||
self.VTOLLandSpiral,
|
||||
self.VTOLQuicktune,
|
||||
self.RCDisableAirspeedUse,
|
||||
self.mission_MAV_CMD_DO_VTOL_TRANSITION,
|
||||
])
|
||||
return ret
|
||||
|
Loading…
Reference in New Issue
Block a user