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

Spawning care-o-bot gripper in gazebo

asked 2011-07-06 01:32:57 -0500

Bemfica gravatar image

updated 2011-07-06 06:18:21 -0500

mmwise gravatar image

Hi guys, and thanks in advance!

there is a way to spawn just the gripper of Care-o-Bot/PR2 in Gazebo? I tried:

export ROBOT=cob3-2
roslaunch gazebo_worlds empty_world.launch
rosrun gazebo spawn_model -file `pwd`/sdh.urdf.xacro -urdf -z 1 -model my_hand

but it didn't work and being honest I'm not sure about what I'm doing. Could someone indicates me some document/tutorial? I did the cob_bringup tutorial but it explain you how to simulate all the robot together. Thanks again.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
2

answered 2011-07-07 06:44:42 -0500

hsu gravatar image

You can wrap the xacro in your own model file, anchoring the gripper to a dummy link:

<?xml version="1.0"?>
<robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
       xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
       xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
       xmlns:xacro="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
       name="sdh" >

  <!-- The following included files set up definitions of parts of the robot body -->
  <!-- cob sdh-->
  <include filename="$(find cob_description)/ros/urdf/sdh_v0/sdh.urdf.xacro" />

  <!-- foot for arm-->
  <link name="dummy_link">
          <inertial>
             <origin xyz="0 0 -10" rpy="0 0 0"/>
             <mass value="1000.0"/>
             <inertia ixx="100.0"  ixy="0"  ixz="0" iyy="100.0" iyz="0" izz="100.0" />
          </inertial>

          <visual>
             <origin xyz="0 0 0.25" rpy="0 0 0" />
             <geometry>
                    <box size="0.6 0.4 0.4"/>
                    <!--cylinder radius="0.1" length="0.5"/-->
             </geometry>
             <material name="Blue" />
          </visual>

          <collision>
             <origin xyz="0 0 0.25" rpy="0 0 0" />
             <geometry>
                    <box size="0.6 0.4 0.4"/>
                    <!--cylinder radius="0.1" length="0.5"/-->
             </geometry>
          </collision>
  </link>

  <!-- sdh -->
  <xacro:cob_sdh_v0 name="sdh" parent="dummy_link">
    <origin xyz="0 0 0" rpy="0 3.1415926 0" />
  </xacro:cob_sdh_v0>

</robot>

save it as test.urdf.xacro in your own ros package (my_own_foo_ros_pkg). Then construct a launch script to push the xacro file onto the parameter server:

<launch>
  <!-- send pr2 urdf to param server -->
  <param name="robot_description" command="$(find xacro)/xacro.py '$(find my_own_foo_ros_pkg)/test.urdf.xacro'" />
</launch>
edit flag offensive delete link more
2

answered 2011-07-06 07:12:40 -0500

hsu gravatar image

sdh.urdf.xacro is a xacro file, you need to convert it into urdf first. You'll need some code somewhere that makes use of the cob_sdh_v0 macro described in the xacro file. For example, when the gripper is attached to the arm arm_sdh.urdf.xacro, it is invoked by following code blocks:

<!-- cob sdh-->
<include filename="$(find cob_description)/ros/urdf/sdh_v0/sdh.urdf.xacro" />
<!-- sdh -->
<xacro:cob_sdh_v0 name="sdh" parent="arm_7_link">
  <origin xyz="0 0 0" rpy="0 3.1415926 0" />
</xacro:cob_sdh_v0>

I suggest taking a look at the tutorials in xacro and urdf packages first.

John

edit flag offensive delete link more

Comments

okay. Thank you man! I'll read the xacro tutorials again and I'll try this conversion. I was trying to edit the "main" launch file (sim.launch/cob3-2.launch) to cut off the parts that I'm not interested to (torso/head/arm etc), is it the right way?
Bemfica gravatar image Bemfica  ( 2011-07-06 20:07:02 -0500 )edit

Question Tools

Stats

Asked: 2011-07-06 01:32:57 -0500

Seen: 580 times

Last updated: Jul 07 '11