change in the velocity of objects after a collision
Hi i want to simulate a inelastic collision between a ball and table in gazebo11, the problem is when i disable the gravity in the model.sdf of the ball the velocity of the ball changes in different heights which can't happen in a valid model the sdf models are : <collision name="collision">
<pose>0 0 0 0 -0 0</pose>
<geometry>
<sphere>
<radius>0.02</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
<torsional>
<coefficient>0</coefficient>
<patch_radius>0</patch_radius>
<surface_radius>0</surface_radius>
<use_patch_radius>0</use_patch_radius>
<ode>
<slip>0</slip>
</ode>
</torsional>
</friction>
<bounce>
<restitution_coefficient>1.0</restitution_coefficient>
<threshold>0.1</threshold>
</bounce>
<contact>
<collide_without_contact>0</collide_without_contact>
<collide_without_contact_bitmask>1</collide_without_contact_bitmask>
<collide_bitmask>1</collide_bitmask>
<ode>
<soft_cfm>0.0</soft_cfm>
<soft_erp>1.0</soft_erp>
<kp>1e+14</kp>
<kd>0.0</kd>
<max_vel>1e+6</max_vel>
<min_depth>0</min_depth>
</ode>
</contact>
</surface>
</collision>
and for the table : <collision name="collision"> <laser_retro>0</laser_retro> <max_contacts>10</max_contacts> <pose>0 0 0 0 -0 0</pose> <geometry> <box> <size>2.74 1.525 0.02</size> </box> </geometry>
<surface>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
<torsional>
<coefficient>0</coefficient>
<patch_radius>0</patch_radius>
<surface_radius>0</surface_radius>
<use_patch_radius>0</use_patch_radius>
<ode>
<slip>0</slip>
</ode>
</torsional>
</friction>
<bounce>
<restitution_coefficient>1.0</restitution_coefficient>
<threshold>0.01</threshold>
</bounce>
<contact>
<collide_without_contact>0</collide_without_contact>
<collide_without_contact_bitmask>1</collide_without_contact_bitmask>
<collide_bitmask>1</collide_bitmask>
<ode>
<soft_cfm>0.0</soft_cfm>
<soft_erp>1.0</soft_erp>
<kp>10e+13</kp>
<kd>0.0</kd>
<max_vel>1e+6</max_vel>
<min_depth>0</min_depth>
</ode>
<!-- <bullet>
<split_impulse>1</split_impulse>
<split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>
<soft_cfm>0</soft_cfm>
<soft_erp>0.2</soft_erp>
<kp>1e+13</kp>
<kd>1</kd>
</bullet> -->
</contact>
</surface>
</collision>