Gazebo | Ignition | Community
Ask Your Question
1

How to locate joint axes in SDF 1.3

asked 2013-06-18 17:56:48 -0500

PMilani gravatar image

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: image description

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: image description

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 ... (more)

edit retag flag offensive close merge delete

Comments

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.

AndreiHaidu gravatar imageAndreiHaidu ( 2013-06-19 03:03:05 -0500 )edit

Have a look at the answer below, the solution seems peculiar.

PMilani gravatar imagePMilani ( 2013-06-21 20:26:08 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
1

answered 2013-06-21 20:41:27 -0500

PMilani gravatar image

After inserting the model, I saved a couple of .world instances. In some of these the joint axis was properly located. I found that the difference between those where the axis was properly located and those where the axis wasn't was due to the <link> <pose> in the <state> element in the .world file being different to the <pose> for the link in the .model description. After changing this value in my .world files, making it equal to my .model elements the axis was correctly located.

.model file link description - note the pose values (with ** for emphasis)

<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>

These need to reflect the .world file <state> values, if they do not then there will be issues with correct location of axes:

<state world_name='default'>
      <sim_time>0 0</sim_time>
      <real_time>0 53614</real_time>
      <wall_time>1371509281 132633228</wall_time>
      <model name='HMM_version2'>
        <pose>0.000000 0.000000 2.000000 0.000000 0.000000 0.000000</pose>
        <link name='Gripper'>
          <pose>1.621480 **1.212000** 1.345880 0.000000 0.000000 1.570000</pose>
          <velocity>0.000000 0.000000 0.000000 0.000000 0.000000 0.000000</velocity>
          <acceleration>0.000000 0.000000 0.000000 0.000000 0.000000 0.000000</acceleration>
          <wrench>0.000000 0.000000 0.000000 0.000000 0.000000 0.000000</wrench>
        </link>
        <link name='Tool'>
          <pose>1.521480 0.962960 1.345880 1.570000 0.000000 0.000000</pose>
          <velocity>0.000000 0.000000 0.000000 0.000000 0.000000 0.000000</velocity>
          <acceleration>0.000000 0.000000 0.000000 0.000000 0.000000 0.000000</acceleration>
          <wrench>0.000000 0.000000 0.000000 0.000000 0.000000 0.000000</wrench>
        </link>

      </model>
    </state>

when the axis wasn't aligned the empasised element had a value of 1.013.

There seems to be three locations for implementing joint <pose> in the model. I have stuck to using only that related to links and leaving other poses as "0 0 0 0 0 0". It probably doesn't matter eitherway, but sticking to adjusting pose in only one location, either <joint> or <link> saves confusion and eases debugging.

edit flag offensive delete link more
0

answered 2013-06-27 19:08:55 -0500

nkoenig gravatar image

The <pose> within the <joint> element specifies an offset in the child link frame. You can use the <pose> tag to position the joint relative to the child link.

edit flag offensive delete link more
Login/Signup to Answer

Question Tools

1 follower

Stats

Asked: 2013-06-18 17:56:48 -0500

Seen: 1,951 times

Last updated: Jun 27 '13