@@ -303,18 +303,18 @@ void GazeboMavlinkInterface::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf
303
303
#endif
304
304
presetManager->CurrentProfile (" default_physics" );
305
305
306
- // We currently need to have the real_time_update_rate at a multiple of 250 Hz for lockstep.
307
- // Also, the max_step_size needs to match this (e.g. 0.004 s at 250 Hz or 0.002 s at 500 Hz).
306
+ // We currently need to have the real_time_update_rate at a multiple of 200 Hz for lockstep.
307
+ // Also, the max_step_size needs to match this (e.g. 0.005 s at 200 Hz or 0.0025 s at 400 Hz).
308
308
// Therefore we check these params and abort if they won't work.
309
309
310
310
presetManager->GetCurrentProfileParam (" real_time_update_rate" , param);
311
311
double real_time_update_rate = boost::any_cast<double >(param);
312
312
const int real_time_update_rate_int = static_cast <int >(real_time_update_rate + 0.5 );
313
313
314
- if (real_time_update_rate_int % 250 != 0 )
314
+ if (real_time_update_rate_int % 200 != 0 )
315
315
{
316
316
gzerr << " real_time_update_rate is " << real_time_update_rate_int
317
- << " but needs to be multiple of 250 Hz, aborting.\n " ;
317
+ << " but needs to be multiple of 200 Hz, aborting.\n " ;
318
318
abort ();
319
319
}
320
320
@@ -328,7 +328,7 @@ void GazeboMavlinkInterface::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf
328
328
abort ();
329
329
}
330
330
331
- update_skip_factor_ = real_time_update_rate_int / 250 ;
331
+ update_skip_factor_ = real_time_update_rate_int / 200 ;
332
332
333
333
// Adapt the real_time_update_rate according to the speed
334
334
// that we ask for in the env variable.
@@ -648,7 +648,7 @@ void GazeboMavlinkInterface::OnUpdate(const common::UpdateInfo& /*_info*/) {
648
648
649
649
previous_imu_seq_ = last_imu_message_.seq ();
650
650
651
- // Always run at 250 Hz. At 500 Hz, the skip factor should be 2, at 1000 Hz 4 .
651
+ // Always run at 200 Hz. At 400 Hz, the skip factor should be 2, at 1000 Hz 5 .
652
652
if (!(previous_imu_seq_ % update_skip_factor_ == 0 )) {
653
653
return ;
654
654
}
0 commit comments