Skip to content

Commit

Permalink
Tools: autotest: add test for MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCA…
Browse files Browse the repository at this point in the history
…L_NED
  • Loading branch information
peterbarker committed Feb 22, 2019
1 parent 8c1c56c commit ce8ea63
Showing 1 changed file with 90 additions and 0 deletions.
90 changes: 90 additions & 0 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -2065,6 +2065,41 @@ def test_setting_modes_via_auxswitch(self):
if ex is not None:
raise ex

def fly_guided_stop(self,
timeout=20,
groundspeed_tolerance=0.05,
climb_tolerance=0.001):
"""stop the vehicle moving in guided mode"""
self.progress("Stopping vehicle")
tstart = self.get_sim_time()
while True:
if self.get_sim_time_cached() - tstart > timeout:
raise NotAchievedException("Vehicle did not stop")
# send a position-control command
self.mav.mav.set_position_target_local_ned_send(
0, # timestamp
1, # target system_id
1, # target component id
mavutil.mavlink.MAV_FRAME_BODY_NED,
0b1111111111111000, # mask specifying use-only-x-y-z
0, # x
0, # y
0, # z
0, # vx
0, # vy
0, # vz
0, # afx
0, # afy
0, # afz
0, # yaw
0, # yawrate
)
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
print("%s" % str(m))
if (m.groundspeed < groundspeed_tolerance and
m.climb < climb_tolerance):
break

def fly_guided_move_relative(self, lat, lon, alt):
startpos = self.mav.recv_match(type='GLOBAL_POSITION_INT',
blocking=True)
Expand Down Expand Up @@ -2098,6 +2133,58 @@ def fly_guided_move_relative(self, lat, lon, alt):
self.progress("delta=%f (want >10)" % delta)
if delta > 10:
break
self.fly_guided_stop()

def fly_guided_move_local(self, x, y, z_up, timeout=100):
"""move the vehicle using MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED"""
startpos = self.mav.recv_match(type='LOCAL_POSITION_NED', blocking=True)
self.progress("startpos=%s" % str(startpos))

tstart = self.get_sim_time()
while True:
if self.get_sim_time() - tstart > timeout:
raise NotAchievedException("Did not start to move")
# send a position-control command
self.mav.mav.set_position_target_local_ned_send(
0, # timestamp
1, # target system_id
1, # target component id
mavutil.mavlink.MAV_FRAME_LOCAL_NED,
0b1111111111111000, # mask specifying use-only-x-y-z
x, # x
y, # y
-z_up,# z
0, # vx
0, # vy
0, # vz
0, # afx
0, # afy
0, # afz
0, # yaw
0, # yawrate
)
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
print("%s" % m)
if m.groundspeed > 0.5:
break

self.progress("Waiting for vehicle to stop...")
self.wait_groundspeed(1, 100, timeout=timeout)

stoppos = self.mav.recv_match(type='LOCAL_POSITION_NED', blocking=True)
self.progress("stop_pos=%s" % str(stoppos))

x_achieved = stoppos.x - startpos.x
if x_achieved - x > 1:
raise NotAchievedException("Did not achieve x position: want=%f got=%f" % (x, x_achieved))

y_achieved = stoppos.y - startpos.y
if y_achieved - y > 1:
raise NotAchievedException("Did not achieve y position: want=%f got=%f" % (y, y_achieved))

z_achieved = stoppos.z - startpos.z
if z_achieved - z_up > 1:
raise NotAchievedException("Did not achieve z position: want=%f got=%f" % (z_up, z_achieved))

def earth_to_body(self, vector):
m = self.mav.messages["ATTITUDE"]
Expand Down Expand Up @@ -2220,6 +2307,9 @@ def fly_guided_change_submode(self):
"""move the vehicle using set_position_target_global_int"""
self.fly_guided_move_relative(5, 5, 10)

"""move the vehicle using MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED"""
self.fly_guided_move_local(5, 5, 10)

self.progress("Landing")
self.mavproxy.send('switch 2\n') # land mode
self.wait_mode('LAND')
Expand Down

0 comments on commit ce8ea63

Please sign in to comment.