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

Redundant locations in URDF for joint position/effort/velocity limits

asked 2022-03-22 18:20:35 -0500

In ROS1 (and now in ROS2), position (and effort/velocity) limits were specified in the Joint URDF definition.

I understand that the more flexible <ros2_control> tags in URDF allow the specification of limits for any user-defined interface as well, but in the specific case of position (and effort/velocity) limits, how are redundant values handled?

For example, say I have a joint definition with position limits, as below:

  <joint name="gripper_joint" type="revolute">
    <axis xyz="0 1 0"/>
    <parent link="base_link"/>
    <child link="gripper_link"/>
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <limit effort="1000.0" lower="-1.57" upper="1.57" velocity="10.0"/>    <!-- <<< HERE -->
    <dynamics damping="0.0" friction="0.0"/>
  </joint>

And I also specify a <ros2_control> tag with a different set of position limits, as below:

  <ros2_control name="gripper" type="system">
    <hardware>
      <plugin>gazebo_ros2_control/GazeboSystem</plugin>
    </hardware>
    <joint name="gripper_joint">
      <command_interface name="position">
        <param name="min">0.0</param>             <!-- <<<< HERE -->
        <param name="max">1.0</param>             <!-- <<<< HERE -->
        <param name="initial_value">0.5</param>
      </command_interface>
      <state_interface name="position">
    </joint>

What is the order of precedence by which these conflicting values are resolved?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2022-03-23 18:15:32 -0500

shonigmann gravatar image

updated 2022-04-22 11:29:09 -0500

My understanding is that the intent is to have the following hierarchy for ros2_control:

  1. yaml config file (highest precedence)
  2. <ros2_control> limit tags in the URDF
  3. <joint> limit tags in the URDF (lowest precedence)

That said, it has been a while since I've looked through the code and at the time, this was still an "in development" feature of ros2_control. The last time I was reviewing the code, my impression was that only limits defined in the yaml file would be respected, and only if the controller was setup to respect them.

There's a bit of discussion on this draft PR that may help shed some light.

Maybe someone else can chime in with more recent insights.

EDIT: adding a small note that may help for clarity - I believe the intent is also to have checks to ensure that the higher precedence limits do not break the URDF limits; e.g. the URDF should specify hardware limits (e.g. the known max speed of a motor, the known end of travel on a joint) set by the manufacturer, the yaml file would specify more conservative control limits based on the user's needs (e.g. adding a safety margin around the end of travel)

edit flag offensive delete link more

Comments

Thanks @shonigmann! In regards to your recent edit, where would a developer enforce these limits? It appears to me that this information cannot be enforced via custom code at the hardware_interface::CommandInterface level, for a few reasons. So, is it entirely the responsibility of controllers to enforce these limits? If this was enforced at the hardware_interface layer instead, it would not only be simpler but also save a lot of redundant checks from needing to be added to controllers.

alikureishy gravatar image alikureishy  ( 2022-04-21 19:42:27 -0500 )edit

I can only speculate based on the implementation in ros(1)_control and the PRs I've seen so far. But my understanding is that the intent is to have a standalone JointLimits structure that captures your limits. At least at some point the idea was to have hardware limits captured as part of the hardware initialization but this was from a closed PR 1 year ago. From the latest PR, it looks like Controller limits would be initialized from the yaml config. Then the controller can have its own limit structure, then when writing commands to the hardware, both could be enforced (though perhaps in different steps). I don't actively develop ros2_control so I'm reaching a bit here

shonigmann gravatar image shonigmann  ( 2022-04-22 13:04:57 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2022-03-22 18:20:35 -0500

Seen: 334 times

Last updated: Apr 22 '22