mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 01:13:57 -04:00
Tools: autotest: correct wait_servo_channel_value error path
Also make flaps test a little more verbose
This commit is contained in:
parent
42b89e7427
commit
dd88e6e85c
@ -562,10 +562,10 @@ class AutoTestPlane(AutoTest):
|
|||||||
self.set_parameter("SERVO%u_MAX" % servo_ch, servo_ch_max)
|
self.set_parameter("SERVO%u_MAX" % servo_ch, servo_ch_max)
|
||||||
self.set_parameter("SERVO%u_TRIM" % servo_ch, servo_ch_trim)
|
self.set_parameter("SERVO%u_TRIM" % servo_ch, servo_ch_trim)
|
||||||
|
|
||||||
# check flaps are not deployed:
|
self.progress("check flaps are not deployed")
|
||||||
self.set_rc(flaps_ch, flaps_ch_min)
|
self.set_rc(flaps_ch, flaps_ch_min)
|
||||||
self.wait_servo_channel_value(servo_ch, servo_ch_min)
|
self.wait_servo_channel_value(servo_ch, servo_ch_min)
|
||||||
# deploy the flaps:
|
self.progress("deploy the flaps")
|
||||||
self.set_rc(flaps_ch, flaps_ch_max)
|
self.set_rc(flaps_ch, flaps_ch_max)
|
||||||
tstart = self.get_sim_time()
|
tstart = self.get_sim_time()
|
||||||
self.wait_servo_channel_value(servo_ch, servo_ch_max)
|
self.wait_servo_channel_value(servo_ch, servo_ch_max)
|
||||||
@ -576,7 +576,7 @@ class AutoTestPlane(AutoTest):
|
|||||||
if delta_time < delta_time_min or delta_time > delta_time_max:
|
if delta_time < delta_time_min or delta_time > delta_time_max:
|
||||||
raise NotAchievedException((
|
raise NotAchievedException((
|
||||||
"Flaps Slew not working (%f seconds)" % (delta_time,)))
|
"Flaps Slew not working (%f seconds)" % (delta_time,)))
|
||||||
# undeploy flaps:
|
self.progress("undeploy flaps")
|
||||||
self.set_rc(flaps_ch, flaps_ch_min)
|
self.set_rc(flaps_ch, flaps_ch_min)
|
||||||
self.wait_servo_channel_value(servo_ch, servo_ch_min)
|
self.wait_servo_channel_value(servo_ch, servo_ch_min)
|
||||||
|
|
||||||
|
@ -1163,6 +1163,8 @@ class AutoTest(ABC):
|
|||||||
m = self.mav.recv_match(type='SERVO_OUTPUT_RAW',
|
m = self.mav.recv_match(type='SERVO_OUTPUT_RAW',
|
||||||
blocking=True,
|
blocking=True,
|
||||||
timeout=remaining)
|
timeout=remaining)
|
||||||
|
if m is None:
|
||||||
|
continue
|
||||||
m_value = getattr(m, channel_field, None)
|
m_value = getattr(m, channel_field, None)
|
||||||
self.progress("SERVO_OUTPUT_RAW.%s=%u want=%u" %
|
self.progress("SERVO_OUTPUT_RAW.%s=%u want=%u" %
|
||||||
(channel_field, m_value, value))
|
(channel_field, m_value, value))
|
||||||
|
Loading…
Reference in New Issue
Block a user