Why does an SDF model moved through /gazebo/set_model_state service doesnt colide with objects
Hi, I am moving an sdf cube setting its state through the /gazebo/set_model_state service, through python. The SDF is as follows, and is spawned through the gazebo/spawn_sdf_model service. I have tried it with and without the inertial component:
<?xml version="1.0"?>
<sdf version="1.4">
<model name="piece">
<static>True</static>
<link name="link">
<!--
<inertial>
<mass>0.001</mass>
<inertia>
<ixx>0.0000001667</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0000000667</iyy>
<iyz>0</iyz>
<izz>0.0000001667</izz>
</inertia>
</inertial>
-->
<collision name="collision">
<geometry>
<box><size>0.5 0.5 0.5</size></box>
</geometry>
<surface>
<friction>
<ode>
<mu>0.4</mu>
<mu2>0.4</mu2>
</ode>
</friction>
<contact>
<ode>
<max_vel>0.1</max_vel>
<min_depth>0.0001</min_depth>
</ode>
</contact>
</surface>
</collision>
<visual name="visual">
<geometry>
<box><size>0.5 0.5 0.5</size></box>
</geometry>
</visual>
</link>
</model>
</sdf>
Its moving perfectly but when a standard cube is placed in its trajectory, it just crosses as if it wasn't there. But if the movement stops and I move the standard cube a bit , then the collisions come into place.
Is there a way of update the physics in the same way that it gets updated when the standard cube is moved by hand? Am I missing something in how gazebo works? Extra Data: ROS Version: kinetic GAzebo Version: 7.0
Thankyou
Could you put on your Python code which moves that object by
/gazebo/set_model_state
topic?