mirror of https://github.com/ArduPilot/ardupilot
autotest: move upload_simple_relhome_mission up
This commit is contained in:
parent
d73ce0ed57
commit
ca35d01baa
|
@ -6787,55 +6787,6 @@ class AutoTestCopter(AutoTest):
|
|||
|
||||
self.do_RTL()
|
||||
|
||||
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
|
||||
offsets in metres from home'''
|
||||
|
||||
# add a dummy waypoint for home
|
||||
items = [(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0, 0)]
|
||||
items.extend(items_in)
|
||||
seq = 0
|
||||
ret = []
|
||||
for (t, n, e, alt) in items:
|
||||
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),
|
||||
)
|
||||
seq += 1
|
||||
|
||||
return ret
|
||||
|
||||
def upload_simple_relhome_mission(self, items, target_system=1, target_component=1):
|
||||
mission = self.create_simple_relhome_mission(
|
||||
items,
|
||||
target_system=target_system,
|
||||
target_component=target_component)
|
||||
self.check_mission_upload_download(mission)
|
||||
|
||||
def test_replay(self):
|
||||
'''test replay correctness'''
|
||||
self.progress("Building Replay")
|
||||
|
|
|
@ -2736,6 +2736,55 @@ class AutoTest(ABC):
|
|||
self.set_rc(ch, 1000)
|
||||
self.delay_sim_time(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
|
||||
offsets in metres from home'''
|
||||
|
||||
# add a dummy waypoint for home
|
||||
items = [(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0, 0)]
|
||||
items.extend(items_in)
|
||||
seq = 0
|
||||
ret = []
|
||||
for (t, n, e, alt) in items:
|
||||
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),
|
||||
)
|
||||
seq += 1
|
||||
|
||||
return ret
|
||||
|
||||
def upload_simple_relhome_mission(self, items, target_system=1, target_component=1):
|
||||
mission = self.create_simple_relhome_mission(
|
||||
items,
|
||||
target_system=target_system,
|
||||
target_component=target_component)
|
||||
self.check_mission_upload_download(mission)
|
||||
|
||||
def get_mission_count(self):
|
||||
return self.get_parameter("MIS_TOTAL")
|
||||
|
||||
|
|
Loading…
Reference in New Issue