autotest: add test for MAV_CMD_DO_SET_MISSION_CURRENT

This commit is contained in:
Peter Barker 2021-02-18 21:33:04 +11:00 committed by Peter Barker
parent e3de88d1d4
commit 4aed767fe9
2 changed files with 95 additions and 0 deletions

View File

@ -4269,6 +4269,23 @@ class AutoTest(ABC):
mavutil.mavlink.enums["MAV_RESULT"][m.result].name))
break
def set_current_waypoint_using_mav_cmd_do_set_mission_current(
self,
seq,
target_sysid=1,
target_compid=1):
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT,
seq,
0,
0,
0,
0,
0,
0,
timeout=1,
target_sysid=target_sysid,
target_compid=target_compid)
def set_current_waypoint_using_mission_set_current(self,
seq,
target_sysid=1,

View File

@ -5566,6 +5566,80 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.mavproxy.send("param fetch\n")
self.mavproxy.expect("Received [0-9]+ parameters")
def MAV_CMD_DO_SET_MISSION_CURRENT_mission(self, target_system=1, target_component=1):
return copy.copy([
self.mav.mav.mission_item_int_encode(
target_system,
target_component,
0, # seq
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
0, # current
0, # autocontinue
3, # p1
0, # p2
0, # p3
0, # p4
int(1.0000 * 1e7), # latitude
int(1.0000 * 1e7), # longitude
31.0000, # altitude
mavutil.mavlink.MAV_MISSION_TYPE_MISSION),
self.mav.mav.mission_item_int_encode(
target_system,
target_component,
1, # seq
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
0, # current
0, # autocontinue
3, # p1
0, # p2
0, # p3
0, # p4
int(1.0000 * 1e7), # latitude
int(1.0000 * 1e7), # longitude
31.0000, # altitude
mavutil.mavlink.MAV_MISSION_TYPE_MISSION),
self.mav.mav.mission_item_int_encode(
target_system,
target_component,
2, # seq
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
0, # current
0, # autocontinue
3, # p1
0, # p2
0, # p3
0, # p4
int(1.0000 * 1e7), # latitude
int(1.0000 * 1e7), # longitude
31.0000, # altitude
mavutil.mavlink.MAV_MISSION_TYPE_MISSION),
])
def MAV_CMD_DO_SET_MISSION_CURRENT(self, target_sysid=None, target_compid=1):
if target_sysid is None:
target_sysid = self.sysid_thismav()
self.check_mission_upload_download(self.MAV_CMD_DO_SET_MISSION_CURRENT_mission())
self.set_current_waypoint(2)
self.set_current_waypoint_using_mav_cmd_do_set_mission_current(2)
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT,
17,
0,
0,
0,
0,
0,
0,
timeout=1,
target_sysid=target_sysid,
target_compid=target_compid,
want_result=mavutil.mavlink.MAV_RESULT_FAILED)
def tests(self):
'''return list of all tests'''
ret = super(AutoTestRover, self).tests()
@ -5668,6 +5742,10 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
"Test handling of SET_POSITION_TARGET_LOCAL_NED",
self.SET_POSITION_TARGET_LOCAL_NED),
("MAV_CMD_DO_SET_MISSION_CURRENT",
"Test handling of CMD_DO_SET_MISSION_CURRENT",
self.MAV_CMD_DO_SET_MISSION_CURRENT),
("Button",
"Test Buttons",
self.test_button),