autotest: use named parameters for send_cmd and run_cmd

This commit is contained in:
Peter Barker 2023-07-15 22:40:01 +10:00 committed by Peter Barker
parent 85eeffcbc3
commit bde43f167e
4 changed files with 107 additions and 179 deletions

View File

@ -122,27 +122,21 @@ class AutoTestTracker(AutoTest):
# magically changes to SERVOTEST (3) # magically changes to SERVOTEST (3)
for value in 1900, 1200: for value in 1900, 1200:
channel = 1 channel = 1
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, self.run_cmd(
channel, mavutil.mavlink.MAV_CMD_DO_SET_SERVO,
value, p1=channel,
0, p2=value,
0, timeout=1,
0, )
0,
0,
timeout=1)
self.wait_servo_channel_value(channel, value) self.wait_servo_channel_value(channel, value)
for value in 1300, 1670: for value in 1300, 1670:
channel = 2 channel = 2
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, self.run_cmd(
channel, mavutil.mavlink.MAV_CMD_DO_SET_SERVO,
value, p1=channel,
0, p2=value,
0, timeout=1,
0, )
0,
0,
timeout=1)
self.wait_servo_channel_value(channel, value) self.wait_servo_channel_value(channel, value)
def SCAN(self): def SCAN(self):

View File

@ -567,13 +567,9 @@ class AutoTestPlane(AutoTest):
new_alt = 100 new_alt = 100
self.run_cmd_int( self.run_cmd_int(
mavutil.mavlink.MAV_CMD_DO_REPOSITION, mavutil.mavlink.MAV_CMD_DO_REPOSITION,
0, p5=int(loc.lat * 1e7),
0, p6=int(loc.lng * 1e7),
0, p7=new_alt, # alt
0,
int(loc.lat * 1e7),
int(loc.lng * 1e7),
new_alt, # alt
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
) )
self.wait_altitude(new_alt-10, new_alt, timeout=30, relative=True) self.wait_altitude(new_alt-10, new_alt, timeout=30, relative=True)
@ -596,13 +592,12 @@ class AutoTestPlane(AutoTest):
self.progress("set new position with GPS") self.progress("set new position with GPS")
self.run_cmd_int( self.run_cmd_int(
mavutil.mavlink.MAV_CMD_EXTERNAL_POSITION_ESTIMATE, mavutil.mavlink.MAV_CMD_EXTERNAL_POSITION_ESTIMATE,
self.get_sim_time()-1, # transmit time p1=self.get_sim_time()-1, # transmit time
0.5, # processing delay p2=0.5, # processing delay
50, # accuracy p3=50, # accuracy
0, p5=int(loc.lat * 1e7),
int(loc.lat * 1e7), p6=int(loc.lng * 1e7),
int(loc.lng * 1e7), p7=float("NaN"), # alt
float("NaN"), # alt
frame=mavutil.mavlink.MAV_FRAME_GLOBAL, frame=mavutil.mavlink.MAV_FRAME_GLOBAL,
want_result=mavutil.mavlink.MAV_RESULT_FAILED, want_result=mavutil.mavlink.MAV_RESULT_FAILED,
) )
@ -631,13 +626,12 @@ class AutoTestPlane(AutoTest):
self.progress("set new position with no GPS") self.progress("set new position with no GPS")
self.run_cmd_int( self.run_cmd_int(
mavutil.mavlink.MAV_CMD_EXTERNAL_POSITION_ESTIMATE, mavutil.mavlink.MAV_CMD_EXTERNAL_POSITION_ESTIMATE,
self.get_sim_time()-1, # transmit time p1=self.get_sim_time()-1, # transmit time
0.5, # processing delay p2=0.5, # processing delay
50, # accuracy p3=50, # accuracy
0, p5=gpi.lat+1,
gpi.lat+1, p6=gpi.lon+1,
gpi.lon+1, p7=float("NaN"), # alt
float("NaN"), # alt
frame=mavutil.mavlink.MAV_FRAME_GLOBAL, frame=mavutil.mavlink.MAV_FRAME_GLOBAL,
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED
) )
@ -820,13 +814,9 @@ class AutoTestPlane(AutoTest):
self.change_mode("GUIDED") self.change_mode("GUIDED")
self.run_cmd_int( self.run_cmd_int(
mavutil.mavlink.MAV_CMD_DO_REPOSITION, mavutil.mavlink.MAV_CMD_DO_REPOSITION,
0, p5=12345, # lat* 1e7
0, p6=12345, # lon* 1e7
0, p7=100 # alt
0,
12345, # lat* 1e7
12345, # lon* 1e7
100 # alt
) )
self.delay_sim_time(10) self.delay_sim_time(10)
self.progress("Ensuring initial speed is known and relatively constant") self.progress("Ensuring initial speed is known and relatively constant")
@ -838,13 +828,11 @@ class AutoTestPlane(AutoTest):
new_target_groundspeed = initial_speed + 5 new_target_groundspeed = initial_speed + 5
self.run_cmd( self.run_cmd(
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
1, # groundspeed p1=1, # groundspeed
new_target_groundspeed, p2=new_target_groundspeed,
-1, # throttle / no change p3=-1, # throttle / no change
0, # absolute values p4=0, # absolute values
0, )
0,
0)
self.wait_groundspeed(new_target_groundspeed-0.5, new_target_groundspeed+0.5, timeout=40) self.wait_groundspeed(new_target_groundspeed-0.5, new_target_groundspeed+0.5, timeout=40)
self.progress("Adding some wind, ensuring groundspeed holds") self.progress("Adding some wind, ensuring groundspeed holds")
self.set_parameter("SIM_WIND_SPD", 5) self.set_parameter("SIM_WIND_SPD", 5)
@ -855,25 +843,21 @@ class AutoTestPlane(AutoTest):
# clear target groundspeed # clear target groundspeed
self.run_cmd( self.run_cmd(
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
1, # groundspeed p1=1, # groundspeed
0, p2=0,
-1, # throttle / no change p3=-1, # throttle / no change
0, # absolute values p4=0, # absolute values
0, )
0,
0)
self.progress("Setting airspeed") self.progress("Setting airspeed")
new_target_airspeed = initial_speed + 5 new_target_airspeed = initial_speed + 5
self.run_cmd( self.run_cmd(
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
0, # airspeed p1=0, # airspeed
new_target_airspeed, p2=new_target_airspeed,
-1, # throttle / no change p3=-1, # throttle / no change
0, # absolute values p4=0, # absolute values
0, )
0,
0)
self.wait_airspeed(new_target_airspeed-0.5, new_target_airspeed+0.5) self.wait_airspeed(new_target_airspeed-0.5, new_target_airspeed+0.5)
self.progress("Adding some wind, hoping groundspeed increases/decreases") self.progress("Adding some wind, hoping groundspeed increases/decreases")
self.set_parameters({ self.set_parameters({
@ -2008,13 +1992,11 @@ class AutoTestPlane(AutoTest):
self.location_offset_ne(loc, 500, 500) self.location_offset_ne(loc, 500, 500)
self.run_cmd_int( self.run_cmd_int(
mavutil.mavlink.MAV_CMD_DO_REPOSITION, mavutil.mavlink.MAV_CMD_DO_REPOSITION,
0, p1=0,
mavutil.mavlink.MAV_DO_REPOSITION_FLAGS_CHANGE_MODE, p2=mavutil.mavlink.MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
0, p5=int(loc.lat * 1e7),
0, p6=int(loc.lng * 1e7),
int(loc.lat * 1e7), p7=100, # alt
int(loc.lng * 1e7),
100, # alt
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
) )
self.wait_location(loc, accuracy=100) self.wait_location(loc, accuracy=100)
@ -2946,9 +2928,11 @@ class AutoTestPlane(AutoTest):
self.reboot_sitl() self.reboot_sitl()
self.delay_sim_time(5) self.delay_sim_time(5)
self.progress("Running accelcal") self.progress("Running accelcal")
self.run_cmd(mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, self.run_cmd(
0, 0, 0, 0, 4, 0, 0, mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
timeout=5) p5=4,
timeout=5,
)
self.wait_ready_to_arm() self.wait_ready_to_arm()
self.arm_vehicle() self.arm_vehicle()
@ -3107,13 +3091,17 @@ class AutoTestPlane(AutoTest):
self.set_parameter("SIM_IMUT_FIXED", 12) self.set_parameter("SIM_IMUT_FIXED", 12)
self.progress("Running accel cal") self.progress("Running accel cal")
self.run_cmd(mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, self.run_cmd(
0, 0, 0, 0, 4, 0, 0, mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
timeout=5) p5=4,
timeout=5,
)
self.progress("Running gyro cal") self.progress("Running gyro cal")
self.run_cmd(mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, self.run_cmd(
0, 0, 0, 0, 1, 0, 0, mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
timeout=5) p5=1,
timeout=5,
)
self.set_parameters({ self.set_parameters({
"SIM_IMUT_FIXED": 0, "SIM_IMUT_FIXED": 0,
"INS_TCAL1_ENABLE": 2, "INS_TCAL1_ENABLE": 2,
@ -3353,13 +3341,9 @@ class AutoTestPlane(AutoTest):
loc = self.mav.location() loc = self.mav.location()
self.run_cmd_int( self.run_cmd_int(
mavutil.mavlink.MAV_CMD_DO_REPOSITION, mavutil.mavlink.MAV_CMD_DO_REPOSITION,
0, p5=int(loc.lat * 1e7),
0, p6=int(loc.lng * 1e7),
0, p7=50, # alt
0,
int(loc.lat * 1e7),
int(loc.lng * 1e7),
50 # alt
) )
self.delay_sim_time(5) self.delay_sim_time(5)
# create an airspeed sensor error by freezing to the # create an airspeed sensor error by freezing to the
@ -3370,13 +3354,10 @@ class AutoTestPlane(AutoTest):
self.set_parameter("SIM_ARSPD_FAIL", m.airspeed) self.set_parameter("SIM_ARSPD_FAIL", m.airspeed)
self.run_cmd( self.run_cmd(
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
0, # airspeed p1=0, # airspeed
30, p2=30,
-1, # throttle / no change p3=-1, # throttle / no change
0, # absolute values p4=0, # absolute values
0,
0,
0
) )
self.wait_statustext(text="EKF3 lane switch", timeout=30, the_function=fail_speed, check_context=True) self.wait_statustext(text="EKF3 lane switch", timeout=30, the_function=fail_speed, check_context=True)
if self.lane_switches != [1, 0, 1, 0, 1]: if self.lane_switches != [1, 0, 1, 0, 1]:
@ -3797,13 +3778,9 @@ class AutoTestPlane(AutoTest):
new_home.altitude = new_home.altitude + 300000 # 300 metres new_home.altitude = new_home.altitude + 300000 # 300 metres
self.run_cmd_int( self.run_cmd_int(
mavutil.mavlink.MAV_CMD_DO_SET_HOME, mavutil.mavlink.MAV_CMD_DO_SET_HOME,
0, # p1, p5=new_home.latitude,
0, # p2, p6=new_home.longitude,
0, # p3, p7=new_home.altitude/1000.0, # mm => m
0, # p4,
new_home.latitude,
new_home.longitude,
new_home.altitude/1000.0, # mm => m
) )
old_bootcount = self.get_parameter('STAT_BOOTCNT') old_bootcount = self.get_parameter('STAT_BOOTCNT')
self.progress("Forcing watchdog reset") self.progress("Forcing watchdog reset")
@ -4463,25 +4440,13 @@ class AutoTestPlane(AutoTest):
self.progress("Checking incorrect tag behaviour") self.progress("Checking incorrect tag behaviour")
self.run_cmd( self.run_cmd(
mavutil.mavlink.MAV_CMD_DO_JUMP_TAG, mavutil.mavlink.MAV_CMD_DO_JUMP_TAG,
jump_target + 1, # p1 p1=jump_target + 1,
0, # p2
0, # p3
0, # p4
0, # p5
0, # p6
0, # p7
want_result=mavutil.mavlink.MAV_RESULT_FAILED want_result=mavutil.mavlink.MAV_RESULT_FAILED
) )
self.progress("Checking correct tag behaviour") self.progress("Checking correct tag behaviour")
self.run_cmd( self.run_cmd(
mavutil.mavlink.MAV_CMD_DO_JUMP_TAG, mavutil.mavlink.MAV_CMD_DO_JUMP_TAG,
jump_target, # p1 p1=jump_target,
0, # p2
0, # p3
0, # p4
0, # p5
0, # p6
0, # p7
) )
self.assert_current_waypoint(4) self.assert_current_waypoint(4)
@ -4519,13 +4484,7 @@ class AutoTestPlane(AutoTest):
self.arm_vehicle() self.arm_vehicle()
self.run_cmd( self.run_cmd(
mavutil.mavlink.MAV_CMD_DO_JUMP_TAG, mavutil.mavlink.MAV_CMD_DO_JUMP_TAG,
17, # p1 p1=17,
0, # p2
0, # p3
0, # p4
0, # p5
0, # p6
0, # p7
want_result=mavutil.mavlink.MAV_RESULT_FAILED want_result=mavutil.mavlink.MAV_RESULT_FAILED
) )
self.disarm_vehicle() self.disarm_vehicle()
@ -4569,8 +4528,10 @@ class AutoTestPlane(AutoTest):
# reboot to clear potentially bad state # reboot to clear potentially bad state
def trigger_airspeed_cal(self): def trigger_airspeed_cal(self):
self.run_cmd(mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, self.run_cmd(
0, 0, 1, 0, 0, 0, 0) mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
p3=1,
)
def AirspeedCal(self): def AirspeedCal(self):
'''test Airspeed calibration''' '''test Airspeed calibration'''

View File

@ -375,15 +375,11 @@ class AutoTestSub(AutoTest):
"""Reboot SITL instance and wait it to reconnect.""" """Reboot SITL instance and wait it to reconnect."""
# out battery is reset to full on reboot. So reduce it to 10% # out battery is reset to full on reboot. So reduce it to 10%
# and wait for it to go above 50. # and wait for it to go above 50.
self.run_cmd(mavutil.mavlink.MAV_CMD_BATTERY_RESET, self.run_cmd(
255, # battery mask mavutil.mavlink.MAV_CMD_BATTERY_RESET,
10, # percentage p1=255, # battery mask
0, p2=10, # percentage
0, )
0,
0,
0,
0)
self.run_cmd_reboot() self.run_cmd_reboot()
tstart = time.time() tstart = time.time()
while True: while True:
@ -392,14 +388,10 @@ class AutoTestSub(AutoTest):
# ask for the message: # ask for the message:
batt = None batt = None
try: try:
self.send_cmd(mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE, self.send_cmd(
mavutil.mavlink.MAVLINK_MSG_ID_BATTERY_STATUS, mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE,
0, p1=mavutil.mavlink.MAVLINK_MSG_ID_BATTERY_STATUS,
0, )
0,
0,
0,
0)
batt = self.mav.recv_match(type='BATTERY_STATUS', batt = self.mav.recv_match(type='BATTERY_STATUS',
blocking=True, blocking=True,
timeout=1) timeout=1)

View File

@ -320,27 +320,13 @@ class AutoTestRover(AutoTest):
self.start_subtest("Checking mavlink commands") self.start_subtest("Checking mavlink commands")
self.change_mode("MANUAL") self.change_mode("MANUAL")
self.progress("Starting Sprayer") self.progress("Starting Sprayer")
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER, self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER, p1=1)
1, # p1
0, # p2
0, # p3
0, # p4
0, # p5
0, # p6
0) # p7
self.progress("Testing speed-ramping") self.progress("Testing speed-ramping")
self.set_rc(3, 1700) # start driving forward self.set_rc(3, 1700) # start driving forward
self.wait_servo_channel_value(pump_ch, 1690, timeout=60, comparator=operator.gt) self.wait_servo_channel_value(pump_ch, 1690, timeout=60, comparator=operator.gt)
self.start_subtest("Stopping Sprayer") self.start_subtest("Stopping Sprayer")
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER, self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER, p1=0)
0, # p1
0, # p2
0, # p3
0, # p4
0, # p5
0, # p6
0) # p7
self.wait_servo_channel_value(pump_ch, pump_ch_min) self.wait_servo_channel_value(pump_ch, pump_ch_min)
self.set_rc(3, 1000) # start driving forward self.set_rc(3, 1000) # start driving forward
@ -4773,13 +4759,12 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.wait_ready_to_arm() self.wait_ready_to_arm()
self.run_cmd( self.run_cmd(
mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST, mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST,
1, # p1 - motor instance p1=1, # motor instance
mavutil.mavlink.MOTOR_TEST_THROTTLE_PWM, # p2 - throttle type p2=mavutil.mavlink.MOTOR_TEST_THROTTLE_PWM, # throttle type
magic_throttle_value, # p3 - throttle p3=magic_throttle_value, # throttle
5, # p4 - timeout p4=5, # timeout
1, # p5 - motor count p5=1, # motor count
0, # p6 - test order (see MOTOR_TEST_ORDER) p6=0, # test order (see MOTOR_TEST_ORDER)
0, # p7
) )
self.wait_armed() self.wait_armed()
self.progress("Waiting for magic throttle value") self.progress("Waiting for magic throttle value")
@ -5929,18 +5914,14 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.set_current_waypoint_using_mav_cmd_do_set_mission_current(2) self.set_current_waypoint_using_mav_cmd_do_set_mission_current(2)
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT, self.run_cmd(
17, mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT,
0, p1=17,
0, timeout=1,
0, target_sysid=target_sysid,
0, target_compid=target_compid,
0, want_result=mavutil.mavlink.MAV_RESULT_FAILED,
0, )
timeout=1,
target_sysid=target_sysid,
target_compid=target_compid,
want_result=mavutil.mavlink.MAV_RESULT_FAILED)
def FlashStorage(self): def FlashStorage(self):
'''Test flash storage (for parameters etc)''' '''Test flash storage (for parameters etc)'''