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

Adding doors in gazebo

asked 2012-07-05 06:39:44 -0500

prasanna.kumar gravatar image

updated 2012-07-05 06:41:33 -0500

Hi,

I want to add doors to the world that I have created in Gazebo. Basically I have modelled the entire house with furnitures and without doors. I want to add doors now. My plan is, for each door 1. Create an hinge - cylinder of radius 0.1 and length 0.2
2. Door that partially covers the hinge (as in real world). 3. A revolute joint along z axis at the intersection.

This is the code I use

<robot name="Work_room_door">
  <link name="hinge">
    <inertial>
      <origin xyz="0 0 1.125"/> 
      <mass value="0.5" />
      <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.125" rpy="0 0 0" />
      <geometry>
        <cylinder length="0.2" radius="0.05"/>
      </geometry>
    </visual>
  </link>

  <link name="door">
     <inertial>
      <origin xyz="0 0.2 1.125"/> 
      <mass value="5.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.2 1.125" rpy="0 0 1.57" />
      <geometry>
        <box size="0.4 .1 2.2"/>
      </geometry>
    </visual>
  </link>

  <joint name="door_hinge" type="revolute">
    <parent link="hinge"/>
    <child link="door"/>
    <origin xyz="0 0.225 1.125"/>
    <axis xyz="0 0 1"/>
    <limit effort="15.0" lower="-1.57" upper="1.57" velocity="1"/>
  </joint>

</robot>

When I run the command

roslaunch urdf_tutorial display.launch model:=door.urdf gui:=True

When I control the joint using gui that comes up, the door does not swivel around the hinge. Rather, it is still without motion. Please, help me with this. How can I make the door swivel around the hinge ? or is there any other method to do it ? Thanks!

edit retag flag offensive close merge delete

Comments

was this ever resolved?

SL Remy gravatar image SL Remy  ( 2013-01-07 03:20:40 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2012-07-26 13:26:15 -0500

mcevoyandy gravatar image

seems to work as-is for me (axes may be off, but I'm not sure what you're going for). do you get any global status errors when rviz starts?

edit flag offensive delete link more

Question Tools

Stats

Asked: 2012-07-05 06:39:44 -0500

Seen: 2,155 times

Last updated: Jul 05 '12