Browse Source

SITL: send vicon data at 70ms intervals

this matches the max rate that EK2 will accept this data
master
Andrew Tridgell 6 years ago
parent
commit
4ca48f225d
  1. 4
      libraries/SITL/SIM_Vicon.cpp

4
libraries/SITL/SIM_Vicon.cpp

@ -97,8 +97,8 @@ void Vicon::update_vicon_position_estimate(const Location &loc, @@ -97,8 +97,8 @@ void Vicon::update_vicon_position_estimate(const Location &loc,
return;
}
if (now_us - last_observation_usec < 10000) {
// create observations at 10ms
if (now_us - last_observation_usec < 70000) {
// create observations at 70ms intervals (matches EK2 max rate)
return;
}

Loading…
Cancel
Save