mirror of https://github.com/ArduPilot/ardupilot
autotest: use named parameters for send_cmd and run_cmd
most commands don't use all the parameters. Counting through these was painful.
This commit is contained in:
parent
277d16831d
commit
d69ba376ad
|
@ -125,15 +125,10 @@ class AutoTestCopter(AutoTest):
|
|||
|
||||
def user_takeoff(self, alt_min=30, timeout=30, max_err=5):
|
||||
'''takeoff using mavlink takeoff command'''
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
|
||||
0, # param1
|
||||
0, # param2
|
||||
0, # param3
|
||||
0, # param4
|
||||
0, # param5
|
||||
0, # param6
|
||||
alt_min # param7
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
|
||||
p7=alt_min,
|
||||
)
|
||||
self.wait_for_alt(alt_min, timeout=timeout, max_err=max_err)
|
||||
|
||||
def takeoff(self,
|
||||
|
@ -1138,7 +1133,10 @@ class AutoTestCopter(AutoTest):
|
|||
self.context_collect('STATUSTEXT')
|
||||
self.arm_vehicle()
|
||||
if user_takeoff:
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 0, 0, 0, 0, 10)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
|
||||
p7=10,
|
||||
)
|
||||
else:
|
||||
self.set_rc(3, 1700)
|
||||
# we may never see ourselves as armed in a heartbeat
|
||||
|
@ -2664,16 +2662,12 @@ class AutoTestCopter(AutoTest):
|
|||
raise NotAchievedException("Failed ordering for requested CASE:", case)
|
||||
if len(case[4]):
|
||||
self.context_collect('STATUSTEXT')
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
1, # ARM
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
timeout=10,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
p1=1, # ARM
|
||||
timeout=10,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
|
||||
)
|
||||
self.wait_statustext(case[4], check_context=True)
|
||||
self.context_stop_collecting('STATUSTEXT')
|
||||
self.progress("############################### All GPS Order Cases Tests Passed")
|
||||
|
@ -2685,16 +2679,12 @@ class AutoTestCopter(AutoTest):
|
|||
self.start_sup_program(instance=1, args="-M")
|
||||
self.delay_sim_time(2)
|
||||
self.context_collect('STATUSTEXT')
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
1, # ARM
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
timeout=10,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
p1=1, # ARM
|
||||
timeout=10,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
|
||||
)
|
||||
self.wait_statustext(".*Node .* unhealthy", check_context=True, regex=True)
|
||||
self.stop_sup_program(instance=0)
|
||||
self.start_sup_program(instance=0)
|
||||
|
@ -3647,14 +3637,10 @@ class AutoTestCopter(AutoTest):
|
|||
|
||||
self.progress("Test triggering with mavlink message")
|
||||
self.takeoff(20)
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_PARACHUTE,
|
||||
2, # release
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_PARACHUTE,
|
||||
p1=2, # release
|
||||
)
|
||||
self.wait_statustext('BANG', timeout=60)
|
||||
self.disarm_vehicle(force=True)
|
||||
self.reboot_sitl()
|
||||
|
@ -3672,15 +3658,10 @@ class AutoTestCopter(AutoTest):
|
|||
|
||||
self.progress("Test mavlink triggering")
|
||||
self.takeoff(20)
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_PARACHUTE,
|
||||
mavutil.mavlink.PARACHUTE_DISABLE, # param1
|
||||
0, # param2
|
||||
0, # param3
|
||||
0, # param4
|
||||
0, # param5
|
||||
0, # param6
|
||||
0 # param7
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_PARACHUTE,
|
||||
p1=mavutil.mavlink.PARACHUTE_DISABLE,
|
||||
)
|
||||
ok = False
|
||||
try:
|
||||
self.wait_statustext('BANG', timeout=2)
|
||||
|
@ -3688,15 +3669,10 @@ class AutoTestCopter(AutoTest):
|
|||
ok = True
|
||||
if not ok:
|
||||
raise NotAchievedException("Disabled parachute fired")
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_PARACHUTE,
|
||||
mavutil.mavlink.PARACHUTE_ENABLE, # param1
|
||||
0, # param2
|
||||
0, # param3
|
||||
0, # param4
|
||||
0, # param5
|
||||
0, # param6
|
||||
0 # param7
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_PARACHUTE,
|
||||
p1=mavutil.mavlink.PARACHUTE_ENABLE,
|
||||
)
|
||||
ok = False
|
||||
try:
|
||||
self.wait_statustext('BANG', timeout=2)
|
||||
|
@ -3711,15 +3687,10 @@ class AutoTestCopter(AutoTest):
|
|||
|
||||
# parachute should not fire if you go from disabled to release:
|
||||
self.takeoff(20)
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_PARACHUTE,
|
||||
mavutil.mavlink.PARACHUTE_RELEASE,
|
||||
0, # param2
|
||||
0, # param3
|
||||
0, # param4
|
||||
0, # param5
|
||||
0, # param6
|
||||
0 # param7
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_PARACHUTE,
|
||||
p1=mavutil.mavlink.PARACHUTE_RELEASE,
|
||||
)
|
||||
ok = False
|
||||
try:
|
||||
self.wait_statustext('BANG', timeout=2)
|
||||
|
@ -3729,24 +3700,14 @@ class AutoTestCopter(AutoTest):
|
|||
raise NotAchievedException("Parachute fired when going straight from disabled to release")
|
||||
|
||||
# now enable then release parachute:
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_PARACHUTE,
|
||||
mavutil.mavlink.PARACHUTE_ENABLE, # param1
|
||||
0, # param2
|
||||
0, # param3
|
||||
0, # param4
|
||||
0, # param5
|
||||
0, # param6
|
||||
0 # param7
|
||||
)
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_PARACHUTE,
|
||||
mavutil.mavlink.PARACHUTE_RELEASE,
|
||||
0, # param2
|
||||
0, # param3
|
||||
0, # param4
|
||||
0, # param5
|
||||
0, # param6
|
||||
0 # param7
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_PARACHUTE,
|
||||
p1=mavutil.mavlink.PARACHUTE_ENABLE,
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_PARACHUTE,
|
||||
p1=mavutil.mavlink.PARACHUTE_RELEASE,
|
||||
)
|
||||
self.wait_statustext('BANG! Parachute deployed', timeout=2)
|
||||
self.disarm_vehicle(force=True)
|
||||
self.reboot_sitl()
|
||||
|
@ -3793,15 +3754,16 @@ class AutoTestCopter(AutoTest):
|
|||
# default frame is "+" - start motor of 2 is "B", which is
|
||||
# motor 1... see
|
||||
# https://ardupilot.org/copter/docs/connect-escs-and-motors.html
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST,
|
||||
2, # start motor
|
||||
mavutil.mavlink.MOTOR_TEST_THROTTLE_PWM,
|
||||
pwm_in, # pwm-to-output
|
||||
2, # timeout in seconds
|
||||
2, # number of motors to output
|
||||
0, # compass learning
|
||||
0,
|
||||
timeout=timeout)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST,
|
||||
p1=2, # start motor
|
||||
p2=mavutil.mavlink.MOTOR_TEST_THROTTLE_PWM,
|
||||
p3=pwm_in, # pwm-to-output
|
||||
p4=2, # timeout in seconds
|
||||
p5=2, # number of motors to output
|
||||
p6=0, # compass learning
|
||||
timeout=timeout,
|
||||
)
|
||||
# long timeouts here because there's a pause before we start motors
|
||||
self.wait_servo_channel_value(1, pwm_in, timeout=10)
|
||||
self.wait_servo_channel_value(4, pwm_in, timeout=10)
|
||||
|
@ -3814,15 +3776,16 @@ class AutoTestCopter(AutoTest):
|
|||
# min/max are used.
|
||||
expected_pwm = 1000 + (self.get_parameter("RC3_MAX") - self.get_parameter("RC3_MIN")) * percentage/100.0
|
||||
self.progress("expected pwm=%f" % expected_pwm)
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST,
|
||||
2, # start motor
|
||||
mavutil.mavlink.MOTOR_TEST_THROTTLE_PERCENT,
|
||||
percentage, # pwm-to-output
|
||||
2, # timeout in seconds
|
||||
2, # number of motors to output
|
||||
0, # compass learning
|
||||
0,
|
||||
timeout=timeout)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST,
|
||||
p1=2, # start motor
|
||||
p2=mavutil.mavlink.MOTOR_TEST_THROTTLE_PERCENT,
|
||||
p3=percentage, # pwm-to-output
|
||||
p4=2, # timeout in seconds
|
||||
p5=2, # number of motors to output
|
||||
p6=0, # compass learning
|
||||
timeout=timeout,
|
||||
)
|
||||
self.wait_servo_channel_value(1, expected_pwm, timeout=10)
|
||||
self.wait_servo_channel_value(4, expected_pwm, timeout=10)
|
||||
self.wait_statustext("finished motor test")
|
||||
|
@ -4832,15 +4795,10 @@ class AutoTestCopter(AutoTest):
|
|||
self.progress("Check setting an invalid mode")
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_SET_MODE,
|
||||
mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
|
||||
126,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
p1=mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
|
||||
p2=126,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
|
||||
timeout=1
|
||||
timeout=1,
|
||||
)
|
||||
self.set_rc(3, 1000)
|
||||
self.run_cmd_do_set_mode("ACRO")
|
||||
|
@ -4889,14 +4847,12 @@ class AutoTestCopter(AutoTest):
|
|||
'''yaw aircraft in guided/rate mode'''
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_CONDITION_YAW,
|
||||
60, # target angle
|
||||
0, # degrees/second
|
||||
1, # -1 is counter-clockwise, 1 clockwise
|
||||
1, # 1 for relative, 0 for absolute
|
||||
0, # p5
|
||||
0, # p6
|
||||
0, # p7
|
||||
quiet=True)
|
||||
p1=60, # target angle
|
||||
p2=0, # degrees/second
|
||||
p3=1, # -1 is counter-clockwise, 1 clockwise
|
||||
p4=1, # 1 for relative, 0 for absolute
|
||||
quiet=True,
|
||||
)
|
||||
|
||||
def setup_servo_mount(self, roll_servo=5, pitch_servo=6, yaw_servo=7):
|
||||
'''configure a rpy servo mount; caller responsible for required rebooting'''
|
||||
|
@ -4923,11 +4879,12 @@ class AutoTestCopter(AutoTest):
|
|||
|
||||
def set_mount_mode(self, mount_mode):
|
||||
'''set mount mode'''
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_MOUNT_CONFIGURE,
|
||||
mount_mode,
|
||||
0, # stabilize roll (unsupported)
|
||||
0, # stabilize pitch (unsupported)
|
||||
0, 0, 0, 0)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_MOUNT_CONFIGURE,
|
||||
p1=mount_mode,
|
||||
p2=0, # stabilize roll (unsupported)
|
||||
p3=0, # stabilize pitch (unsupported)
|
||||
)
|
||||
|
||||
def Mount(self):
|
||||
'''Test Camera/Antenna Mount'''
|
||||
|
@ -4993,14 +4950,16 @@ class AutoTestCopter(AutoTest):
|
|||
self.do_pitch(0) # level vehicle
|
||||
self.wait_pitch(0, despitch_tolerance)
|
||||
self.set_mount_mode(mavutil.mavlink.MAV_MOUNT_MODE_MAVLINK_TARGETING)
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW,
|
||||
-20, # pitch angle in degrees
|
||||
0, # yaw angle in degrees
|
||||
0, # pitch rate in degrees (NaN to ignore)
|
||||
0, # yaw rate in degrees (NaN to ignore)
|
||||
0, # flags (0=Body-frame, 16/GIMBAL_MANAGER_FLAGS_YAW_LOCK=Earth Frame)
|
||||
0, # unused
|
||||
0) # gimbal id
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW,
|
||||
p1=-20, # pitch angle in degrees
|
||||
p2=0, # yaw angle in degrees
|
||||
p3=0, # pitch rate in degrees (NaN to ignore)
|
||||
p4=0, # yaw rate in degrees (NaN to ignore)
|
||||
p5=0, # flags (0=Body-frame, 16/GIMBAL_MANAGER_FLAGS_YAW_LOCK=Earth Frame)
|
||||
p6=0, # unused
|
||||
p7=0, # gimbal id
|
||||
)
|
||||
self.test_mount_pitch(-20, 1, mavutil.mavlink.MAV_MOUNT_MODE_MAVLINK_TARGETING)
|
||||
|
||||
# point gimbal at specified location
|
||||
|
@ -5144,53 +5103,34 @@ class AutoTestCopter(AutoTest):
|
|||
20)
|
||||
roi_alt = 0
|
||||
self.progress("Using MAV_CMD_DO_SET_ROI_LOCATION")
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_ROI_LOCATION,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
roi_lat,
|
||||
roi_lon,
|
||||
roi_alt,
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_SET_ROI_LOCATION,
|
||||
p5=roi_lat,
|
||||
p6=roi_lon,
|
||||
p7=roi_alt,
|
||||
)
|
||||
self.test_mount_pitch(-52, 5, mavutil.mavlink.MAV_MOUNT_MODE_GPS_POINT)
|
||||
self.progress("Using MAV_CMD_DO_SET_ROI_LOCATION")
|
||||
# start by pointing the gimbal elsewhere with a
|
||||
# known-working command:
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_SET_ROI_LOCATION,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
roi_lat + 1,
|
||||
roi_lon + 1,
|
||||
roi_alt,
|
||||
p5=roi_lat + 1,
|
||||
p6=roi_lon + 1,
|
||||
p7=roi_alt,
|
||||
)
|
||||
# now point it with command_int:
|
||||
self.run_cmd_int(
|
||||
mavutil.mavlink.MAV_CMD_DO_SET_ROI_LOCATION,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
int(roi_lat * 1e7),
|
||||
int(roi_lon * 1e7),
|
||||
roi_alt,
|
||||
p5=int(roi_lat * 1e7),
|
||||
p6=int(roi_lon * 1e7),
|
||||
p7=roi_alt,
|
||||
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
|
||||
)
|
||||
self.test_mount_pitch(-52, 5, mavutil.mavlink.MAV_MOUNT_MODE_GPS_POINT)
|
||||
|
||||
self.progress("Using MAV_CMD_DO_SET_ROI_NONE")
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_ROI_NONE,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
)
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_ROI_NONE)
|
||||
self.test_mount_pitch(0, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING)
|
||||
|
||||
start = self.mav.location()
|
||||
|
@ -5200,15 +5140,12 @@ class AutoTestCopter(AutoTest):
|
|||
-200)
|
||||
roi_alt = 0
|
||||
self.progress("Using MAV_CMD_DO_SET_ROI")
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_ROI,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
roi_lat,
|
||||
roi_lon,
|
||||
roi_alt,
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_SET_ROI,
|
||||
p5=roi_lat,
|
||||
p6=roi_lon,
|
||||
p7=roi_alt,
|
||||
)
|
||||
self.test_mount_pitch(-7.5, 1, mavutil.mavlink.MAV_MOUNT_MODE_GPS_POINT)
|
||||
|
||||
start = self.mav.location()
|
||||
|
@ -5258,15 +5195,10 @@ class AutoTestCopter(AutoTest):
|
|||
20)
|
||||
roi_alt = 0
|
||||
self.progress("Using MAV_CMD_DO_SET_ROI_SYSID")
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_ROI_SYSID,
|
||||
self.mav.source_system,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_SET_ROI_SYSID,
|
||||
p1=self.mav.source_system,
|
||||
)
|
||||
self.mav.mav.global_position_int_send(
|
||||
0, # time boot ms
|
||||
int(roi_lat * 1e7),
|
||||
|
@ -5338,15 +5270,12 @@ class AutoTestCopter(AutoTest):
|
|||
-100)
|
||||
roi_alt = 0
|
||||
self.progress("Using MAV_CMD_DO_SET_ROI")
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_ROI,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
roi_lat,
|
||||
roi_lon,
|
||||
roi_alt,
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_SET_ROI,
|
||||
p5=roi_lat,
|
||||
p6=roi_lon,
|
||||
p7=roi_alt,
|
||||
)
|
||||
|
||||
self.progress("Waiting for vehicle to point towards ROI")
|
||||
self.wait_heading(225, timeout=600, minimum_duration=2)
|
||||
|
@ -5380,15 +5309,12 @@ class AutoTestCopter(AutoTest):
|
|||
bearing = self.bearing_to(there)
|
||||
self.wait_heading(bearing, timeout=600, minimum_duration=2)
|
||||
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_ROI,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
roi_lat,
|
||||
roi_lon,
|
||||
roi_alt,
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_SET_ROI,
|
||||
p5=roi_lat,
|
||||
p6=roi_lon,
|
||||
p7=roi_alt,
|
||||
)
|
||||
|
||||
self.progress("Wait for vehicle to point sssse due to moving")
|
||||
self.wait_heading(170, timeout=600, minimum_duration=1)
|
||||
|
@ -7697,13 +7623,7 @@ class AutoTestCopter(AutoTest):
|
|||
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_AIRFRAME_CONFIGURATION,
|
||||
0,
|
||||
0, # deploy
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0
|
||||
p2=0, # deploy
|
||||
)
|
||||
|
||||
self.context_collect("STATUSTEXT")
|
||||
|
@ -8749,13 +8669,10 @@ class AutoTestCopter(AutoTest):
|
|||
target = initial_heading
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_CONDITION_YAW,
|
||||
target, # target angle
|
||||
10, # degrees/second
|
||||
1, # -1 is counter-clockwise, 1 clockwise
|
||||
0, # 1 for relative, 0 for absolute
|
||||
0, # p5
|
||||
0, # p6
|
||||
0, # p7
|
||||
p1=target, # target angle
|
||||
p2=10, # degrees/second
|
||||
p3=1, # -1 is counter-clockwise, 1 clockwise
|
||||
p4=0, # 1 for relative, 0 for absolute
|
||||
)
|
||||
self.wait_heading(target, minimum_duration=2, timeout=50)
|
||||
|
||||
|
@ -8773,13 +8690,10 @@ class AutoTestCopter(AutoTest):
|
|||
part_way_target = initial_heading + 10
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_CONDITION_YAW,
|
||||
target, # target angle
|
||||
degsecond, # degrees/second
|
||||
1, # -1 is counter-clockwise, 1 clockwise
|
||||
0, # 1 for relative, 0 for absolute
|
||||
0, # p5
|
||||
0, # p6
|
||||
0, # p7
|
||||
p1=target, # target angle
|
||||
p2=degsecond, # degrees/second
|
||||
p3=1, # -1 is counter-clockwise, 1 clockwise
|
||||
p4=0, # 1 for relative, 0 for absolute
|
||||
)
|
||||
self.wait_heading(part_way_target)
|
||||
self.wait_heading(target, minimum_duration=2)
|
||||
|
@ -8789,13 +8703,10 @@ class AutoTestCopter(AutoTest):
|
|||
part_way_target = initial_heading + 30
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_CONDITION_YAW,
|
||||
target, # target angle
|
||||
degsecond, # degrees/second
|
||||
-1, # -1 is counter-clockwise, 1 clockwise
|
||||
0, # 1 for relative, 0 for absolute
|
||||
0, # p5
|
||||
0, # p6
|
||||
0, # p7
|
||||
p1=target, # target angle
|
||||
p2=degsecond, # degrees/second
|
||||
p3=-1, # -1 is counter-clockwise, 1 clockwise
|
||||
p4=0, # 1 for relative, 0 for absolute
|
||||
)
|
||||
self.wait_heading(part_way_target)
|
||||
self.wait_heading(target, minimum_duration=2)
|
||||
|
@ -9583,14 +9494,7 @@ class AutoTestCopter(AutoTest):
|
|||
|
||||
self.start_subtest("Checking mavlink commands")
|
||||
self.progress("Starting Sprayer")
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER,
|
||||
1, # p1
|
||||
0, # p2
|
||||
0, # p3
|
||||
0, # p4
|
||||
0, # p5
|
||||
0, # p6
|
||||
0) # p7
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER, p1=1)
|
||||
|
||||
self.progress("Testing speed-ramping")
|
||||
self.wait_servo_channel_value(
|
||||
|
@ -9601,14 +9505,8 @@ class AutoTestCopter(AutoTest):
|
|||
)
|
||||
|
||||
self.start_subtest("Stopping Sprayer")
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER,
|
||||
0, # p1
|
||||
0, # p2
|
||||
0, # p3
|
||||
0, # p4
|
||||
0, # p5
|
||||
0, # p6
|
||||
0) # p7
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER, p1=0)
|
||||
|
||||
self.wait_servo_channel_value(pump_ch, pump_ch_min)
|
||||
|
||||
self.context_pop()
|
||||
|
|
|
@ -1888,26 +1888,13 @@ class AutoTest(ABC):
|
|||
shutil.move(valgrind_log, backup_valgrind_log)
|
||||
|
||||
def run_cmd_reboot(self):
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,
|
||||
1, # confirmation
|
||||
1, # reboot autopilot
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,
|
||||
p1=1, # reboot autopilot
|
||||
)
|
||||
|
||||
def run_cmd_run_prearms(self):
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0)
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS)
|
||||
|
||||
def run_cmd_enable_high_latency(self, new_state):
|
||||
p1 = 0
|
||||
|
@ -1916,13 +1903,7 @@ class AutoTest(ABC):
|
|||
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_CONTROL_HIGH_LATENCY,
|
||||
p1, # p1 - enable/disable
|
||||
0, # p2
|
||||
0, # p3
|
||||
0, # p4
|
||||
0, # p5
|
||||
0, # p6
|
||||
0, # p7
|
||||
p1=p1, # enable/disable
|
||||
)
|
||||
|
||||
def reboot_sitl_mav(self, required_bootcount=None, force=False):
|
||||
|
@ -1962,13 +1943,10 @@ class AutoTest(ABC):
|
|||
p6 = 20190226 # magic force-reboot value
|
||||
self.send_cmd(
|
||||
mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,
|
||||
1,
|
||||
1,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
p6,
|
||||
0)
|
||||
p1=1,
|
||||
p2=1,
|
||||
p6=p6,
|
||||
)
|
||||
do_context = True
|
||||
if do_context:
|
||||
self.context_push()
|
||||
|
@ -2058,9 +2036,9 @@ class AutoTest(ABC):
|
|||
self.progress("Restarting Scripting")
|
||||
self.run_cmd_int(
|
||||
mavutil.mavlink.MAV_CMD_SCRIPTING,
|
||||
mavutil.mavlink.SCRIPTING_CMD_STOP_AND_RESTART,
|
||||
0, 0, 0, 0, 0, 0,
|
||||
timeout=5)
|
||||
p1=mavutil.mavlink.SCRIPTING_CMD_STOP_AND_RESTART,
|
||||
timeout=5,
|
||||
)
|
||||
|
||||
def set_streamrate(self, streamrate, timeout=20, stream=mavutil.mavlink.MAV_DATA_STREAM_ALL):
|
||||
'''set MAV_DATA_STREAM_ALL; timeout is wallclock time'''
|
||||
|
@ -3895,14 +3873,9 @@ class AutoTest(ABC):
|
|||
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_AUX_FUNCTION,
|
||||
function, # p1
|
||||
level, # p2
|
||||
0, # p3
|
||||
0, # p4
|
||||
0, # p5
|
||||
0, # p6
|
||||
0, # p7
|
||||
want_result=want_result
|
||||
p1=function,
|
||||
p2=level,
|
||||
want_result=want_result,
|
||||
)
|
||||
|
||||
def assert_mission_count(self, expected):
|
||||
|
@ -5074,24 +5047,13 @@ class AutoTest(ABC):
|
|||
return self.mav.motors_armed()
|
||||
|
||||
def send_mavlink_arm_command(self):
|
||||
self.send_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
1, # ARM
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0)
|
||||
self.send_cmd(
|
||||
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
p1=1, # ARM
|
||||
)
|
||||
|
||||
def send_mavlink_run_prearms_command(self):
|
||||
self.send_cmd(mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0)
|
||||
self.send_cmd(mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS)
|
||||
|
||||
def analog_rangefinder_parameters(self):
|
||||
return {
|
||||
|
@ -5107,43 +5069,29 @@ class AutoTest(ABC):
|
|||
|
||||
def send_debug_trap(self, timeout=6000):
|
||||
self.progress("Sending trap to autopilot")
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DEBUG_TRAP,
|
||||
32451, # magic number to trap
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
timeout=timeout)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DEBUG_TRAP,
|
||||
p1=32451, # magic number to trap
|
||||
timeout=timeout,
|
||||
)
|
||||
|
||||
def try_arm(self, result=True, expect_msg=None, timeout=60):
|
||||
"""Send Arming command, wait for the expected result and statustext."""
|
||||
self.progress("Try arming and wait for expected result")
|
||||
self.drain_mav()
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
1, # ARM
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED if result else mavutil.mavlink.MAV_RESULT_FAILED,
|
||||
timeout=timeout)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
p1=1, # ARM
|
||||
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED if result else mavutil.mavlink.MAV_RESULT_FAILED,
|
||||
timeout=timeout,
|
||||
)
|
||||
if expect_msg is not None:
|
||||
self.wait_statustext(
|
||||
expect_msg,
|
||||
timeout=timeout,
|
||||
the_function=lambda: self.send_cmd(
|
||||
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
1, # ARM
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
p1=1, # ARM
|
||||
target_sysid=None,
|
||||
target_compid=None,
|
||||
))
|
||||
|
@ -5155,15 +5103,12 @@ class AutoTest(ABC):
|
|||
if force:
|
||||
p2 = 2989
|
||||
try:
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
1, # ARM
|
||||
p2,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
timeout=timeout)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
p1=1, # ARM
|
||||
p2=p2,
|
||||
timeout=timeout,
|
||||
)
|
||||
except ValueError as e:
|
||||
# statustexts are queued; give it a second to arrive:
|
||||
self.delay_sim_time(5)
|
||||
|
@ -5189,30 +5134,23 @@ class AutoTest(ABC):
|
|||
p2 = 0
|
||||
if force:
|
||||
p2 = 21196 # magic force disarm value
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
0, # DISARM
|
||||
p2,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
timeout=timeout)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
p1=0, # DISARM
|
||||
p2=p2,
|
||||
timeout=timeout,
|
||||
)
|
||||
self.wait_disarmed()
|
||||
|
||||
def disarm_vehicle_expect_fail(self):
|
||||
'''disarm, checking first that non-forced disarm fails, then doing a forced disarm'''
|
||||
self.progress("Disarm - expect to fail")
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
0, # DISARM
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
timeout=10,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
p1=0, # DISARM
|
||||
timeout=10,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
|
||||
)
|
||||
self.progress("Disarm - forced")
|
||||
self.disarm_vehicle(force=True)
|
||||
|
||||
|
@ -5766,18 +5704,29 @@ class AutoTest(ABC):
|
|||
|
||||
def run_cmd_int(self,
|
||||
command,
|
||||
p1,
|
||||
p2,
|
||||
p3,
|
||||
p4,
|
||||
x,
|
||||
y,
|
||||
z,
|
||||
p1=0,
|
||||
p2=0,
|
||||
p3=0,
|
||||
p4=0,
|
||||
x=0,
|
||||
y=0,
|
||||
z=0,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
|
||||
timeout=10,
|
||||
target_sysid=None,
|
||||
target_compid=None,
|
||||
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_INT):
|
||||
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
|
||||
p5=None,
|
||||
p6=None,
|
||||
p7=None,
|
||||
):
|
||||
|
||||
if p5 is not None:
|
||||
x = p5
|
||||
if p6 is not None:
|
||||
y = p6
|
||||
if p7 is not None:
|
||||
z = p7
|
||||
|
||||
if target_sysid is None:
|
||||
target_sysid = self.sysid_thismav()
|
||||
|
@ -5804,13 +5753,13 @@ class AutoTest(ABC):
|
|||
|
||||
def send_cmd(self,
|
||||
command,
|
||||
p1,
|
||||
p2,
|
||||
p3,
|
||||
p4,
|
||||
p5,
|
||||
p6,
|
||||
p7,
|
||||
p1=0,
|
||||
p2=0,
|
||||
p3=0,
|
||||
p4=0,
|
||||
p5=0,
|
||||
p6=0,
|
||||
p7=0,
|
||||
target_sysid=None,
|
||||
target_compid=None,
|
||||
mav=None,
|
||||
|
@ -5854,13 +5803,13 @@ class AutoTest(ABC):
|
|||
|
||||
def run_cmd(self,
|
||||
command,
|
||||
p1,
|
||||
p2,
|
||||
p3,
|
||||
p4,
|
||||
p5,
|
||||
p6,
|
||||
p7,
|
||||
p1=0,
|
||||
p2=0,
|
||||
p3=0,
|
||||
p4=0,
|
||||
p5=0,
|
||||
p6=0,
|
||||
p7=0,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
|
||||
target_sysid=None,
|
||||
target_compid=None,
|
||||
|
@ -5921,13 +5870,7 @@ class AutoTest(ABC):
|
|||
target_sysid=1,
|
||||
target_compid=1):
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT,
|
||||
seq,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
p1=seq,
|
||||
timeout=1,
|
||||
target_sysid=target_sysid,
|
||||
target_compid=target_compid)
|
||||
|
@ -6060,13 +6003,8 @@ class AutoTest(ABC):
|
|||
def send_cmd_do_set_mode(self, mode):
|
||||
self.send_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_SET_MODE,
|
||||
mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
|
||||
self.get_mode_from_mode_mapping(mode),
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0
|
||||
p1=mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
|
||||
p2=self.get_mode_from_mode_mapping(mode),
|
||||
)
|
||||
|
||||
def assert_mode(self, mode):
|
||||
|
@ -6147,15 +6085,10 @@ class AutoTest(ABC):
|
|||
custom_mode = self.get_mode_from_mode_mapping(mode)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_SET_MODE,
|
||||
base_mode,
|
||||
custom_mode,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
p1=base_mode,
|
||||
p2=custom_mode,
|
||||
want_result=want_result,
|
||||
timeout=timeout
|
||||
timeout=timeout,
|
||||
)
|
||||
|
||||
def do_set_mode_via_command_long(self, mode, timeout=30):
|
||||
|
@ -6247,13 +6180,10 @@ class AutoTest(ABC):
|
|||
raise NotAchievedException("Did not achieve heading")
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_CONDITION_YAW,
|
||||
heading, # target angle
|
||||
10, # degrees/second
|
||||
1, # -1 is counter-clockwise, 1 clockwise
|
||||
0, # 1 for relative, 0 for absolute
|
||||
0, # p5
|
||||
0, # p6
|
||||
0, # p7
|
||||
p1=heading, # target angle
|
||||
p2=10, # degrees/second
|
||||
p3=1, # -1 is counter-clockwise, 1 clockwise
|
||||
p4=0, # 1 for relative, 0 for absolute
|
||||
)
|
||||
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
|
||||
self.progress("heading=%d want=%d" % (m.heading, int(heading)))
|
||||
|
@ -6274,15 +6204,12 @@ class AutoTest(ABC):
|
|||
def do_set_relay(self, relay_num, on_off, timeout=10):
|
||||
"""Set relay with a command long message."""
|
||||
self.progress("Set relay %d to %d" % (relay_num, on_off))
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_RELAY,
|
||||
relay_num,
|
||||
on_off,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
timeout=timeout)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_SET_RELAY,
|
||||
p1=relay_num,
|
||||
p2=on_off,
|
||||
timeout=timeout,
|
||||
)
|
||||
|
||||
def do_set_relay_mavproxy(self, relay_num, on_off):
|
||||
"""Set relay with mavproxy."""
|
||||
|
@ -6296,15 +6223,11 @@ class AutoTest(ABC):
|
|||
p1 = 1
|
||||
else:
|
||||
p1 = 0
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE,
|
||||
p1, # param1
|
||||
0, # param2
|
||||
0, # param3
|
||||
0, # param4
|
||||
0, # param5
|
||||
0, # param6
|
||||
0, # param7
|
||||
want_result=want_result)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE,
|
||||
p1=p1, # param1
|
||||
want_result=want_result,
|
||||
)
|
||||
|
||||
def do_fence_enable(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):
|
||||
self.do_fence_en_or_dis_able(True, want_result=want_result)
|
||||
|
@ -8437,14 +8360,8 @@ Also, ignores heartbeats not from our target system'''
|
|||
try:
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_GET_HOME_POSITION,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
quiet=quiet)
|
||||
quiet=quiet,
|
||||
)
|
||||
except ValueError:
|
||||
continue
|
||||
m = self.mav.messages.get("HOME_POSITION", None)
|
||||
|
@ -8546,15 +8463,12 @@ Also, ignores heartbeats not from our target system'''
|
|||
new_y = orig_home.longitude + 2000
|
||||
new_z = orig_home.altitude + 300000 # 300 metres
|
||||
print("new home: %s %s %s" % (str(new_x), str(new_y), str(new_z)))
|
||||
self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_SET_HOME,
|
||||
0, # p1,
|
||||
0, # p2,
|
||||
0, # p3,
|
||||
0, # p4,
|
||||
new_x,
|
||||
new_y,
|
||||
new_z/1000.0, # mm => m
|
||||
)
|
||||
self.run_cmd_int(
|
||||
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
|
||||
p5=new_x,
|
||||
p6=new_y,
|
||||
p7=new_z/1000.0, # mm => m
|
||||
)
|
||||
|
||||
home = self.poll_home_position()
|
||||
self.progress("home: %s" % str(home))
|
||||
|
@ -8584,43 +8498,35 @@ Also, ignores heartbeats not from our target system'''
|
|||
self.progress("Waiting for EKF to start")
|
||||
self.wait_ready_to_arm()
|
||||
self.progress("now use lat=0, lon=0 to reset home to current location")
|
||||
self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_SET_HOME,
|
||||
0, # p1,
|
||||
0, # p2,
|
||||
0, # p3,
|
||||
0, # p4,
|
||||
0, # lat
|
||||
0, # lon
|
||||
new_z/1000.0, # mm => m
|
||||
)
|
||||
self.run_cmd_int(
|
||||
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
|
||||
p5=0, # lat
|
||||
p6=0, # lon
|
||||
p7=new_z/1000.0, # mm => m
|
||||
)
|
||||
home = self.poll_home_position()
|
||||
self.progress("home: %s" % str(home))
|
||||
if self.distance_to_home(use_cached_home=True) > 1:
|
||||
raise NotAchievedException("Setting home to current location did not work")
|
||||
|
||||
self.progress("Setting home elsewhere again")
|
||||
self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_SET_HOME,
|
||||
0, # p1,
|
||||
0, # p2,
|
||||
0, # p3,
|
||||
0, # p4,
|
||||
new_x,
|
||||
new_y,
|
||||
new_z/1000.0, # mm => m
|
||||
)
|
||||
self.run_cmd_int(
|
||||
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
|
||||
p5=new_x,
|
||||
p6=new_y,
|
||||
p7=new_z/1000.0, # mm => m
|
||||
)
|
||||
if self.distance_to_home() < 10:
|
||||
raise NotAchievedException("Setting home to location did not work")
|
||||
|
||||
self.progress("use param1=1 to reset home to current location")
|
||||
self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_SET_HOME,
|
||||
1, # p1,
|
||||
0, # p2,
|
||||
0, # p3,
|
||||
0, # p4,
|
||||
37, # lat
|
||||
21, # lon
|
||||
new_z/1000.0, # mm => m
|
||||
)
|
||||
self.run_cmd_int(
|
||||
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
|
||||
p1=1, # use current location
|
||||
p5=37, # lat
|
||||
p6=21, # lon
|
||||
p7=new_z/1000.0, # mm => m
|
||||
)
|
||||
home = self.poll_home_position()
|
||||
self.progress("home: %s" % str(home))
|
||||
if self.distance_to_home() > 1:
|
||||
|
@ -8634,33 +8540,18 @@ Also, ignores heartbeats not from our target system'''
|
|||
def zero_mag_offset_parameters(self, compass_count=3):
|
||||
self.progress("Zeroing Mag OFS parameters")
|
||||
self.get_sim_time()
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS,
|
||||
2, # param1 (compass0)
|
||||
0, # param2
|
||||
0, # param3
|
||||
0, # param4
|
||||
0, # param5
|
||||
0, # param6
|
||||
0 # param7
|
||||
)
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS,
|
||||
5, # param1 (compass1)
|
||||
0, # param2
|
||||
0, # param3
|
||||
0, # param4
|
||||
0, # param5
|
||||
0, # param6
|
||||
0 # param7
|
||||
)
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS,
|
||||
6, # param1 (compass2)
|
||||
0, # param2
|
||||
0, # param3
|
||||
0, # param4
|
||||
0, # param5
|
||||
0, # param6
|
||||
0 # param7
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS,
|
||||
p1=2, # param1 (compass0)
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS,
|
||||
p1=5, # param1 (compass1)
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS,
|
||||
p1=6, # param1 (compass2)
|
||||
)
|
||||
self.progress("zeroed mag parameters")
|
||||
params = [
|
||||
[("SIM_MAG1_OFS1_X", "COMPASS_OFS_X", 0),
|
||||
|
@ -8744,17 +8635,15 @@ Also, ignores heartbeats not from our target system'''
|
|||
mavproxy.send("sitl_stop\n")
|
||||
mavproxy.send("sitl_attitude 0 0 0\n")
|
||||
self.get_sim_time()
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL,
|
||||
tmask, # p1: mag_mask
|
||||
0, # p2: retry
|
||||
0, # p3: autosave
|
||||
0, # p4: delay
|
||||
0, # param5
|
||||
0, # param6
|
||||
0, # param7
|
||||
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
|
||||
timeout=20,
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL,
|
||||
p1=tmask, # p1: mag_mask
|
||||
p2=0, # retry
|
||||
p3=0, # autosave
|
||||
p4=0, # delay
|
||||
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
|
||||
timeout=20,
|
||||
)
|
||||
mavproxy.send("sitl_magcal\n")
|
||||
|
||||
def do_prep_mag_cal_test(mavproxy, params):
|
||||
|
@ -8862,29 +8751,19 @@ Also, ignores heartbeats not from our target system'''
|
|||
self.progress("Calibration progress compass ID %d: %s%%" % (cid, str(reached_pct[cid])))
|
||||
if cid == 0 and 13 <= reached_pct[0] <= 15:
|
||||
self.progress("Request again to start calibration, it shouldn't restart from 0")
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL,
|
||||
target_mask,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
|
||||
timeout=20,
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL,
|
||||
p1=target_mask,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
|
||||
timeout=20,
|
||||
)
|
||||
|
||||
if reached_pct[0] > 30:
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_CANCEL_MAG_CAL,
|
||||
target_mask, # p1: mag_mask
|
||||
0, # param2
|
||||
0, # param3
|
||||
0, # param4
|
||||
0, # param5
|
||||
0, # param6
|
||||
0, # param7
|
||||
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_CANCEL_MAG_CAL,
|
||||
p1=target_mask,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
|
||||
)
|
||||
if tstop is None:
|
||||
tstop = self.get_sim_time_cached()
|
||||
if tstop is not None:
|
||||
|
@ -8980,17 +8859,12 @@ Also, ignores heartbeats not from our target system'''
|
|||
self.check_zeros_mag_orient()
|
||||
self.progress("Send acceptation and check value")
|
||||
self.wait_heartbeat()
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_ACCEPT_MAG_CAL,
|
||||
target_mask, # p1: mag_mask
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
|
||||
timeout=20,
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_ACCEPT_MAG_CAL,
|
||||
p1=target_mask, # p1: mag_mask
|
||||
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
|
||||
timeout=20,
|
||||
)
|
||||
self.check_mag_parameters(params, compass_tnumber)
|
||||
self.verify_parameter_values({"COMPASS_ORIENT": self.get_parameter("SIM_MAG1_ORIENT")})
|
||||
for count in range(2, compass_tnumber + 1):
|
||||
|
@ -9012,17 +8886,15 @@ Also, ignores heartbeats not from our target system'''
|
|||
self.set_parameter("COMPASS_ORIENT%d" % count, self.get_parameter("SIM_MAG%d_ORIENT" % count))
|
||||
self.arm_vehicle()
|
||||
self.progress("Test calibration rejection when armed")
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL,
|
||||
target_mask, # p1: mag_mask
|
||||
0, # p2: retry
|
||||
0, # p3: autosave
|
||||
0, # p4: delay
|
||||
0, # param5
|
||||
0, # param6
|
||||
0, # param7
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
|
||||
timeout=20,
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL,
|
||||
p1=target_mask, # p1: mag_mask
|
||||
p2=0, # retry
|
||||
p3=0, # autosave
|
||||
p4=0, # delay
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
|
||||
timeout=20,
|
||||
)
|
||||
self.disarm_vehicle()
|
||||
self.mavproxy_unload_module(mavproxy, "relay")
|
||||
self.mavproxy_unload_module(mavproxy, "sitl_calibration")
|
||||
|
@ -9292,28 +9164,18 @@ Also, ignores heartbeats not from our target system'''
|
|||
|
||||
ss = self.assert_receive_message('SIMSTATE', timeout=1, verbose=True)
|
||||
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_FIXED_MAG_CAL_YAW,
|
||||
math.degrees(ss.yaw), # param1
|
||||
0, # param2
|
||||
0, # param3
|
||||
0, # param4
|
||||
0, # param5
|
||||
0, # param6
|
||||
0 # param7
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_FIXED_MAG_CAL_YAW,
|
||||
p1=math.degrees(ss.yaw),
|
||||
)
|
||||
self.verify_parameter_values(wanted)
|
||||
|
||||
# run same command but as command_int:
|
||||
self.zero_mag_offset_parameters()
|
||||
self.run_cmd_int(mavutil.mavlink.MAV_CMD_FIXED_MAG_CAL_YAW,
|
||||
math.degrees(ss.yaw), # param1
|
||||
0, # param2
|
||||
0, # param3
|
||||
0, # param4
|
||||
0, # param5
|
||||
0, # param6
|
||||
0 # param7
|
||||
)
|
||||
self.run_cmd_int(
|
||||
mavutil.mavlink.MAV_CMD_FIXED_MAG_CAL_YAW,
|
||||
p1=math.degrees(ss.yaw),
|
||||
)
|
||||
self.verify_parameter_values(wanted)
|
||||
|
||||
self.progress("Rebooting and making sure we could arm with these values")
|
||||
|
@ -9603,23 +9465,11 @@ Also, ignores heartbeats not from our target system'''
|
|||
self.start_subtest("Arm/disarm vehicle with COMMAND_INT")
|
||||
self.run_cmd_int(
|
||||
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
1, # ARM
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
p1=1, # ARM
|
||||
)
|
||||
self.run_cmd_int(
|
||||
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
0, # DISARM
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
p1=0, # DISARM
|
||||
)
|
||||
|
||||
self.progress("arm with mavproxy")
|
||||
|
@ -9785,16 +9635,11 @@ Also, ignores heartbeats not from our target system'''
|
|||
else:
|
||||
self.progress("Not armable mode : %s" % mode)
|
||||
self.change_mode(mode)
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
1, # ARM
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
p1=1, # ARM
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
|
||||
)
|
||||
self.progress("PASS not able to arm in mode : %s" % mode)
|
||||
if mode in self.get_position_armable_modes_list():
|
||||
self.progress("Armable mode needing Position : %s" % mode)
|
||||
|
@ -9807,16 +9652,11 @@ Also, ignores heartbeats not from our target system'''
|
|||
self.progress("Not armable mode without Position : %s" % mode)
|
||||
self.wait_gps_disable()
|
||||
self.change_mode(mode)
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
1, # ARM
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED
|
||||
)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
p1=1, # ARM
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
|
||||
)
|
||||
self.set_parameter("SIM_GPS_DISABLE", 0)
|
||||
self.wait_ekf_happy() # EKF may stay unhappy for a while
|
||||
self.progress("PASS not able to arm without Position in mode : %s" % mode)
|
||||
|
@ -9906,15 +9746,12 @@ Also, ignores heartbeats not from our target system'''
|
|||
set_interval = rate_hz
|
||||
else:
|
||||
set_interval = self.rate_to_interval_us(rate_hz)
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL,
|
||||
id,
|
||||
set_interval,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
mav=mav)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL,
|
||||
p1=id,
|
||||
p2=set_interval,
|
||||
mav=mav,
|
||||
)
|
||||
|
||||
def send_get_message_interval(self, victim_message, mav=None):
|
||||
if mav is None:
|
||||
|
@ -10090,18 +9927,14 @@ Also, ignores heartbeats not from our target system'''
|
|||
mav = self.mav
|
||||
if type(message_id) == str:
|
||||
message_id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % message_id)
|
||||
self.send_cmd(mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE,
|
||||
message_id,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
target_sysid=target_sysid,
|
||||
target_compid=target_compid,
|
||||
quiet=quiet,
|
||||
mav=mav)
|
||||
self.send_cmd(
|
||||
mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE,
|
||||
p1=message_id,
|
||||
target_sysid=target_sysid,
|
||||
target_compid=target_compid,
|
||||
quiet=quiet,
|
||||
mav=mav,
|
||||
)
|
||||
|
||||
def poll_message(self, message_id, timeout=10, quiet=False, mav=None):
|
||||
if mav is None:
|
||||
|
@ -10115,7 +9948,7 @@ Also, ignores heartbeats not from our target system'''
|
|||
mavutil.mavlink.MAV_RESULT_ACCEPTED,
|
||||
timeout,
|
||||
quiet=quiet,
|
||||
mav=mav
|
||||
mav=mav,
|
||||
)
|
||||
while True:
|
||||
if self.get_sim_time_cached() - tstart > timeout:
|
||||
|
@ -11487,27 +11320,19 @@ switch value'''
|
|||
self.wait_ready_to_arm()
|
||||
self.context_push()
|
||||
self.set_parameter("%s_POSXY_P" % param_prefix, -1)
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
1, # ARM
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
timeout=4,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
p1=1, # ARM
|
||||
timeout=4,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
|
||||
)
|
||||
self.context_pop()
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
1, # ARM
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
timeout=4,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
p1=1, # ARM
|
||||
timeout=4,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
|
||||
)
|
||||
self.disarm_vehicle()
|
||||
|
||||
def assert_not_receiving_message(self, message, timeout=1, mav=None):
|
||||
|
@ -11591,13 +11416,7 @@ switch value'''
|
|||
self.context_collect("STATUSTEXT")
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_FLIGHTTERMINATION,
|
||||
1, # terminate
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
p1=1, # terminate
|
||||
)
|
||||
self.wait_statustext("Terminating due to GCS request", check_context=True)
|
||||
self.context_pop()
|
||||
|
@ -11911,14 +11730,8 @@ switch value'''
|
|||
# try to arm the vehicle:
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
1, # ARM
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED
|
||||
p1=1, # ARM
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
|
||||
)
|
||||
self.assert_prearm_failure("Motors Emergency Stopped",
|
||||
other_prearm_failures_fatal=False)
|
||||
|
@ -12270,14 +12083,10 @@ switch value'''
|
|||
|
||||
self.context_collect('STATUSTEXT')
|
||||
command = mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION
|
||||
self.send_cmd(command,
|
||||
0, # p1
|
||||
0, # p2
|
||||
1, # p3, baro
|
||||
0, # p4
|
||||
0, # p5
|
||||
0, # p6
|
||||
0) # p7
|
||||
self.send_cmd(
|
||||
command,
|
||||
p3=1, # p3, baro
|
||||
)
|
||||
# this is a test for asynchronous handling of mavlink messages:
|
||||
self.run_cmd_get_ack(command, mavutil.mavlink.MAV_RESULT_IN_PROGRESS, 2)
|
||||
self.run_cmd_get_ack(command, mavutil.mavlink.MAV_RESULT_ACCEPTED, 5)
|
||||
|
@ -12857,15 +12666,11 @@ switch value'''
|
|||
gpi_abs_alt = int((m.alt+500) / 1000) # mm -> m
|
||||
|
||||
# grab a battery-remaining percentage
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_BATTERY_RESET,
|
||||
255, # battery mask
|
||||
96, # percentage
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0)
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_BATTERY_RESET,
|
||||
p1=255, # battery mask
|
||||
p2=96, # percentage
|
||||
)
|
||||
m = self.assert_receive_message('BATTERY_STATUS', timeout=1)
|
||||
want_battery_remaining_pct = m.battery_remaining
|
||||
|
||||
|
@ -13613,25 +13418,17 @@ SERIAL5_BAUD 128
|
|||
|
||||
def send_pause_command(self):
|
||||
'''pause AUTO/GUIDED modes'''
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE,
|
||||
0, # 0: pause, 1: continue
|
||||
0, # param2
|
||||
0, # param3
|
||||
0, # param4
|
||||
0, # param5
|
||||
0, # param6
|
||||
0) # param7
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE,
|
||||
p1=0, # 0: pause, 1: continue
|
||||
)
|
||||
|
||||
def send_resume_command(self):
|
||||
'''resume AUTO/GUIDED modes'''
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE,
|
||||
1, # 0: pause, 1: continue
|
||||
0, # param2
|
||||
0, # param3
|
||||
0, # param4
|
||||
0, # param5
|
||||
0, # param6
|
||||
0) # param7
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE,
|
||||
p1=1, # 0: pause, 1: continue
|
||||
)
|
||||
|
||||
def enum_state_name(self, enum_name, state, pretrim=None):
|
||||
e = mavutil.mavlink.enums[enum_name]
|
||||
|
|
Loading…
Reference in New Issue