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

Controlling the UR10e via the effort command in the Gazebo environment

asked 2022-11-02 06:43:24 -0500

sm3304ove gravatar image

Hello. I'm trying to control a UR10e with the effort command in my Gazebo simulation. The effort value I am currently giving each joint is [0.0, -71.0770284, -23.0658876, 0.0, 0.0, 0.0]. This seems to be enough force to move the UR10e. However, on the Gazebo, the UR10e does not move at all, despite receiving the effort command correctly. Passing a very large effort value will cause the joint to move, but that doesn't seem right. Did I something wrong?

UR10e urdf is from the ur_e_description package, and transmission and gazebo_ros_control plugins have been added as follows.

    <?xml version="1.0" encoding="utf-8"?>
<robot
  name="ur10e">
  <link name="world"/>

  <joint name="world_to_ur10e" type="fixed">
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <parent link="world"/>  
    <child link="base_link"/>  
  </joint>  
  <link name="base_link">
    <visual>
      <geometry>
        <mesh filename="package://ur10e_description/meshes/ur10e/visual/base.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur10e_description/meshes/ur10e/collision/base.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="4.0"/>
      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
      <inertia ixx="0.0061063308908" ixy="0.0" ixz="0.0" iyy="0.0061063308908" iyz="0.0" izz="0.01125"/>
    </inertial>
  </link>
  <joint name="shoulder_pan_joint" type="revolute">
    <parent link="base_link"/>
    <child link="shoulder_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.181"/>
    <axis xyz="0 0 1"/>
    <limit effort="330.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.14"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="shoulder_link">
    <visual>
      <geometry>
        <mesh filename="package://ur10e_description/meshes/ur10e/visual/shoulder.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur10e_description/meshes/ur10e/collision/shoulder.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="7.778"/>
      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
      <inertia ixx="0.03147431257693659" ixy="0.0" ixz="0.0" iyy="0.03147431257693659" iyz="0.0" izz="0.021875624999999996"/>
    </inertial>
  </link>
  <joint name="shoulder_lift_joint" type="revolute">
    <parent link="shoulder_link"/>
    <child link="upper_arm_link"/>
    <origin rpy="0.0 1.5707963267948966 0.0" xyz="0.0 0.176 0.0"/>
    <axis xyz="0 1 0"/>

    <limit effort="330.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.14"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="upper_arm_link">
    <visual>
      <geometry>
        <mesh filename="package://ur10e_description/meshes/ur10e/visual/upperarm.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2022-11-07 22:10:32 -0500

danzimmerman gravatar image

This seems to be enough force to move the UR10e

What tool did you get to get those values?

I did a quick check here and got approximately 121Nm for the shoulder lift and 34Nm for the elbow when the arm angles are all zero.

Precisely, [ -0. , -120.812, -33.961, -0. , 0. , 0. ]

I'm loading the UR10e URDF from the Universal_Robots_ROS2_Description into Pinocchio and using pin.computeStaticTorque(model, data, q, fext)

Not 100% sure that's right but you might want to get a second opinion on the expected torques depending on the initial posture of the robot. If it's dangling down like pendulum the joints will absolutely move but if it's starting out lying more or less horizontal on the Gazebo floor it might not.

You might try using the position controller in Gazebo and put the robot in some pose and see what the joint efforts are.

ur_e_description

Are you building from source? Using Kinetic?

I think things changed a lot around the time of https://github.com/ros-industrial/uni... and I think that unified everything into a single ur_description

I wonder if the joint inertias are different. It's been a long time, over a year, since I was working with the ROS 1 driver in Gazebo so my memory is kind of fuzzy, but I think there were some changes to the UR10e inertias. Hopefully someone else can bring some clarity on that.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2022-11-02 06:43:24 -0500

Seen: 57 times

Last updated: Nov 07 '22