0
$\begingroup$

Rosanswers logo

Grasping is not working in this primitive case I've made. The object is a box of mass 1 and default friction and contact parameters. The gripper uses two prismatic joints to move two c-shaped links together. All these are shown in this image. Note the gripper-joint coordinate frames (the x- and z-direction vectors are visible).

image description

When the gripper closes on the box and the robot then moves upward, the box does not get lifted, as shown in this animation (it's for a taller gripper than above but the behavior is identical, also the gripper in the animation used just one prismatic joint). Since the normal force between the gripper and box is 200 N (that's what I have the joint effort set at, as shown in the sdf below) then the lifting force should be at least 200 N, while 9.81 N should suffice to lift the box. Do you have an idea why the box doesn't go up?

image description

===== additional info Here's a link to my gazebosim question on the same topic with a slightly different grasping scenario. http://answers.gazebosim.org/question/20217/physics-problem-with-simple-movement-of-grasped-object/ =====

The following plots were made via

rqt_plot ft_senr_topic_p/wrench/force/x, ft_sensor_topic_p/wrench/force/z, ft_sensor_topic_d/wrench/force/x, ft_sensor_topic_d/wrench/force/z

to graph the x and z components of the joint forces for the two prismatic gripper joints. In this one the joints are controlled with the EffortJointInterface. When the x components drop down, at about 28.6 seconds, that's when the gripper is higher than the box and it closes.

image description

For this plot the gripper friction coefficient is changed to 100, which appears to have made no change.

image description

The final plot is with mu=100 and using the PositionJointInterface. At about 24.4 seconds On this one, the x-components drop down. That's when the robot starts to move upward (prior to that it's stationary with the gripper closed around the box). The spikes after that, at 24.8, are when the gripper clears the box. It's odd to me that one joint has a positive z-component and the other has a negative z-component of force.

image description

Update

In an attempt to circumvent this problem I made an object that's wider in the middle and gripper blocks to match it. In theory, if the gripper stayed at its closed position then friction would not be required for lifting the object. I increased the effort limit on the joints from 200 to 500.

With 'EffortJointInterface' the same problem occurs as with the box, and with the PositionJointInterface the grasp is unstable and the object goes flying away.

To battle the instability I changed max_vel and min_depth on both the gripper and object to 0 and 0.001, respectively. Alas, the simulation remained unstable with PositionJointInterface even with these changes.

Here is an animation and force plot when using EffortJointInterface.

image description

image description

Here is an animation and force plot when using PositionJointInterface.

image description

image description

Here is the sdf of the object.

<sdf version='1.6'>
  <model name='wideCone'>
    <link name='wideCone'>
      <pose frame=''>0 0 0 0 -0 0</pose>
      <inertial>
        <pose frame=''>-0 0 0.145 0 -0 0</pose>
        <mass>0.1</mass>
        <inertia>
          <ixx>0</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0</iyy>
          <iyz>0</iyz>
          <izz>0</izz>
        </inertia>
        <!--mass>9</mass>
        <inertia>
          <ixx>0.443658</ixx>
          <ixy>-4.45426e-18</ixy>
          <ixz>-4.19225e-18</ixz>
          <iyy>0.443658</iyy>
          <iyz>2.2175e-17</iyz>
          <izz>0.52339</izz>
        </inertia-->
      </inertial>
      <collision name='wideCone_collision'>
        <pose frame=''>0 0 0 1.5708 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://wideCone/meshes/wideCone.STL</uri>
          </mesh>
        </geometry>
    <surface>
      <!--friction>
        <ode>
          <mu>100.0</mu>
          <mu2>100.0</mu2>
        </ode>
      </friction-->
      <contact>
        <ode>
          <!--kp>1e9</kp>
          <kd>1e2</kd-->
          <max_vel>0</max_vel>
          <min_depth>0.001</min_depth>
        </ode>
      </contact>
    </surface>
      </collision>
      <visual name='wideCone_visual'>
        <pose frame=''>0 0 0 1.5708 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://wideCone/meshes/wideCone.STL</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
  </model>
</sdf>

Here is the gripper urdf xacro.

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


  <!-- Switch between EffortJointInterface and PositionJointInterface, still requires change in yaml files -->
  <xacro:property name="using_position_not_effort" value="true" />

  <!-- Constants for gripper joint controllers -->
  <xacro:property name="effort_limit" value="500" />
  <xacro:property name="gripper_friction" value="100" />
  <xacro:property name="gripper_min_depth" value="0.001" />

  <!-- Phantom link for center of gripper -->
  <link name="gripper_center" >
    <inertial>
      <mass value="0.01"/>
      <inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
    </inertial>
  </link>

  <!-- One side of gripper -->
  <link name="side_p" >
    <visual>
      <origin xyz="0 0.177 0" rpy="${pi / 2} 0 ${5 * pi / 8}" />
      <geometry>
    <mesh filename="package://mobile_manipulator/models/gripper_fake/meshes/gripperClaw.STL"/>
      </geometry>
    </visual>
    <collision>
      <origin xyz="0 0.177 0" rpy="${pi / 2} 0 ${5 * pi / 8}" />
      <geometry>
    <mesh filename="package://mobile_manipulator/models/gripper_fake/meshes/gripperClaw.STL"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="1" />
      <inertia ixx="0.01" ixy="0.005" ixz="0.0003" iyy="0.02" iyz="0.00004" izz="0.02" />
    </inertial>
  </link>

  <!-- Second side of gripper -->
  <link name="side_d" >
    <visual>
      <origin xyz="0 -0.177 0" rpy="${pi / 2} 0 ${-3 * pi / 8}" />
      <geometry>
    <mesh filename="package://mobile_manipulator/models/gripper_fake/meshes/gripperClaw.STL"/>
      </geometry>
    </visual>
    <collision>
      <origin xyz="0 -0.177 0" rpy="${pi / 2} 0 ${-3 * pi / 8}" />
      <geometry>
    <mesh filename="package://mobile_manipulator/models/gripper_fake/meshes/gripperClaw.STL"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="1" />
      <inertia ixx="0.01" ixy="0.005" ixz="0.0003" iyy="0.02" iyz="0.00004" izz="0.02" />
    </inertial>
  </link>
  

  <!-- Prismatic joint -->
  <joint name="gripper_joint_p" type="prismatic">
    <origin xyz="0 0 0" rpy="0 0 0" />
    <parent link="gripper_center" />
    <child link="side_p" />
    <limit effort="${effort_limit}" lower="-100" upper="100" velocity="0.5"/>
  </joint>
  
  <joint name="gripper_joint_d" type="prismatic">
    <origin xyz="0 0 0" rpy="0 0 0" />
    <parent link="gripper_center" />
    <child link="side_d" />
    <limit effort="${effort_limit}" lower="-100" upper="100" velocity="0.5"/>
  </joint>

  <!-- Transmission for ROS control -->
  <xacro:if value="${using_position_not_effort == 'true'}">
    <transmission name="gripper_joint_transmission_p">
      <type>transmission_interface/SimpleTransmission</type>
      <joint name="gripper_joint_p">
    <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
      </joint>
      <actuator name="gripper_joint_motor_p">
    <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    <mechanicalReduction>1</mechanicalReduction>
      </actuator>
    </transmission>
    
    <transmission name="gripper_joint_transmission_d">
      <type>transmission_interface/SimpleTransmission</type>
      <joint name="gripper_joint_d">
    <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
      </joint>
      <actuator name="gripper_joint_motor_d">
    <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    <mechanicalReduction>1</mechanicalReduction>
      </actuator>
    </transmission>
  </xacro:if>
  
  <xacro:if value="${using_position_not_effort == 'false'}">
    <transmission name="gripper_joint_transmission_p">
      <type>transmission_interface/SimpleTransmission</type>
      <joint name="gripper_joint_p">
    <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      </joint>
      <actuator name="gripper_joint_motor_p">
    <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    <mechanicalReduction>1</mechanicalReduction>
      </actuator>
    </transmission>
    
    <transmission name="gripper_joint_transmission_d">
      <type>transmission_interface/SimpleTransmission</type>
      <joint name="gripper_joint_d">
    <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      </joint>
      <actuator name="gripper_joint_motor_d">
    <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    <mechanicalReduction>1</mechanicalReduction>
      </actuator>
    </transmission>
  </xacro:if>
  

  <!-- Enable joint feedback -->
  <gazebo reference="gripper_joint_p">
    <provideFeedback>true</provideFeedback>
  </gazebo>
  
  <gazebo reference="gripper_joint_d">
    <provideFeedback>true</provideFeedback>
  </gazebo>
  
  <!-- ft_sensor plugin -->
  <gazebo>
    <plugin name="ft_sensor_p" filename="libgazebo_ros_ft_sensor.so">
      <updateRate>100.0</updateRate>
      <topicName>ft_sensor_topic_p</topicName>
      <jointName>gripper_joint_p</jointName>
    </plugin>
  </gazebo>
  
  <gazebo>
    <plugin name="ft_sensor_d" filename="libgazebo_ros_ft_sensor.so">
      <updateRate>100.0</updateRate>
      <topicName>ft_sensor_topic_d</topicName>
      <jointName>gripper_joint_d</jointName>
    </plugin>
  </gazebo>
  
  <!-- High friction on gripper -->
  <gazebo reference="gripper_wide_block_p">
    <mu1>${gripper_friction}</mu1>
    <mu2>${gripper_friction}</mu2>
    <minDepth>${gripper_min_depth}</minDepth>  
    <maxVel>0</maxVel>
  </gazebo>
  
  <gazebo reference="gripper_wide_block_d">
    <mu1>${gripper_friction}</mu1>
    <mu2>${gripper_friction}</mu2>
    <minDepth>${gripper_min_depth}</minDepth>  
    <maxVel>0</maxVel>
  </gazebo>

</robot>

Thanks for your time!

Edit: Do you think this strange behavior could be from using Gazebo 9 with the latest version of gazebo_ros_pkgs, which was done as a fix for an earlier problem?


Originally posted by raequin on ROS Answers with karma: 368 on 2018-05-15

Post score: 5


Original comments

Comment by jayess on 2018-05-15:
Your second image didn't attach. Can you please try again?

Comment by PeteBlackerThe3rd on 2018-05-15:
Is there a reason why the surface properties of the box are commented out?

Comment by raequin on 2018-05-15:
@jayess, the animation is now attached.

@PeteBlackerThe3rd, the surface properties of the box are commented out because changing them made no difference so I just reverted to the default values.

Comment by gvdhoorn on 2018-05-16:
Tbh I believe this is more a Gazebo issue for now. Seeing as you're using SDF exclusively here and we're talking about interaction with objects in the dynamic simulation, perhaps posting this to answers.gazebosim.org would result in better/faster/more answers.

Comment by raequin on 2018-05-16:
@gvdhoorn, Tbh I had intended to post it on the gazebosim forum but it was the end of the day and I was hurrying and ended up using this one instead :) Thanks for the advice, I'll go post it there now. One thing, though, the gripper sdf was generated from a urdf xacro file.

Comment by gvdhoorn on 2018-05-16:
re: xacro/sdf: I don't believe that really matters -- for now. This seems to be something to do with interaction of various objects in the Gazebo world, and as such will probably have something to do with either the static model of your sim, or the sim (object) properties. Gazebo ppl will ..

Comment by gvdhoorn on 2018-05-16:
.. probably know more about this.

If you do end up posting there, please post a link here so we can keep things connected.

And if possible -- and you remember -- if you solve it, please post here as well.

If it does turn out to be on the ROS side, you can continue here.

Comment by raequin on 2018-05-16:
Thanks @gvdhoorn. Would you check out the update I made to this question and see if the gazebo_ros_control elements are working as you'd expect?

Comment by PeteBlackerThe3rd on 2018-05-16:
Have you tried giving the box a mass of zero to see what happens then. It appears to be behaving as if it weighs a metric ton!

Comment by raequin on 2018-05-16:
@PeteBlackerThe3rd it's interesting, when I set the mass to 0.0001 or zero the object (box or cylinder thing) acts massive, but when I set mass to 0.01 it works a little better. With PositionJointInterface I can pick it up, but is unstable. With EffortJointInterface it still slides through.

Comment by fvd on 2018-09-05:
Have you posted this on gazebosim? Please update with a link if you have. Contacts are notoriously hard to simulate, and this is definitely a question that belongs there.

Comment by raequin on 2018-09-05:
Thanks, @fdv, I will add a gazebosim link. I've read before that contacts are hard to simulate in Gazebo, and so people have trouble grasping objects, but yet I've also seen a couple of success stories and my mobile robot wheels interact well with the ground plane so there must be an answer :)

Comment by saikishor on 2018-09-19:
I am using the Position Joint Interface, but I am facing a similar issue. I am able to grasp, but later after grasping, If I am performing any motion, then the grippers open due to some unknown reasons, and the grasp object falls off. Any idea regd. this?. I am in Gazebo 7 now, but worked in 2.2.5

Comment by jayess on 2018-09-19:
@Sai Kishor Kothakota please create a new question and reference this one. Your question will be more visible that way.

Comment by saikishor on 2018-09-19:
@jayess I am referring to this one http://answers.gazebosim.org/question/20490/issue-with-the-post-grasp-motion-in-gazebo/

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

The cause behind this unrealistic interaction (that is, this lack of friction) is the use of PositionJointInterface for the UR10 joints. Here's a decent explanation of the phenomenon:

... using 'set position' or 'set velocity' in gazebo forces the physics simulation to try and accomplish this, which results in strange behavior. It's actually preferable, according to the Gazebo team members I'm working with, to always use 'set force' in Gazebo because that allows a more normal interaction when the commanded force of an arm joint puts the arm in contact with the environment.

Following an example, I made local changes to the universal_robot package to use EffortJointInterface instead. Some gain values from ARIAC provide decent performance. Thanks to everyone who contributed suggestions!


Originally posted by raequin with karma: 368 on 2018-09-17

This answer was ACCEPTED on the original site

Post score: 3

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.