mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SITL: SIM_Vicon supports sending at 50hz
This commit is contained in:
parent
6c10655059
commit
c4440a81f4
@ -100,8 +100,8 @@ void Vicon::update_vicon_position_estimate(const Location &loc,
|
||||
return;
|
||||
}
|
||||
|
||||
if (now_us - last_observation_usec < 70000) {
|
||||
// create observations at 70ms intervals (matches EK2 max rate)
|
||||
if (now_us - last_observation_usec < 20000) {
|
||||
// create observations at 20ms intervals (matches EKF max rate)
|
||||
return;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user