PX4-SITL_gazebo-classic icon indicating copy to clipboard operation
PX4-SITL_gazebo-classic copied to clipboard

Multi-vehicle lockstep simulation bug

Open fabianschilling opened this issue 5 years ago • 16 comments

When launching multiple vehicles in lockstep simulation (i.e. with PX4_SIM_SPEED_FACTOR != 1), the Gazebo world parameter real_time_update_rate is scaled by the given speed factor from the environment variable every time a new vehicle is spawned with the gazebo_mavlink_interface. As an immediate consequence, the gazebo_mavlink_interface gets aborted because the real_time_update_rate is no longer equal to the initially required 250Hz.

To reproduce:

~ $ PX4_SIM_SPEED_FACTOR=0.5 roslaunch px4 multi_uav_mavros_sitl.launch verbose:=true
...
... # Output for uav0 (still fine!)
[Msg] Connecting to PX4 SITL using TCP
[Msg] Lockstep is enabled
[Msg] Speed factor set to: 0.5
...
... # Output for uav1 (crash!)
[Msg] Connecting to PX4 SITL using TCP
[Msg] Lockstep is enabled
[Msg] Speed factor set to: 0.5
[Err] [gazebo_mavlink_interface.cpp:242] real_time_update_rate is set to 125 instead of 250, aborting.
...

I don't know the SITL architecture too well but gazebo_mavlink_interface.cpp does not seem like the ideal place to adjust the real_time_update_rate parameter since it is model (and not world) specific.

Where should this ideally be implemented? I'm happy to help with the fix!

@julianoes and @TSC21

fabianschilling avatar Jul 08 '19 15:07 fabianschilling

Thanks for raising this. I need to have a look.

For now have a look in gazebo_mavlink_interface.cpp

julianoes avatar Jul 08 '19 15:07 julianoes

@fabianschilling did you notice any reduction with the real time factor during serval hours simulation with several quadcopters?

shrit avatar Sep 19 '19 09:09 shrit

@shrit I don't think your issue is related to this.

julianoes avatar Sep 19 '19 09:09 julianoes

@fabianschilling is this still an issue?

julianoes avatar May 09 '21 08:05 julianoes

I have met the same problem, have you solve this bug yet?

unravelwool avatar May 18 '21 03:05 unravelwool

I have found this commit and this code block in gazebo_mavlink_interface.cpp:

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

presetManager->GetCurrentProfileParam("max_step_size", param);
const double max_step_size = our_any_cast<double>(param);
if (1.0 / real_time_update_rate != max_step_size)
{
  gzerr << "max_step_size of " << max_step_size
        << " s does not match real_time_update_rate of "
        << real_time_update_rate << ", aborting.\n";
  abort();
}
...

I'm just using Iris quad rotors. Can I comment out the two abort() to make px4 allow any real_time_update_rate and max_step_size in gazebo, just like this:

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

presetManager->GetCurrentProfileParam("max_step_size", param);
const double max_step_size = our_any_cast<double>(param);
if (1.0 / real_time_update_rate != max_step_size)
{
  gzerr << "max_step_size of " << max_step_size
        << " s does not match real_time_update_rate of "
        << real_time_update_rate << ", aborting.\n";
//  abort();
}

unravelwool avatar May 18 '21 03:05 unravelwool

No, I don't think that will work. You need to make sure all your models have the same real_time_update_rate of 250.

julianoes avatar May 18 '21 04:05 julianoes

Thanks very much for your prompt reply! Is your meaning that px4 doesn't achieve the speed-up of multi-vehicle simulation in gazebo by using PX4_SIM_SPEED_FACTOR env? Do you know other workarounds to speed up the simulation of multi-vehicle in gazebo? :)

unravelwool avatar May 18 '21 09:05 unravelwool

@unravelwool the real_time_update_rate_int is really just an implementation detail. I think PX4_SIM_SPEED_FACTOR should still work as intended, but maybe I'm missing something.

How can I reproduce this? What commands are you running?

julianoes avatar May 19 '21 05:05 julianoes

@julianoes Yes this is still a problem (at least on SITL Gazebo that comes with the latest stable PX4 v1.11.3). Launching multiple vehicles works as intended as long as PX4_SIM_SPEED_FACTOR = 1, otherwise spawning fails after the first vehicle.

For my use case, it is not an issue in practice since my hardware cannot keep up with real-time factor of 1 anyways and thus Gazebo runs as fast as possible even without increasing the speed factor.

fabianschilling avatar May 25 '21 09:05 fabianschilling

Is it fixed with upcoming v1.12?

julianoes avatar May 25 '21 16:05 julianoes

I think I've found a way to work around this issue. First spawn all the UAVs with PX4_SIM_SPEED_FACTOR=1, then call /gazebo/set_physics_properties service to set your desire time steps.

crazypatoto avatar Jul 05 '22 16:07 crazypatoto

I have the similar issue with Gazebo Multi-Vehicle simulation , I'm running Gazebo 9 and iris model.

Os is Ubuntu 20.08. PX4 version is 1.14.0V. NVIDIA T400 4GB 525.60.11 driver version.

I have tried multiple ways by changing real_time_factor and real_time_update_rate in default.sdf. But, It didn't work, Up to 4 vehicle the speed is fine, but after 4 its very slow. Please help me with this issue.

Thanks in advance.

JoshikaNetha avatar Feb 10 '23 04:02 JoshikaNetha

@JoshikaNetha So what you're saying is that it does work but that it doesn't simulate as many vehicles as quickly as you would like - is that correct?

Did you see this note in the docs:

At some point IO or CPU will limit the speed that is possible on your machine and it will be slowed down "automatically". Powerful desktop machines can usually run the simulation at around 6-10x, for notebooks the achieved rates can be around 3-4x.

hamishwillee avatar Feb 15 '23 00:02 hamishwillee

I'm unable to run gazebo multi-vehicle simulation speedly, upto four vehicles speed is fine, but after 4 it is too slow.I'm working on dell precision 3660 desktop.

JoshikaNetha avatar Feb 16 '23 12:02 JoshikaNetha

I think this is going to be fixed by https://github.com/PX4/PX4-SITL_gazebo-classic/pull/959

hamishwillee avatar Feb 21 '23 22:02 hamishwillee