ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
2

Gazebo ignores URDF velocity and effort limits

asked 2011-08-30 04:56:58 -0500

Panagiotis gravatar image

updated 2011-08-30 21:33:39 -0500

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

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
9

answered 2011-08-30 21:48:51 -0500

There's an explanation on the effort and velocity safety limits here. As far as I know, these safety limits are only taken into account if you use the pr2_controller_manager as a Gazebo controller plugin (don't be fooled by the name, the controller manager is also very useful for non-PR2 robots). If you write your own controller, you can of course also write it such that it respects those limits.

Now that I think about it, it would be illogical for apply_joint_effort to respect those limits: they represent desired limits on effort and velocity that you don't want the controller to exceed. They are not physical limits on the joints. The service apply_joint_effort simulates the effect of some "external" subject other than the controller taking the joint and twisting it.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2011-08-30 04:56:58 -0500

Seen: 2,935 times

Last updated: Aug 30 '11