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

Revision history [back]

I had a similar problem recently. AFAIK, Gazebo doesn't support mimic joints, and the gearbox joint cannot simulate arbitrary mimic joints. The way I've solved it is by adding a MimicJointPlugin to each mimic joint. What that plugin does is that it applies forces to the mimic joints so that they follow the mimiced joint.

This works in most cases, but it's not perfect; it depends on your use case. My use case was that I wanted to simulate a Robotiq 2 finger gripper, which is based on parallel kinematics. The end result using the MimicJointPlugin still had some issues, mainly that since URDF cannot represent closed kinematic chains, I had to break the loop somewhere (i.e., remove one joint in the closed chain), and that joint doesn't keep together when there is actually an object in the gripper; instead, the two loose ends of the chain flop around.

In SDF, you can actually represent closed kinematic chains. In many cases, this would even eliminate the need for mimic joints; if your mechanism is based on parallel kinematics, you can probably even just represent the closed kinematic chain directly and leave all joints unactuated except for the joint you're controlling, and things should just work because of physics. But I don't know if it's possible to just convert your URDF to SDF and use that in Gazebo together with ROS, and have everything else still work (like ros_control, sensor plugins, ...).

I had a similar problem recently. AFAIK, Gazebo doesn't support mimic joints, and the gearbox joint cannot simulate arbitrary mimic joints. The way I've solved it is by adding a MimicJointPlugin to each mimic joint. What that plugin does is that it applies forces to the mimic joints so that they follow the mimiced joint.

This works in most cases, but it's not perfect; it depends on your use case. My use case was that I wanted to simulate a Robotiq 2 finger gripper, which is based on parallel kinematics. The end result using the MimicJointPlugin still had some issues, mainly that since URDF cannot represent closed kinematic chains, I had to break the loop somewhere (i.e., remove one joint in the closed chain), and that joint doesn't keep together when there is actually an object in the gripper; instead, the two loose ends of the chain flop around.

In SDF, you can actually represent closed kinematic chains. In many cases, this would even eliminate the need for mimic joints; if your mechanism is based on parallel kinematics, you can probably even just represent the closed kinematic chain directly and leave all joints unactuated except for the joint you're controlling, and things should just work because of physics. But I don't know if it's possible to just convert your URDF to SDF and use that in Gazebo together with ROS, and have everything else still work (like ros_control, sensor plugins, ...).

EDIT:

To work around a bug in Gazebo, you should set the pid_gains parameter like this (assuming that gripper_right_outer_knuckle_joint etc. are your mimic joints):

gazebo_ros_control:
  pid_gains:
    # the following gains are used by the gazebo_mimic_joint plugin
    gripper_right_outer_knuckle_joint:
      p: 20.0
      i: 0.1
      d: 0.0
      i_clamp: 0.2
      antiwindup: false
      publish_state: true
    gripper_left_inner_knuckle_joint:
      [...]

I had a similar problem recently. AFAIK, Gazebo doesn't support mimic joints, and the gearbox joint cannot simulate arbitrary mimic joints. The way I've solved it is by adding a MimicJointPlugin to each mimic joint. What that plugin does is that it applies forces to the mimic joints so that they follow the mimiced joint.

This works in most cases, but it's not perfect; it depends on your use case. My use case was that I wanted to simulate a Robotiq 2 finger gripper, which is based on parallel kinematics. The end result using the MimicJointPlugin still had some issues, mainly that since URDF cannot represent closed kinematic chains, I had to break the loop somewhere (i.e., remove one joint in the closed chain), and that joint doesn't keep together when there is actually an object in the gripper; instead, the two loose ends of the chain flop around.

In SDF, you can actually represent closed kinematic chains. In many cases, this would even eliminate the need for mimic joints; if your mechanism is based on parallel kinematics, you can probably even just represent the closed kinematic chain directly and leave all joints unactuated except for the joint you're controlling, and things should just work because of physics. But I don't know if it's possible to just convert your URDF to SDF and use that in Gazebo together with ROS, and have everything else still work (like ros_control, sensor plugins, ...).

EDIT:

To work around a bug in Gazebo, you should set the pid_gains parameter like this (assuming that gripper_right_outer_knuckle_joint etc. are your mimic joints):

gazebo_ros_control:
  pid_gains:
    # the following gains are used by the gazebo_mimic_joint plugin
    gripper_right_outer_knuckle_joint:
      p: 20.0
      i: 0.1
      d: 0.0
      i_clamp: 0.2
      antiwindup: false
      publish_state: true
    gripper_left_inner_knuckle_joint:
      [...]

EDIT2:

I've written a tutorial package that demonstrates how to use the mimic joint plugin while avoiding the bug #612:

https://github.com/mintar/mimic_joint_gazebo_tutorial