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

screw joint in Gazebo

asked 2018-03-23 07:52:51 -0500

benqll gravatar image

updated 2020-03-30 04:44:01 -0500

fvd gravatar image

Hello,

I'm trying to simulate screw joints using Gazebo 7 and ROS Kinetic, like this but i am failed. Gazebo cannot parse the xacro when I added the screw type joint.

I have looked into the pr2_description, torso.gazebo.xacro, which is an example.

Can anyone give me an explanation of the screw type joint or sample code for a screw joint? Thank you.

Here is the error message:

Error [parser_urdf.cc:3474] Unable to call parseURDF on robot model
Error [parser.cc:341] parse as old deprecated model file failed.

Here is my code:

<?xml version="1.0"?>
<robot name="OBS">
<link name="base">
<inertial>
  <origin
    xyz="0 0.1 0"
    rpy="0 0 0" />
  <mass
    value="2" />
  <inertia
    ixx="0"
    ixy="0"
    ixz="0"
    iyy="0"
    iyz="0"
    izz="0" />
</inertial>
<visual>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://rov_props/meshes/OBS.STL" />
  </geometry>
  <material
    name="">
    <color
      rgba="1 0 0 1" />
  </material>
</visual>
<collision>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://rov_props/meshes/OBS.STL" />
  </geometry>
</collision>

 <buoyancy>
  <compensation>0.8</compensation>
  <origin xyz= "0 0 0"/>
  <limit radius="0.05"/>
  <damping xyz="50 50 60" rpy="50 50 50"/>
 </buoyancy>
</link>

<link name="leveling_arm1">
    <inertial>
      <origin
        xyz="0 0 0 "
        rpy="0 0 0" />
      <mass
        value="0.2" />
      <inertia
        ixx="-0.0"
        ixy="-0.0"
        ixz="-0.0"
        iyy="-0.0"
        iyz="-0.0"
        izz="-0.1" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://rov_props/meshes/levelingArm.STL" />
      </geometry>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://rov_props/meshes/levelingArm.STL" />
      </geometry>
    </collision>
     <buoyancy>
      <compensation>0.5</compensation>
      <origin xyz= "0 0 0"/>
      <limit radius="0.05"/>
      <damping xyz="50 50 60" rpy="50 50 50"/>
     </buoyancy>
</link>


    <joint name="screw_level1" type="screw">
        <parent link="base_link"/>
        <child link="leveling_arm1"/>
        <axis>
            <xyz>0 0 1</xyz>
        </axis>
        <thread_pitch>3141.6</thread_pitch>
    </joint>
</robot>
edit retag flag offensive close merge delete

Comments

Can you add the error message you get when parseing the URDF file, then we will be able to help you solve this one. The obvious mistake I could think of is a missing <thread_pitch> tag, but that's just a guess until we see the error message.

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2018-03-25 06:45:43 -0500 )edit

Pete Thank you for answering my question. I have updated the error message and my coding. i do not miss the <thread_pitch> that it may not be the problem.

benqll gravatar image benqll  ( 2018-03-29 09:51:13 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-03-29 10:40:32 -0500

Riss69 gravatar image

After understanding the implementation of screw joint in pr2's torso part. It is clear that URDF don't support screw joint, so to add the functionality of the same we have to use gazebo tags since SDF (For those who don't know:Under the hood gazebo converts urdf to sdf before spawning) totally supports it.

You also need to specify prismatic and continuous joints. Refer to pr2.urdf for full understanding. Following is the snippet from the mentioned above.

<gazebo>
<joint name="torso_lift_screw_torso_lift_joint" type="screw">
  <parent>torso_lift_link</parent>
  <child>torso_lift_motor_screw_link</child>
  <axis>
    <xyz>0 0 1</xyz>
  </axis>
  <thread_pitch>3141.6</thread_pitch>
  </joint>
 </gazebo>
 <transmission name="torso_lift_trans" type="pr2_mechanism_model/SimpleTransmission">
   <actuator name="torso_lift_motor"/>
<joint name="torso_lift_joint"/>
<mechanicalReduction>-47641.53</mechanicalReduction>
<simulated_actuated_joint name="torso_lift_motor_screw_joint" simulated_reduction="3141.6"/>
    </transmission>
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2018-03-23 07:52:51 -0500

Seen: 818 times

Last updated: Mar 30 '20