Cannot control gripper to grasp object in gazebo
Hi everybody,I had this problem when doing gazebo simulation:when I use an gripper to grasp a small box in gazebo,the gripper is not able to move the box,and has a deformation(shown as follows)
I wonder if the problem is about the configuration of PID and inertial parameters
I control the gripper using an action client to send a FollowJointTrajectoryGoal,the code is as follows:
# close griper
gripper_goal = FollowJointTrajectoryGoal()
gripper_goal.trajectory = gripper_traj_close
gripper_goal.goal_time_tolerance = rospy.Duration(0.0)
gripper_client.send_goal(gripper_goal)
gripper_client.wait_for_result(rospy.Duration(5.0))
the fripper controller file is as follows:
gripper_controller:
type: position_controllers/JointTrajectoryController
joints:
- finger_joint
gains:
finger_joint: {p: 50, d: 1, i: 0.01, i_clamp: 1}
constraints:
goal_time: 0.5 # Override default
state_publish_rate: 25 # Override default
action_monitor_rate: 30 # Override default
stop_trajectory_duration: 0 # Override default
the xacro file of the gripper is as follows:
<?xml version="1.0"?>
<link name="${prefix}${fingerprefix}_outer_knuckle">
<inertial>
<origin xyz="-0.000200000000003065 0.0199435877845359 0.0292245259211331" rpy="0 0 0" />
<mass value="0.00853198276973456" />
<inertia ixx="2.89328108496468E-06" ixy="-1.57935047237397E-19" ixz="-1.93980378593255E-19" iyy="1.86719750325683E-06" iyz="-1.21858577871576E-06" izz="1.21905238907251E-06" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://iiwa_description/meshes/gripper/visual/robotiq_arg2f_85_outer_knuckle.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://iiwa_description/meshes/gripper/collision/robotiq_arg2f_85_outer_knuckle.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="${prefix}${fingerprefix}_outer_finger">
<inertial>
<origin xyz="0.00030115855001899 0.0373907951953854 -0.0208027427000385" rpy="0 0 0" />
<mass value="0.022614240507152" />
<inertia ixx="1.52518312458174E-05" ixy="9.76583423954399E-10" ixz="-5.43838577022588E-10" iyy="6.17694243867776E-06" iyz="6.78636130740228E-06" izz="1.16494917907219E-05" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://iiwa_description/meshes/gripper/visual/robotiq_arg2f_85_outer_finger.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://iiwa_description/meshes/gripper/collision/robotiq_arg2f_85_outer_finger.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="${prefix}${fingerprefix}_inner_knuckle">
<inertial>
<origin xyz="0.000123011831763771 0.0507850843201817 0.00103968640075166" rpy="0 0 0" />
<mass value="0.0271177346495152" />
<inertia ixx="2.61910379223783E-05" ixy="-2.43616858946494E-07" ixz="-6.37789906117123E-09" iyy="2.8270243746167E-06" iyz="-5.37200748039765E-07" izz="2.83695868220296E-05" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://iiwa_description/meshes/gripper/visual/robotiq_arg2f_85_inner_knuckle.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://iiwa_description/meshes/gripper/collision/robotiq_arg2f_85_inner_knuckle.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="${prefix}${fingerprefix}_inner_finger">
<inertial>
<origin xyz="0.000299999999999317 0.0160078233491243 -0.0136945669206257" rpy="0 0 0" />
<mass value="0.0104003125914103" />
<inertia ixx="2.71909453810972E-06" ixy="1.35402465472579E-21" ixz="-7.1817349065269E-22" iyy="7.69100314106116E-07" iyz="6.74715432769696E-07" izz="2.30315190420171E-06" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://iiwa_description/meshes/gripper/visual/robotiq_arg2f_85_inner_finger.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://iiwa_description/meshes/gripper/collision/robotiq_arg2f_85_inner_finger.dae" scale="0.001 0.001 0.001" />
</geometry>
</collision>
</link>
<!-- Finger pad link, the default are the "big pads" with rubber-->
<link name="${prefix}${fingerprefix}_inner_finger_pad">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.022 0.00635 0.0375"/>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.022 0.00635 0.0375"/>
</geometry>
<material name="">
<color rgba="0.9 0.0 0.0 1" />
</material>
</collision>
</link>
<joint name="${prefix}${fingerprefix}_outer_finger_joint" type="fixed">
<origin xyz="0 0.0315 -0.0041" rpy="0 0 0"/>
<parent link="${prefix}${fingerprefix}_outer_knuckle" />
<child link="${prefix}${fingerprefix}_outer_finger" />
<axis xyz="1 0 0" />
</joint>
<joint name="${prefix}${fingerprefix}_inner_knuckle_joint" type="revolute">
<!-- <origin xyz="0 ${reflect * -0.0127} 0.06142" rpy="${pi / 2 + .725} 0 ${(reflect - 1) * pi / 2}" /> -->
<origin xyz="0 ${reflect * -0.0127} 0.06142" rpy="0 0 ${(1 + reflect) * pi / 2}"/>
<parent link="${prefix}robotiq_arg2f_base_link" />
<child link="${prefix}${fingerprefix}_inner_knuckle" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0.8757" velocity="2.0" effort="1000" />
<mimic joint="${prefix}finger_joint" multiplier="1" offset="0" />
</joint>
<joint name="${prefix}${fingerprefix}_inner_finger_joint" type="revolute">
<origin xyz="0 0.0061 0.0471" rpy="0 0 0"/>
<parent link="${prefix}${fingerprefix}_outer_finger" />
<child link="${prefix}${fingerprefix}_inner_finger" />
<axis xyz="1 0 0" />
<limit lower="-0.8757" upper="0" velocity="2.0" effort="1000" />
<mimic joint="${prefix}finger_joint" multiplier="-1" offset="0" />
</joint>
<joint name="${prefix}${fingerprefix}_inner_finger_pad_joint" type="fixed">
<origin xyz="0 -0.0220203446692936 0.03242" rpy="0 0 0"/>
<parent link="${prefix}${fingerprefix}_inner_finger" />
<child link="${prefix}${fingerprefix}_inner_finger_pad" />
<axis xyz="0 0 1" />
</joint>
<!-- import robotiq_arg2f.xacro /-->
<joint name="${prefix}finger_joint" type="revolute">
<origin xyz="0 -0.0306011 0.054904" rpy="0 0 ${pi}"/>
<parent link="${prefix}robotiq_arg2f_base_link" />
<child link="${prefix}left_outer_knuckle" />
<axis xyz="1 0 0" />
<limit lower="0.01" upper="0.79" velocity="2.0" effort="1000" />
</joint>
<xacro:finger_joints prefix="${prefix}" fingerprefix="left" reflect="1.0"/>
<joint name="${prefix}right_outer_knuckle_joint" type="revolute">
<origin xyz="0 0.0306011 0.054904" rpy="0 0 0"/>
<parent link="${prefix}robotiq_arg2f_base_link" />
<child link="${prefix}right_outer_knuckle" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0.81" velocity="2.0" effort="1000" />
<mimic joint="${prefix}finger_joint" multiplier="1" offset="0" />
</joint>
<xacro:finger_joints prefix="${prefix}" fingerprefix="right" reflect="-1.0"/>
<!-- Initialization of all joints and links -->
<!-- This is the real position of the gripper defination -->
<xacro:robotiq_arg2f_base_link prefix="${prefix}" parent="${parent}"/>
<xacro:finger_links prefix="${prefix}" fingerprefix="left" stroke="85"/>
<xacro:finger_links prefix="${prefix}" fingerprefix="right" stroke="85"/>
<xacro:finger_joint prefix="${prefix}"/>
<xacro:right_outer_knuckle_joint prefix="${prefix}"/>
<xacro:robotiq_arg2f_transmission prefix="${prefix}"/>
Asked by Carrot12138 on 2020-06-07 04:31:21 UTC
Answers
Hello,
I think you have to provide PID parameter so that Gazebo can make dynamic simulation and not only kinematic. Moreover, I think that mimic joints are not supported by gazebo, but this may need confirmation...
Asked by Clément Rolinat on 2020-06-16 09:53:57 UTC
Comments
The gripper use a mimic plugin to control another finger,and I don't add PID parameters to the follow-up finger...I don't konw whether it's the problem
Asked by Carrot12138 on 2020-06-07 04:52:54 UTC