Gazebo physics solver question: conservation of momentum
I'm trying to work with a door model that does not behave as I would expect. I am trying to get the door to swing freely once a force is imparted to it, but no matter what I change in the urdf, the door still acts as a quasi static object. As soon as the force is removed, the door stops moving.
The code snippet below shows the mods I have used. I have turned all safety controller gains off, tried large and small inertia Izz (0-~100), and eliminated damping and friction.
I don't think I have an issue with understanding physics here. A door is supposed to conserve its momentum on a swing after making contact with an object.
Any suggestions on understanding what is going on here and how I might be able to get the behavior one expects from the door is appreciated. I'm thinking it has something to do with the integration method, but I'm not very clear on how that works in Gazebo. For reference, the model I am using is the door for the PR2 door opening demo located here: http://ros.org/wiki/pr2_simulator/Tutorials/PR2OpenDoor/diamondback
</gazebo>
<joint name="door_joint" type="revolute" >
<origin xyz="0 0 0.05" rpy="0 0 0" />
<axis xyz="0 0 1" />
<limit lower="${-M_PI}" upper="${M_PI}" effort="0" velocity="0" />
<safety_controller soft_lower_limit="${-M_PI+0.1}" soft_upper_limit="${M_PI-0.1}"
k_position="0.0" k_velocity="0.0" />
<dynamics damping="0.0" friction="0.0" />
<parent link="wall1_link" />
<child link="door_link" />
</joint>
<link name="door_link">
<inertial >
<mass value="${M_door}" />
<com xyz="0.0 -0.5 1.0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="30.0" />
</inertial>
<visual >
<origin xyz="0.0 -0.5 1.0" rpy="0 0 ${M_PI}" />
<geometry name="sholder_roll_mesh_file">
<box size="0.1 ${W_door} ${H_door}" />
</geometry>
</visual>
<collision >
<origin xyz="0.0 -0.5 1.0" rpy="0 0 ${M_PI}" />
<geometry name="door_collision_geom">
<box size="0.1 ${W_door} ${H_door}" />
</geometry>
</collision>
</link>
<gazebo reference="door_link">
<material>PR2/Grey</material>
<laserRetro>2000</laserRetro>
<turnGravityOff>false</turnGravityOff>
<selfCollide>false</selfCollide>
<dampingFactor>0.01</dampingFactor>
</gazebo>