mirror of https://github.com/ArduPilot/ardupilot
autotest: relax test limits for single-precision
This commit is contained in:
parent
0665ac0f4f
commit
076a0e848c
|
@ -3833,7 +3833,7 @@ class AutoTestCopter(AutoTest):
|
||||||
new_pos = self.mav.location()
|
new_pos = self.mav.location()
|
||||||
delta = self.get_distance(target, new_pos)
|
delta = self.get_distance(target, new_pos)
|
||||||
self.progress("Landed %f metres from target position" % delta)
|
self.progress("Landed %f metres from target position" % delta)
|
||||||
max_delta = 1
|
max_delta = 1.5
|
||||||
if delta > max_delta:
|
if delta > max_delta:
|
||||||
raise NotAchievedException("Did not land close enough to target position (%fm > %fm" % (delta, max_delta))
|
raise NotAchievedException("Did not land close enough to target position (%fm > %fm" % (delta, max_delta))
|
||||||
|
|
||||||
|
@ -6896,7 +6896,7 @@ class AutoTestCopter(AutoTest):
|
||||||
if self.get_sim_time_cached() - tstart > 10:
|
if self.get_sim_time_cached() - tstart > 10:
|
||||||
break
|
break
|
||||||
vel = self.get_body_frame_velocity()
|
vel = self.get_body_frame_velocity()
|
||||||
if vel.length() > 0.3:
|
if vel.length() > 0.5:
|
||||||
raise NotAchievedException("Moved too much (%s)" %
|
raise NotAchievedException("Moved too much (%s)" %
|
||||||
(str(vel),))
|
(str(vel),))
|
||||||
shove(None, None)
|
shove(None, None)
|
||||||
|
@ -9267,8 +9267,8 @@ class AutoTestCopter(AutoTest):
|
||||||
# before the motors will spin:
|
# before the motors will spin:
|
||||||
self.wait_esc_telem_rpm(
|
self.wait_esc_telem_rpm(
|
||||||
esc=mot,
|
esc=mot,
|
||||||
rpm_min=17640,
|
rpm_min=17626,
|
||||||
rpm_max=17640,
|
rpm_max=17626,
|
||||||
minimum_duration=2,
|
minimum_duration=2,
|
||||||
timeout=5,
|
timeout=5,
|
||||||
)
|
)
|
||||||
|
@ -9277,8 +9277,8 @@ class AutoTestCopter(AutoTest):
|
||||||
self.set_safetyswitch_off()
|
self.set_safetyswitch_off()
|
||||||
self.wait_esc_telem_rpm(
|
self.wait_esc_telem_rpm(
|
||||||
esc=mot,
|
esc=mot,
|
||||||
rpm_min=17640,
|
rpm_min=17626,
|
||||||
rpm_max=17640,
|
rpm_max=17626,
|
||||||
minimum_duration=2,
|
minimum_duration=2,
|
||||||
timeout=5,
|
timeout=5,
|
||||||
)
|
)
|
||||||
|
|
|
@ -403,7 +403,7 @@ class AutoTestHelicopter(AutoTestCopter):
|
||||||
self.progress("Triggering manual autorotation by disabling interlock")
|
self.progress("Triggering manual autorotation by disabling interlock")
|
||||||
self.set_rc(3, 1300)
|
self.set_rc(3, 1300)
|
||||||
self.set_rc(8, 1000)
|
self.set_rc(8, 1000)
|
||||||
self.wait_servo_channel_value(8, 1200, timeout=3)
|
self.wait_servo_channel_value(8, 1199, timeout=3)
|
||||||
self.progress("channel 8 set to autorotation window")
|
self.progress("channel 8 set to autorotation window")
|
||||||
|
|
||||||
self.set_rc(8, 2000)
|
self.set_rc(8, 2000)
|
||||||
|
|
Loading…
Reference in New Issue