Prismatic joint with PositionJointInterface interferes with Gazebo physics
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?
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>
So without
ros_control
/ thePositionJointInterface
in the mix, everything works?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.
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.
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
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.
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.