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

Prismatic joint with PositionJointInterface interferes with Gazebo physics

asked 2017-03-11 15:23:52 -0500

gudjon gravatar image

updated 2017-03-12 13:23:23 -0500

I working on a simulation model of a forklift using ROS control and Gazebo. I'm using a prismatic joint to simulate the piston moving the forks up and down. Since I added a PositionJointInterface to the joint transmission I have been having issues with the physics. It seams to fix the joint in place. If I put the forklift in the air it hangs there, swinging by the joint, instead of falling down. This does not happen if I use the VelocityJointInterface or EffortJointInterface.

Is this a bug or am I using the position controller incorrectly?

Forklift refusing to fall

Here is the transmission

  <transmission name="lift_transmission">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="lift1_joint">
      <hardwareInterface>PositionJointInterface</hardwareInterface>
    </joint>  
    <actuator name="lift_motor">
      <hardwareInterface>PositionJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>

Here is the joint and link definition

  <joint name="lift1_joint" type="prismatic">
    <parent link="forklift_body"/>
    <child link="forklift_lift1"/>
    <axis xyz="0 0 1"/>
    <limit lower="0" upper="3" effort="1000" velocity="0.2"/>
  </joint>
  <link name="forklift_lift1">
    <collision>
      <origin xyz="0 -1.44 0.695" rpy="0 0 0"/>
      <geometry>
       <box size="1.2 0.1 1.25"/>
      </geometry>
    </collision>
    <collision>
      <origin xyz="0.32 -2.1 0.06" rpy="0 0 0"/>
      <geometry>
       <box size="0.13 1.2 0.03"/>
      </geometry>
    </collision>
    <collision>
      <origin xyz="-0.32 -2.1 0.06" rpy="0 0 0"/>
      <geometry>
       <box size="0.13 1.2 0.03"/>
      </geometry>
    </collision>    

    <visual>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
       <mesh filename="package://forklift_description/meshes/forklift_lift1.dae"/>
      </geometry>
    </visual>

    <inertial>
      <origin xyz="0 -1.4 0.4" rpy="0 0 0"/>
      <mass value="${lift1_mass}"/>
      <cube_inertia m="${lift1_mass}" w="1" h="1" d="0.2" />
    </inertial>
  </link>
edit retag flag offensive close merge delete

Comments

So without ros_control / the PositionJointInterface in the mix, everything works?

gvdhoorn gravatar image gvdhoorn  ( 2017-03-12 04:12:08 -0500 )edit

Yes, it seems to work with anything but the PositionJointInterface. My current workaround is to use VelocityJointInterface and JointVelocityController.

Now I just noticed that the same issue happens when I use the PositionJointInterface on a revolving joint. That seems weird to me.

gudjon gravatar image gudjon  ( 2017-03-12 10:07:15 -0500 )edit

Hm. Interesting. I can't promise you it'll get diagnosed sooner, but perhaps if you create an MWE others can try to reproduce your issue. It would also help if/when you report this to the tracker.

gvdhoorn gravatar image gvdhoorn  ( 2017-03-13 03:21:18 -0500 )edit

That sounds like the same problem I have. I am trying to create a model for the Farmbot. A gantry. I thought it already worked. But now I tried to get it working. With the controller the joint it just does weired things, rotating like a helicopter including moving a very heavy dirt block

cyborg-x1 gravatar image cyborg-x1  ( 2017-05-31 14:56:45 -0500 )edit

First I though I have a inertia problem but when I remove that joints - everything is just fine. I will try your hint to use the other controllers now.

cyborg-x1 gravatar image cyborg-x1  ( 2017-05-31 14:59:54 -0500 )edit

I have the same issue. Same type of joint. If i remove the transmission the problem is not there anymore but i cannot control the joint.

SorinV gravatar image SorinV  ( 2017-07-10 09:39:56 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
0

answered 2017-05-31 19:14:13 -0500

It seems to be a bug, I proposed a fix for it: https://github.com/ros-simulation/gaz...

edit flag offensive delete link more
1

answered 2017-07-10 11:07:18 -0500

SorinV gravatar image

updated 2017-07-11 02:46:01 -0500

I managed to use velocity_controllers/JointPositionController instead of position_controllers/JointPositionController with the prismatic joint. You just need to add a PID for it. Here's an example.

Before:

arm_controller:
  type: "position_controllers/JointPositionController"
  joint: arm_joint

After:

arm_controller:
  type: "velocity_controllers/JointPositionController"
  joint: arm_joint
  pid: {p: 100.0, i: 0.01, d: 1.0}

And for the transmission:

<hardwareInterface>hardware_interface/VelocityJointInterface </hardwareInterface>
edit flag offensive delete link more

Question Tools

4 followers

Stats

Asked: 2017-03-11 15:23:52 -0500

Seen: 4,729 times

Last updated: Jul 11 '17