mirror of https://github.com/ArduPilot/ardupilot
Tools: rover autotests send position-target-global-int more slowly
SCurves do not work with very fast changes of target
This commit is contained in:
parent
8ff6972b7e
commit
ea5e3a8ae0
|
@ -3590,7 +3590,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
now = self.get_sim_time_cached()
|
||||
if now - tstart > timeout:
|
||||
raise AutoTestTimeoutException("Did not get to location")
|
||||
if now - last_sent > 1:
|
||||
if now - last_sent > 10:
|
||||
last_sent = now
|
||||
self.mav.mav.set_position_target_global_int_send(
|
||||
0,
|
||||
|
@ -3645,7 +3645,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
now = self.get_sim_time_cached()
|
||||
if now - tstart > timeout:
|
||||
raise NotAchievedException("Did not breach boundary + RTL")
|
||||
if now - last_sent > 1:
|
||||
if now - last_sent > 10:
|
||||
last_sent = now
|
||||
self.mav.mav.set_position_target_global_int_send(
|
||||
0,
|
||||
|
@ -3710,7 +3710,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
now = self.get_sim_time_cached()
|
||||
if now - tstart > timeout:
|
||||
raise NotAchievedException("Did not arrive and stop at boundary")
|
||||
if now - last_sent > 1:
|
||||
if now - last_sent > 10:
|
||||
last_sent = now
|
||||
self.mav.mav.set_position_target_global_int_send(
|
||||
0,
|
||||
|
|
Loading…
Reference in New Issue