Gazebo | Ignition | Community
Ask Your Question
1

Changing static component at runtime does not result in change in physics

asked 2023-02-03 03:24:09 -0500

gsisinna gravatar image

Good morning, everyone, I am trying to change the <static> component of a box at runtime with a plugin.

I am using gz-sim garden and I initially generate my world with objects with <static>True</static> in the SDF file. I would like to change this value for one object at the time. I have the BoxModelEntity, and I can access to its components.

I have done it this way, but although from the component inspector I can see the flag change, the object remains immovable and the collisions are not as I would expect, i.e. the box behaves as if it has infinite mass.

boxModelEntity = _ecm.EntityByComponents(components::Model(), components::Name(boxModelName));

if (_ecm.Component<components::Static>(boxModelEntity)->Data())
{
  gzdbg << "The box model is static" << std::endl;

  // Set the static component of the boxModelEntity to false
  _ecm.CreateComponent(boxModelEntity, components::Static(false));

  // warn the user that the static component of the boxModelEntity has been set to false
  gzdbg << "The static component of the boxModelEntity has been set to false." << std::endl;

  // Update the physics engine  to apply the changes  to the boxModelEntity (set the static component to false) 
  _ecm.SetChanged(boxModelEntity, components::Static::typeId, ComponentState::OneTimeChange);
}
else
{
  gzdbg << "The box model is not static" << std::endl;
}

It seems that once the object is generated in static, despite the change in that property, relative physics is not activated (I need gravity).

Another solution seemed to me to delete the box and recreate an identical one in the same pose with the static component set to false, but I still cannot find an easy way to generate the same box at runtime after removing the previous Entity.

Do you have any suggestions? Thanks!

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2023-02-03 13:08:10 -0500

azeey gravatar image

This is not well documented, but the only components that dynamically affect the Physics system at run time are components with the suffix Cmd or Reset. Other components are read once during mode load.

Unfortunately, the physics API for setting models as static/non-static dynamically is not there yet. We would definitely welcome a PR though

Otherwise, another (non-optimal) approach is to create a detachablefixed joint between the world and each model. You can remove/break this joint to make the model "non-static". It's not exactly the same thing, but might do what you want. Once the joint is detached, you can't attach it back again until https://github.com/gazebosim/gz-sim/p... is merged.

edit flag offensive delete link more

Comments

Thank you very much for the answer, so as I imagined the runtime change of the static component is not supported.

I'll try the detachable joint approach, and if that doesn't work I was thinking of spawning a single box with the dynamics enabled by default and replacing it from time to time to the fake boxes with the dynamics disabled.

In any case I would like to actively contribute on this with a PR in the future, thank you Azeey.

gsisinna gravatar imagegsisinna ( 2023-02-06 04:00:45 -0500 )edit

I tried the detachable joint approach and unfortunately as I thought my RTF falls down and the simulation becomes unusable as too many objects result in collision.

Is there a simple way to destroy the box entity and recreate it in the same location but with static component enabled?

Thanks

gsisinna gravatar imagegsisinna ( 2023-02-06 05:18:03 -0500 )edit
1

The ECM has a Clonefunction you can use https://github.com/gazebosim/gz-sim/b.... Here's an example usage in UserCommands: https://github.com/gazebosim/gz-sim/b...

azeey gravatar imageazeey ( 2023-02-06 09:49:17 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2023-02-03 03:24:09 -0500

Seen: 852 times

Last updated: Feb 03 '23