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

Defining Joints in Solidworks to URDF Exporter for a Conveyor Belt

asked 2013-01-15 04:16:27 -0500

RebeccaK375 gravatar image

updated 2013-01-15 04:34:23 -0500

Dear all,

I am trying to create a working conveyor belt in Gazebo. I built a conveyor in SolidWorks and used the Solidworks to URDF Exporter to generate the URDF file.

The belt appears in Gazebo just fine, but I cannot get it to actually move when effort is applied to a Cylinder.

Image of Conveyor Belt in Question: image description

I think the problem is my definition of links and joints in the Solidworks to URDF Exporter (and the URDF file that is generated).

Here us the URDF File:

<robot
  name="Belt1_BeltLink_2Joints_Velocity_Effort_1Joint">
  <link
    name="belt_link">
    <inertial>
      <origin
        xyz="0.6096 2.7377E-15 -3.81"
        rpy="0 0 0" />
      <mass
        value="44.292" />
      <inertia
        ixx="273.86"
        ixy="4.3225E-28"
        ixz="5.8096E-16"
        iyy="273.75"
        iyz="1.1641E-14"
        izz="7.7268" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://Belt1_BeltLink_2Joints_Velocity_Effort_1Joint/meshes/belt_link.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.79216 0.81961 0.93333 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://Belt1_BeltLink_2Joints_Velocity_Effort_1Joint/meshes/belt_link.STL" />
      </geometry>
    </collision>
  </link>
    <gazebo reference="belt_link">
      <material>Gazebo/FlatBlack</material>
    </gazebo>
  <link
    name="cylinder1_link">
    <inertial>
      <origin
        xyz="0.0013099 -0.6096 -6.1529E-18"
        rpy="0 0 0" />
      <mass
        value="767.9" />
      <inertia
        ixx="114.77"
        ixy="4.9176E-15"
        ixz="-1.3005E-17"
        iyy="39.109"
        iyz="6.0768E-31"
        izz="114.58" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://Belt1_BeltLink_2Joints_Velocity_Effort_1Joint/meshes/cylinder1_link.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.79216 0.81961 0.93333 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://Belt1_BeltLink_2Joints_Velocity_Effort_1Joint/meshes/cylinder1_link.STL" />
      </geometry>
    </collision>
  </link>
  <joint
    name="cylinder1_joint"
    type="continuous">
    <origin
      xyz="0 0 0"
      rpy="1.5708 -1.5708 0" />
    <parent
      link="belt_link" />
    <child
      link="cylinder1_link" />
    <axis
      xyz="0 1 0" />
    <limit
      effort="10"
      velocity="5" />
  </joint>
  <link
    name="cylinder2_link">
    <inertial>
      <origin
        xyz="0.0013099 -0.6096 0"
        rpy="0 0 0" />
      <mass
        value="767.9" />
      <inertia
        ixx="114.77"
        ixy="4.8695E-15"
        ixz="-6.0881E-16"
        iyy="39.109"
        iyz="5.158E-31"
        izz="114.58" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://Belt1_BeltLink_2Joints_Velocity_Effort_1Joint/meshes/cylinder2_link.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.79216 0.81961 0.93333 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://Belt1_BeltLink_2Joints_Velocity_Effort_1Joint/meshes/cylinder2_link.STL" />
      </geometry>
    </collision>
  </link>
  <joint
    name="cylinder2_joint"
    type="continuous">
    <origin
      xyz="0 7.62 0"
      rpy="1.5708 -1.5708 0" />
    <parent
      link="belt_link" />
    <child
      link="cylinder2_link" />
    <axis
      xyz="0 1 0" />
  </joint>
</robot>

Does anyone know how I would define joints and links in SW to URDF Exporter/ URDF in order for the belt to move when torque is applied on one of the cylinders?

I also tried applying joint effort using this:

rosservice call gazebo/apply_joint_effort '{joint_name: cylinder2_joint, effort: 10, start_time: 10000000000, duration: 1000000000}'

Thank you for your help!

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
3

answered 2013-01-15 05:03:55 -0500

brawner gravatar image

I think this problem is trickier than you first assume. Gazebo doesn't yet support deformable materials, it is a rigid body constraint solver. Thus, a belt can only be approximated in Gazebo by a chain of many links. However, URDF is generally used for describing robots and has further constraints over SDF. The important one being that SDF can support closed chains, but URDF can't. Nonetheless, creating an SDF of a belt chain riding on two cylinders may be more trouble than it's worth, if what you're trying to do is approximate a conveyer belt in Gazebo.

One solution to your trouble that avoids the above complexity is to add a static table with no friction and place your block on top. Then create a gazebo plugin or ros node that sets the velocity of the block. See section 6: Set and Get Model Pose and Twist in Simulation via service.

edit flag offensive delete link more

Comments

Thank you for advise! I think I will just do that instead. I will also try working with a chain of links and see if that works.

RebeccaK375 gravatar image RebeccaK375  ( 2013-01-15 05:21:14 -0500 )edit
4

answered 2013-01-15 05:29:37 -0500

RebeccaK375 gravatar image

updated 2013-01-15 05:42:37 -0500

As suggested by branwer, if anyone is trying to make a conveyor belt simulation, you can use the following steps:

1) Create a simple black box object that resembles a belt (I named this file "moving_ground.URDF":

<?xml version="1.0" ?>
<robot name="simple_box">
  <link name="my_box">
    <inertial>
      <origin xyz="0 0 0" /> 
      <mass value="1.0" />
      <inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="100.0"  iyz="0.0"  izz="1.0" />
    </inertial>
    <visual>
      <origin xyz="0 0 0"/>
      <geometry>
        <box size="1 1000 0.01" />
      </geometry>
    </visual>
    <collision>
      <origin xyz="0 0 0"/>
      <geometry>
        <box size="1000 1 0.01" />
      </geometry>
    </collision>
  </link>
  <gazebo reference="my_box">
    <material>Gazebo/FlatBlack</material>
  </gazebo>
</robot>

2) Create a sample object that will go on top of the belt (so you can verify the belt is moving) (I named this file my_box.URDF)

<robot name="simple_box">
  <link name="my_box">
    <inertial>
      <origin xyz="0 0 0" /> 
      <mass value="1.0" />
      <inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="100.0"  iyz="0.0"  izz="1.0" />
    </inertial>
    <visual>
      <origin xyz="0 0 1"/>
      <geometry>
        <box size="0.5 0.5 0.5" />
      </geometry>
    </visual>
    <collision>
      <origin xyz="0 0 1"/>
      <geometry>
        <box size="0.5 0.5 0.5" />
      </geometry>
    </collision>
  </link>
  <gazebo reference="my_box">
    <material>Gazebo/Blue</material>
  </gazebo>
</robot>

3) Open an empty world in gazebo and spawn these two objects:

rosrun gazebo spawn_model -file moving_ground.URDF -urdf -model belt
rosrun gazebo spawn_model -file my_box.URDF -urdf -model my_box

4) Apply a wrench on the belt:

rosservice call /gazebo/apply_body_wrench '{body_name: "belt::my_box", reference_frame: "belt::my_box", wrench: { force: { x: 0, y: 1, z: 0 } }, start_time: 0, duration: -1 }'

And ta daaaa.... It worked for me. Hopefully it will work for you.

This is what it looks like:

Conveyor_Belt

edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2013-01-15 04:16:27 -0500

Seen: 3,702 times

Last updated: Jan 15 '13