Gazebo ignores URDF velocity and effort limits
Hi all,
I am trying to set up a robot description file in urdf that includes "revolute" joints and simulate it in gazebo worlds. I am putting force to my simulated joint by running:
rosservice call gazebo/apply_joint_effort
and providing as argument the joint name, effort and duration. I have also set the limits in effort and velocity in the urdf file.
<?xml version="1.0"?>
<robot name="expjoint">
<link name="expbody">
<inertial>
<origin xyz="0 0 0" />
<mass value="100.0" />
<inertia ixx="1" ixy="0.0" ixz="0.0" iyy="1" iyz="0.0" izz="1" />
</inertial>
<visual>
<origin xyz="0 0 0.6" rpy="0 0 0" />
<geometry>
<cylinder length="1.0" radius="0.12"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0.6" rpy="0 0 0" />
<geometry>
<cylinder length="1.0" radius="0.12"/>
</geometry>
</collision>
</link>
<link name="exparm">
<inertial>
<origin xyz="0 0 0" />
<mass value="10" />
<inertia ixx="1" ixy="0.0" ixz="0.0" iyy="1" iyz="0.0" izz="1" />
</inertial>
<visual>
<origin xyz="0 0 0.1" rpy="0 1.57 0" />
<geometry>
<cylinder length="1" radius="0.02"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0.1" rpy="0 1.57 0" />
<geometry>
<cylinder length="1" radius="0.02"/>
</geometry>
</collision>
</link>
<joint name="expjoint" type="revolute">
<dynamics damping="0.0" friction="0.0"/>
<axis xyz="0 1 0" />
<limit effort="0.0001" velocity="0.0001" lower="-2.2" upper="1.7"/>
<safety_controller k_velocity="10" k_position="10" />
<parent link="expbody"/>
<child link="exparm"/>
<origin xyz="0 0.17 1"/>
</joint>
</robot>
The problem is that the limits in velocity and effort are not applied when i apply the effort through the service call. Any force and any velocity are possible, depending on the effort that is applied. Suprisingly, only the upper and lower limit of the joint seem to work.
Does anybody know what could be the cause of this?
p.s. i am launching gazebo_worlds through the empty_world.launch file.
I would be grateful if anybody could help!
Panagiotis Papadakis