|
|
|
@ -6643,6 +6643,48 @@ class AutoTestCopter(AutoTest):
@@ -6643,6 +6643,48 @@ class AutoTestCopter(AutoTest):
|
|
|
|
|
self.takeoff(10) |
|
|
|
|
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 test_replay(self): |
|
|
|
|
'''test replay correctness''' |
|
|
|
|
self.progress("Building Replay") |
|
|
|
|