Skip to content

Commit

Permalink
autotest: fix Copter motortest test
Browse files Browse the repository at this point in the history
We were swallowing all of the rc output containing the values we were
looking for.

Rearrange so we don't swallow where we were, and increase timeout on the
basis that there's still a narrow race.
  • Loading branch information
peterbarker committed Sep 22, 2020
1 parent d5722b1 commit 64461db
Showing 1 changed file with 6 additions and 6 deletions.
12 changes: 6 additions & 6 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -2565,7 +2565,7 @@ def test_motortest(self, timeout=60):
2, # start motor
mavutil.mavlink.MOTOR_TEST_THROTTLE_PWM,
pwm_in, # pwm-to-output
1, # timeout in seconds
2, # timeout in seconds
2, # number of motors to output
0, # compass learning
0,
Expand All @@ -2578,19 +2578,19 @@ def test_motortest(self, timeout=60):

self.start_subtest("Testing percentage output")
percentage = 90.1
# since MOT_SPIN_MIN and MOT_SPIN_MAX are not set, the RC3
# 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
1, # timeout in seconds
2, # timeout in seconds
2, # number of motors to output
0, # compass learning
0,
timeout=timeout)
# since MOT_SPIN_MIN and MOT_SPIN_MAX are not set, the RC3
# 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.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")
Expand Down

0 comments on commit 64461db

Please sign in to comment.