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

Ignored joint limits by MoveIt!

asked 2017-01-21 10:38:02 -0500

HannesIII gravatar image

updated 2017-01-21 11:11:44 -0500

gvdhoorn gravatar image

Hello,

I am using MoveIt! for a simulated UR10 in Gazebo. When I try to tell the MoveGroup to move the end effector to a position (x,y,z,w), MoveIt! ignores the joint limits which are set in the launch file (-pi/2, pi/2, etc.). This leads frequently to a collision between the shoulder_link and the ground plane. Does anybody know why MoveIt! ignores these limits? If so, how can I resolve this problem? I am using ROS Indigo and Gazebo 2. If you will need more information, please advise :)

Thank you very much in advance! Kind regards, Hannes

Update1: I am referring to this xacro file, the ur10_joint_limited_robot.urdf.xacro...

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"
       name="ur10" >

  <!-- common stuff -->
  <xacro:include filename="$(find ur_description)/urdf/common.gazebo.xacro" />

  <!-- ur10 -->
  <xacro:include filename="$(find ur_description)/urdf/ur10.urdf.xacro" />

  <!-- arm -->
  <xacro:ur10_robot prefix="" joint_limited="true"
         shoulder_pan_lower_limit="${-pi}" shoulder_pan_upper_limit="${pi}"
         shoulder_lift_lower_limit="${-pi/2}" shoulder_lift_upper_limit="${pi/2}"
         elbow_joint_lower_limit="${-pi}" elbow_joint_upper_limit="${pi}"
         wrist_1_lower_limit="${-pi}" wrist_1_upper_limit="${pi}"
         wrist_2_lower_limit="${-pi}" wrist_2_upper_limit="${pi}"
         wrist_3_lower_limit="${-pi}" wrist_3_upper_limit="${pi}"
/>

  <link name="world" />

  <joint name="world_joint" type="fixed">
    <parent link="world" />
    <child link = "base_link" />
    <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
  </joint>

</robot>
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
1

answered 2017-01-21 10:44:14 -0500

gvdhoorn gravatar image

updated 2017-01-21 11:12:12 -0500

Have you updated the limits in the ur10_moveit_config/config/joint_limits.yaml? Those take precedence over what is in the URDF.

Edit: also: which "joint limits which are set in the launch file" are you referring to?

edit flag offensive delete link more

Comments

I did not update the .yaml file. I think the joint limits are set by the xacro file above, aren't they? Thank you for your response!

HannesIII gravatar image HannesIII  ( 2017-01-21 10:59:04 -0500 )edit

Ah, the xacro. Yes, but again: the joint_limits.yaml in the MoveIt configuration package overrides these.

gvdhoorn gravatar image gvdhoorn  ( 2017-01-21 11:13:00 -0500 )edit

It's good to also update them in the xacro though, as only MoveIt uses the values in joint_limits.yaml. Other utilities / nodes parsing the URDF will use those in the URDF itself (as they know nothing about MoveIt, or its parameters).

gvdhoorn gravatar image gvdhoorn  ( 2017-01-21 11:13:53 -0500 )edit

it seems the .yaml file is only vel and accelerations, not positions?? or am i missing something?

danjo gravatar image danjo  ( 2018-10-03 08:25:10 -0500 )edit
0

answered 2021-03-12 07:50:37 -0500

Bjb0403 gravatar image

I've run into this problem with joint_limits.yaml being ignored. The joint_limits.yaml appears to not be able to parse pi/2 etc etc. Initial testing has shown it responds to setting limits in numerical values (radians).

Hope this helps someone.

edit flag offensive delete link more

Comments

This is actually supported. You just need to use the correct sytax.

See wiki/rosparam: YAML Format.

From the example there:

angle1: rad(2*pi)
angle2: deg(180)

And for a larger example (using the more explicit !degrees ctor): ur_description/config/ur10e/joint_limits.yaml.

gvdhoorn gravatar image gvdhoorn  ( 2021-03-12 08:52:29 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2017-01-21 10:38:02 -0500

Seen: 2,760 times

Last updated: Mar 12 '21