How to locate joint axes in SDF 1.3
Hi All,
I'm trying to build a simple gripper. Simple in that a palm and finger are part of the same rigid body and the other finger simply swivels into it, like crocodile jaws.
However I'm having difficulty getting the movable part to rotate about the desired axes. When I switch on view->joints in the menu, the joints gyph (black writing) shows where the joint ought to be as in the picture below:
I am trying to get it rotate about the rigid part of the gripper is as shown in orange. However, my gripper actually seems to be rotating about the green icon which is neither where the joint is shown or where it is intended to rotate.
To demonstrate a picture of the gripper closed is shown below, as you can see Joint8 has moved about the apparent axis of rotation:
My model file pertaining to the gripper is shown here (link:Tool is the rigid part, link:gripper is the moving part):
<link name="Tool">
<pose> 1.52148 0.96296 -0.654121 0 0 0</pose>
<visual name="Tool_visual">
<geometry>
<mesh>
<uri>file://gazebo_ros_plugin/models/meshes/gripper_v2_static.stl</uri>
<scale>1 1 1</scale>
</mesh>
</geometry>
<pose> 0 0 0 0 0 0</pose>
<material>
<script>Gazebo/Grey</script>
</material>
</visual>
<collision name="Tool_collision">
<geometry>
<mesh>
<uri>file://gazebo_ros_plugin/models/meshes/gripper_v2_static.stl</uri>
<scale>1 1 1</scale>
</mesh>
</geometry>
<pose> 0 0 0 0 0 0</pose>
</collision>
<inertial>
<inertia>
<ixx>0.34</ixx>
<ixy>0.000039</ixy>
<ixz>-0.001386</ixz>
<iyy>0.0649</iyy>
<iyz>-0.000114</iyz>
<izz>0.296312</izz>
</inertia>
<pose> 0.000 0.000 0.0 0 0 0</pose>
<mass>2.414</mass>
</inertial>
</link>
<link name="Gripper">
<pose> 1.60148 1.212 -0.654121 0 0 0</pose>
<visual name="Gripper_visual">
<geometry>
<mesh>
<uri>file://gazebo_ros_plugin/models/meshes/gripper_v2_movable.stl</uri>
<scale>2 1 1</scale>
</mesh>
</geometry>
<pose> 0 0.00 0 0 0 0</pose>
<material>
<script>Gazebo/Yellow</script>
</material>
</visual>
<collision name="Gripper_collision">
<geometry>
<mesh>
<uri>file://gazebo_ros_plugin/models/meshes/gripper_v2_movable.stl</uri>
<scale>2 1 1</scale>
</mesh>
</geometry>
<pose> 0 0 0 0 0 0</pose>
</collision>
<inertial>
<inertia>
<ixx>0.00182</ixx>
<ixy>0.0000</ixy>
<ixz>-0.000192</ixz>
<iyy>0.00907</iyy>
<iyz>0</iyz>
<izz>0.007607</izz>
</inertia>
<pose> 0.000 0.000 0.0 0 0 0</pose>
<mass>2.447</mass>
</inertial>
</link>
And the joint8 location:
<joint name="joint8" type="revolute">
<pose>0 0 0 0 0 0</pose>
<parent>Tool</parent>
<child>Gripper</child>
<axis>
<limit>
<lower>-0.5</lower>
<upper>1.1</upper>
<effort>4000</effort>
<velocity>0.171</velocity>
</limit>
<dynamics>
<damping>100</damping>
<friction>100</friction>
</dynamics>
<xyz>0 0 1</xyz>
</axis>
</joint>
The majority of the model has been exported from a sdf-1.0 file. all the other joints and meshes work pretty much correctly.
Can anyone suggest some adjustments to my pose arrangements ...
Did you try offsetting the pose of the joint to the wished position, right now is in `pose 0 0 0 0 0 0 pose` which I guess it means the parents pose.
Have a look at the answer below, the solution seems peculiar.