Skip to content

Commit

Permalink
change default update rate to 200 Hz
Browse files Browse the repository at this point in the history
 - this goes along with the change PX4 side PX4/PX4-Autopilot#14759
  • Loading branch information
dagar committed Apr 28, 2020
1 parent 0823f5e commit 2972966
Show file tree
Hide file tree
Showing 13 changed files with 26 additions and 26 deletions.
4 changes: 2 additions & 2 deletions src/gazebo_mavlink_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -311,10 +311,10 @@ void GazeboMavlinkInterface::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf
double real_time_update_rate = boost::any_cast<double>(param);
const int real_time_update_rate_int = static_cast<int>(real_time_update_rate + 0.5);

if (real_time_update_rate_int % 250 != 0)
if (real_time_update_rate_int % 200 != 0)
{
gzerr << "real_time_update_rate is " << real_time_update_rate_int
<< " but needs to be multiple of 250 Hz, aborting.\n";
<< " but needs to be multiple of 200 Hz, aborting.\n";
abort();
}

Expand Down
4 changes: 2 additions & 2 deletions worlds/baylands.world
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,9 @@
<contact_surface_layer>0.001</contact_surface_layer>
</constraints>
</ode>
<max_step_size>0.004</max_step_size>
<max_step_size>0.005</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
<real_time_update_rate>200</real_time_update_rate>
<magnetic_field>6.0e-6 2.3e-5 -4.2e-5</magnetic_field>
</physics>
</world>
Expand Down
4 changes: 2 additions & 2 deletions worlds/boat.world
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,9 @@
<contact_surface_layer>0.001</contact_surface_layer>
</constraints>
</ode>
<max_step_size>0.004</max_step_size>
<max_step_size>0.005</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
<real_time_update_rate>200</real_time_update_rate>
<magnetic_field>6.0e-6 2.3e-5 -4.2e-5</magnetic_field>
</physics>
</world>
Expand Down
4 changes: 2 additions & 2 deletions worlds/empty.world
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,9 @@
<contact_surface_layer>0.001</contact_surface_layer>
</constraints>
</ode>
<max_step_size>0.004</max_step_size>
<max_step_size>0.005</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
<real_time_update_rate>200</real_time_update_rate>
<magnetic_field>6.0e-6 2.3e-5 -4.2e-5</magnetic_field>
</physics>
</world>
Expand Down
4 changes: 2 additions & 2 deletions worlds/hippocampus.world
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,9 @@
<contact_surface_layer>0.001</contact_surface_layer>
</constraints>
</ode>
<max_step_size>0.004</max_step_size>
<max_step_size>0.005</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
<real_time_update_rate>200</real_time_update_rate>
<magnetic_field>6.0e-6 2.3e-5 -4.2e-5</magnetic_field>
</physics>
</world>
Expand Down
4 changes: 2 additions & 2 deletions worlds/iris_irlock.world
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,9 @@
<contact_surface_layer>0.001</contact_surface_layer>
</constraints>
</ode>
<max_step_size>0.004</max_step_size>
<max_step_size>0.005</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
<real_time_update_rate>200</real_time_update_rate>
<magnetic_field>6.0e-6 2.3e-5 -4.2e-5</magnetic_field>
</physics>

Expand Down
4 changes: 2 additions & 2 deletions worlds/ksql_airport.world
Original file line number Diff line number Diff line change
Expand Up @@ -41,9 +41,9 @@
<contact_surface_layer>0.001</contact_surface_layer>
</constraints>
</ode>
<max_step_size>0.004</max_step_size>
<max_step_size>0.005</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
<real_time_update_rate>200</real_time_update_rate>
<magnetic_field>6.0e-6 2.3e-5 -4.2e-5</magnetic_field>
</physics>
</world>
Expand Down
4 changes: 2 additions & 2 deletions worlds/mcmillan_airfield.world
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,9 @@
<contact_surface_layer>0.001</contact_surface_layer>
</constraints>
</ode>
<max_step_size>0.004</max_step_size>
<max_step_size>0.005</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
<real_time_update_rate>200</real_time_update_rate>
<magnetic_field>6.0e-6 2.3e-5 -4.2e-5</magnetic_field>
</physics>
</world>
Expand Down
4 changes: 2 additions & 2 deletions worlds/sonoma_raceway.world
Original file line number Diff line number Diff line change
Expand Up @@ -31,9 +31,9 @@
<contact_surface_layer>0.001</contact_surface_layer>
</constraints>
</ode>
<max_step_size>0.004</max_step_size>
<max_step_size>0.005</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
<real_time_update_rate>200</real_time_update_rate>
<magnetic_field>6.0e-6 2.3e-5 -4.2e-5</magnetic_field>
</physics>
</world>
Expand Down
4 changes: 2 additions & 2 deletions worlds/typhoon_h480.world
Original file line number Diff line number Diff line change
Expand Up @@ -31,9 +31,9 @@
<contact_surface_layer>0.001</contact_surface_layer>
</constraints>
</ode>
<max_step_size>0.004</max_step_size>
<max_step_size>0.005</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
<real_time_update_rate>200</real_time_update_rate>
<magnetic_field>6.0e-6 2.3e-5 -4.2e-5</magnetic_field>
</physics>
</world>
Expand Down
4 changes: 2 additions & 2 deletions worlds/uuv_hippocampus.world
Original file line number Diff line number Diff line change
Expand Up @@ -96,9 +96,9 @@
<contact_surface_layer>0.001</contact_surface_layer>
</constraints>
</ode>
<max_step_size>0.004</max_step_size>
<max_step_size>0.005</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
<real_time_update_rate>200</real_time_update_rate>
<magnetic_field>6.0e-6 2.3e-5 -4.2e-5</magnetic_field>
</physics>
</world>
Expand Down
4 changes: 2 additions & 2 deletions worlds/warehouse.world
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,9 @@
<contact_surface_layer>0.001</contact_surface_layer>
</constraints>
</ode>
<max_step_size>0.004</max_step_size>
<max_step_size>0.005</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
<real_time_update_rate>200</real_time_update_rate>
<magnetic_field>6.0e-6 2.3e-5 -4.2e-5</magnetic_field>
</physics>

Expand Down
4 changes: 2 additions & 2 deletions worlds/yosemite.world
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,9 @@
<contact_surface_layer>0.001</contact_surface_layer>
</constraints>
</ode>
<max_step_size>0.004</max_step_size>
<max_step_size>0.005</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
<real_time_update_rate>200</real_time_update_rate>
<magnetic_field>6.0e-6 2.3e-5 -4.2e-5</magnetic_field>
</physics>
</world>
Expand Down

0 comments on commit 2972966

Please sign in to comment.