|
From: <hsu...@us...> - 2009-08-24 16:15:37
|
Revision: 22695
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=22695&view=rev
Author: hsujohnhsu
Date: 2009-08-24 16:15:23 +0000 (Mon, 24 Aug 2009)
Log Message:
-----------
rid of wg_robot_description_parser dependence from gazebo_plugin.
update various models to reflect new urdf.
Modified Paths:
--------------
pkg/trunk/demos/door_demos_gazebo/door_defs/door_defs.xml
pkg/trunk/demos/examples_gazebo/dual_link_defs/dual_link.xml
pkg/trunk/demos/examples_gazebo/multi_link_defs/multi_link.xml
pkg/trunk/demos/examples_gazebo/simple_rdf_examples/simple_box.xml
pkg/trunk/demos/examples_gazebo/simple_rdf_examples/simple_cylinder.xml
pkg/trunk/demos/examples_gazebo/simple_rdf_examples/simple_sphere.xml
pkg/trunk/demos/examples_gazebo/single_link_defs/single_link.xml
pkg/trunk/demos/examples_gazebo/table_defs/table_defs.xml
pkg/trunk/demos/plug_in_gazebo/plug_defs/outlet_defs.xml
pkg/trunk/demos/plug_in_gazebo/plug_defs/plug_defs.xml
pkg/trunk/demos/pr2_gazebo/head_cart.launch
pkg/trunk/demos/pr2_gazebo/pr2.launch
pkg/trunk/demos/pr2_gazebo/prf.launch
pkg/trunk/demos/pr2_gazebo/prototype1.launch
pkg/trunk/drivers/simulator/test_pr2_collision_gazebo/test_slide.launch
pkg/trunk/drivers/simulator/test_pr2_sensors_gazebo/test_camera.launch
pkg/trunk/drivers/simulator/test_pr2_sensors_gazebo/test_scan.launch
pkg/trunk/stacks/simulator_gazebo/gazebo_tools/include/gazebo_tools/urdf2gazebo.h
pkg/trunk/stacks/simulator_gazebo/gazebo_tools/manifest.xml
pkg/trunk/stacks/simulator_gazebo/gazebo_tools/src/urdf2gazebo.cpp
Modified: pkg/trunk/demos/door_demos_gazebo/door_defs/door_defs.xml
===================================================================
--- pkg/trunk/demos/door_demos_gazebo/door_defs/door_defs.xml 2009-08-24 16:03:15 UTC (rev 22694)
+++ pkg/trunk/demos/door_demos_gazebo/door_defs/door_defs.xml 2009-08-24 16:15:23 UTC (rev 22695)
@@ -18,46 +18,14 @@
<property name="handle_height" value="0.80" />
<property name="handle_length" value="0.14" />
- <!-- joint blocks -->
- <joint name="door_joint" type="revolute" >
- <axis xyz="0 0 1" />
- <anchor xyz="0 0 0" />
- <limit min="${-M_PI}" max="${M_PI}"
- effort="1000" velocity="10"
- safety_length_min="0.1" safety_length_max="0.1"
- k_position="100.0" k_velocity="10.0" />
- <joint_properties damping="100" friction="0.0" />
- <map name="door_latch" flag="gazebo">
- <elem key="latchJoint" value="handle_joint" />
- <elem key="latchAngle" value="-1.57" />
- <elem key="doorClosedAngle" value="0.0" />
- <elem key="latchKp" value="200.0" />
- <elem key="latchKd" value="0.0" />
- <elem key="latchFMax" value="1000.0" />
- </map>
-
+ <joint name="floor1_joint" type="planar">
+ <parent link="world" />
+ <origin xyz="${wall_x_loc} 0.65 ${0.0}" rpy="0 0 0" />
+ <child link="floor1_link" />
</joint>
- <joint name="handle_joint" type="revolute" >
- <axis xyz="1 0 0" />
- <anchor xyz="0 0 0" />
- <limit min="${-M_PI}" max="${M_PI}"
- effort="1000" velocity="10"
- safety_length_min="0.01" safety_length_max="0.1"
- k_position="100.0" k_velocity="10.0" />
- <joint_properties damping="10" friction="0.0" />
- </joint>
-
- <joint name="floor1_joint" type="planar" />
- <joint name="floor2_joint" type="fixed" />
- <joint name="wall1_joint" type="fixed" />
- <joint name="wall2_joint" type="fixed" />
-
<!-- link blocks -->
<link name="floor1_link">
- <parent name="world" />
- <origin xyz="${wall_x_loc} 0.65 ${0.0}" rpy="0 0 0" />
- <joint name="floor1_joint" />
<inertial>
<mass value="100" />
<com xyz="0 0 0.0" />
@@ -67,11 +35,8 @@
</inertial>
<visual>
<origin xyz="0 8 0.001" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material" value="PR2/Grey" />
- </map>
<geometry name="floor1_visual_geom">
- <mesh scale="8 8 0.002" />
+ <box size="8 8 0.002" />
</geometry>
</visual>
<collision>
@@ -79,18 +44,23 @@
<geometry name="floor1_collision_geom">
<box size="8 8 0.002" />
</geometry>
- <map name="floor1_friction_coefficients" flag="gazebo">
- <elem key="mu1" value="50.0" />
- <elem key="mu2" value="50.0" />
- <elem key="kp" value="1000000000.0" />
- <elem key="kd" value="1.0" />
- </map>
</collision>
</link>
- <link name="floor2_link">
- <parent name="floor1_link" />
+
+ <gazebo reference="floor1_link">
+ <material>PR2/Grey</material>
+ <mu1>50.0</mu1>
+ <mu2>50.0</mu2>
+ <kp>1000000000.0</kp>
+ <kd>1.0</kd>
+ </gazebo>
+
+ <joint name="floor2_joint" type="fixed" >
+ <parent link="floor1_link" />
<origin xyz="0 -8 0" rpy="0 0 0" />
- <joint name="floor2_joint" />
+ <child link="floor2_link" />
+ </joint>
+ <link name="floor2_link">
<inertial>
<mass value="100" />
<com xyz="0 0 0.0" />
@@ -100,11 +70,8 @@
</inertial>
<visual>
<origin xyz="0 -4 0.000" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material" value="PR2/Grey" />
- </map>
<geometry name="floor2_visual_geom">
- <mesh scale="8 8 0.002" />
+ <box size="8 8 0.002" />
</geometry>
</visual>
<collision>
@@ -112,19 +79,22 @@
<geometry name="floor2_collision_geom">
<box size="8 8 0.002" />
</geometry>
- <map name="floor2_friction_coefficients" flag="gazebo">
- <elem key="mu1" value="50.0" />
- <elem key="mu2" value="50.0" />
- <elem key="kp" value="100000000.0" />
- <elem key="kd" value="1.0" />
- </map>
</collision>
</link>
+ <gazebo reference="floor2_link">
+ <material>PR2/Grey</material>
+ <mu1>50.0</mu1>
+ <mu2>50.0</mu2>
+ <kp>100000000.0</kp>
+ <kd>1.0</kd>
+ </gazebo>
- <link name="wall1_link">
- <parent name="floor1_link" />
+ <joint name="wall1_joint" type="fixed" >
+ <parent link="floor1_link" />
<origin xyz="0 0.0 0" rpy="0 0 0" />
- <joint name="wall1_joint" />
+ <child link="wall1_link" />
+ </joint>
+ <link name="wall1_link">
<inertial>
<mass value="100" />
<com xyz="0 5 1" />
@@ -134,11 +104,8 @@
</inertial>
<visual>
<origin xyz="0 5 1" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material" value="PR2/Grey2" />
- </map>
<geometry name="wall1_visual_geom">
- <mesh scale="0.4 10 2" />
+ <box size="0.4 10 2" />
</geometry>
</visual>
<collision>
@@ -146,20 +113,22 @@
<geometry name="wall1_collision_geom">
<box size="0.4 10 2" />
</geometry>
- <map name="wall1_intensity" flag="gazebo">
- <elem key="laserRetro" value="1000" />
- </map>
</collision>
- <map name="wall1_prop" flag="gazebo">
- <elem key="selfCollide" value="false" />
- <elem key="turnGravityOff" value="true" />
- </map>
</link>
+ <gazebo reference="wall1_link">
+ <material>PR2/Grey2</material>
+ <laserRetro>1000</laserRetro>
+ <selfCollide>false</selfCollide>
+ <turnGravityOff>true</turnGravityOff>
+ </gazebo>
- <link name="wall2_link">
- <parent name="floor1_link" />
+
+ <joint name="wall2_joint" type="fixed" >
+ <parent link="floor1_link" />
<origin xyz="0 -1.02 0.0" rpy="0 0 0" />
- <joint name="wall2_joint" />
+ <child link="wall2_link" />
+ </joint>
+ <link name="wall2_link">
<inertial>
<mass value="100" />
<com xyz="0 -5 1" />
@@ -169,11 +138,8 @@
</inertial>
<visual>
<origin xyz="0 -5 1" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material" value="PR2/Grey2" />
- </map>
<geometry name="wall2_visual_geom">
- <mesh scale="0.4 10 2" />
+ <box size="0.4 10 2" />
</geometry>
</visual>
<collision>
@@ -181,20 +147,37 @@
<geometry name="wall2_collision_geom">
<box size="0.4 10 2" />
</geometry>
- <map name="wall2_intensity" flag="gazebo">
- <elem key="laserRetro" value="1500" />
- </map>
</collision>
- <map name="wall2_prop" flag="gazebo">
- <elem key="selfCollide" value="false" />
- <elem key="turnGravityOff" value="true" />
- </map>
</link>
+ <gazebo reference="wall2_link">
+ <material>PR2/Grey2</material>
+ <laserRetro>1500</laserRetro>
+ <selfCollide>false</selfCollide>
+ <turnGravityOff>true</turnGravityOff>
+ </gazebo>
- <link name="door_link">
- <parent name="wall1_link" />
+
+ <gazebo reference="door_link">
+ <latchJoint>handle_joint</latchJoint>
+ <latchAngle>-1.57</latchAngle>
+ <doorClosedAngle>0.0</doorClosedAngle>
+ <latchKp>200.0</latchKp>
+ <latchKd>0.0</latchKd>
+ <latchFMax>1000.0</latchFMax>
+ </gazebo>
+
+ <joint name="door_joint" type="revolute" >
<origin xyz="0 0 0.05" rpy="0 0 0" />
- <joint name="door_joint" />
+ <axis xyz="0 0 1" />
+ <limit lower="${-M_PI}" upper="${M_PI}" effort="1000" velocity="10" />
+ <safety_controller safety_lower_limit="${-M_PI+0.1}" safety_upper_limit="${M_PI-0.1}"
+ k_position="100.0" k_velocity="10.0" />
+ <dynamics damping="100" friction="0.0" />
+
+ <parent link="wall1_link" />
+ <child link="door_link" />
+ </joint>
+ <link name="door_link">
<inertial >
<mass value="30" />
<com xyz="0.0 -0.5 1.0" />
@@ -204,11 +187,8 @@
</inertial>
<visual >
<origin xyz="0.0 -0.5 1.0" rpy="0 0 ${M_PI}" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material" value="PR2/White" />
- </map>
<geometry name="sholder_roll_mesh_file">
- <mesh scale="0.1 1.0 2.0" />
+ <box size="0.1 1.0 2.0" />
</geometry>
</visual>
<collision >
@@ -216,21 +196,27 @@
<geometry name="door_collision_geom">
<box size="0.1 1.0 2.0" />
</geometry>
- <map name="door_intensity" flag="gazebo">
- <elem key="laserRetro" value="2000" />
- </map>
</collision>
- <map name="door_gravity" flag="gazebo">
- <elem key="turnGravityOff" value="true" />
- <elem key="selfCollide" value="false" />
- <elem key="dampingFactor" value="0.01" />
- </map>
</link>
+ <gazebo reference="door_link">
+ <material>PR2/White</material>
+ <laserRetro>2000</laserRetro>
+ <turnGravityOff>true</turnGravityOff>
+ <selfCollide>false</selfCollide>
+ <dampingFactor>0.01</dampingFactor>
+ </gazebo>
- <link name="handle_link">
- <parent name="door_link" />
+ <joint name="handle_joint" type="revolute" >
+ <axis xyz="1 0 0" />
<origin xyz="-0.11 -0.8 ${handle_height-0.05}" rpy="${0*M_PI/2.0} 0 0" />
- <joint name="handle_joint" />
+ <limit lower="${-M_PI}" upper="${M_PI}" effort="1000" velocity="10" />
+ <safety_controller safety_lower_limit="${-M_PI+0.01}" safety_upper_limit="${M_PI-0.1}"
+ k_position="100.0" k_velocity="10.0" />
+ <dynamics damping="10" friction="0.0" />
+ <parent link="door_link" />
+ <child link="handle_link" />
+ </joint>
+ <link name="handle_link">
<inertial >
<mass value="0.3" />
<com xyz="0.0 ${handle_length/2-0.01} 0.0" />
@@ -240,11 +226,8 @@
</inertial>
<visual >
<origin xyz="0.0 ${handle_length/2-0.01} 0.0" rpy="${1*M_PI/2} 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material" value="PR2/Shiny" />
- </map>
<geometry name="sholder_roll_mesh_file">
- <mesh scale="0.02 0.02 ${handle_length}" />
+ <cylinder radius="0.01" length="${handle_length}" />
</geometry>
</visual>
<collision >
@@ -252,27 +235,26 @@
<geometry name="handle_collision_geom">
<cylinder radius="0.01" length="${handle_length}" />
</geometry>
- <map name="handle_intensity" flag="gazebo">
- <elem key="laserRetro" value="3900.0" />
- </map>
- <map name="handle_friction_coefficients" flag="gazebo">
- <elem key="mu1" value="50.0" />
- <elem key="mu2" value="50.0" />
- <elem key="kp" value="100000000.0" />
- <elem key="kd" value="1.0" />
- </map>
</collision>
- <map name="handle_gravity" flag="gazebo">
- <elem key="turnGravityOff" value="true" />
- <elem key="selfCollide" value="false" />
- <elem key="dampingFactor" value="0.05" />
- </map>
</link>
+ <gazebo reference="handle_link">
+ <material>PR2/Shiny</material>
+ <laserRetro>3900.0</laserRetro>
+ <mu1>50.0</mu1>
+ <mu2>50.0</mu2>
+ <kp>100000000.0</kp>
+ <kd>1.0</kd>
+ <turnGravityOff>true</turnGravityOff>
+ <selfCollide>false</selfCollide>
+ <dampingFactor>0.05</dampingFactor>
+ </gazebo>
- <link name="handle1_link">
- <parent name="handle_link" />
+ <joint name="handle1_joint" type="fixed">
+ <parent link="handle_link" />
<origin xyz="0.0 0.0 0" rpy="0 0 0" />
- <joint name="handle1_joint" type="fixed" />
+ <child link="handle1_link" />
+ </joint>
+ <link name="handle1_link">
<inertial >
<mass value="0.1" />
<com xyz="0.0 0.0 0.0" />
@@ -282,11 +264,8 @@
</inertial>
<visual >
<origin xyz="0.025 0.0 0.0" rpy="0 ${1*M_PI/2.0} 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material" value="PR2/Shiny" />
- </map>
<geometry name="sholder_roll_mesh_file">
- <mesh scale="0.02 0.02 0.05" />
+ <cylinder radius="0.01" length="0.05" />
</geometry>
</visual>
<collision >
@@ -294,21 +273,22 @@
<geometry name="handle1_collision_geom">
<cylinder radius="0.01" length="0.05" />
</geometry>
- <map name="handle1_intensity" flag="gazebo">
- <elem key="laserRetro" value="3900.0" />
- </map>
</collision>
- <map name="handle1_options" flag="gazebo">
- <elem key="turnGravityOff" value="true" />
- <elem key="selfCollide" value="false" />
- </map>
</link>
+ <gazebo reference="handle1_link">
+ <material>PR2/Shiny</material>
+ <laserRetro>3900.0</laserRetro>
+ <turnGravityOff>true</turnGravityOff>
+ <selfCollide>false</selfCollide>
+ </gazebo>
- <link name="handle2_link">
- <parent name="handle_link" />
+ <joint name="handle2_joint" type="fixed">
+ <parent link="handle_link" />
<origin xyz="0.0 0.12 0" rpy="0 0 0" />
- <joint name="handle2_joint" type="fixed" />
+ <child link="handle2_link" />
+ </joint>
+ <link name="handle2_link">
<inertial >
<mass value="0.1" />
<com xyz="0.0 0.0 0.0" />
@@ -318,11 +298,8 @@
</inertial>
<visual >
<origin xyz="0.025 0.0 0.0" rpy="0 ${1*M_PI/2.0} 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material" value="PR2/Shiny" />
- </map>
<geometry name="sholder_roll_mesh_file">
- <mesh scale="0.02 0.02 0.05" />
+ <cylinder radius="0.01" length="0.05" />
</geometry>
</visual>
<collision >
@@ -330,21 +307,22 @@
<geometry name="handle2_collision_geom">
<cylinder radius="0.01" length="0.05" />
</geometry>
- <map name="handle2_intensity" flag="gazebo">
- <elem key="laserRetro" value="3900.0" />
- </map>
</collision>
- <map name="handle2_options" flag="gazebo">
- <elem key="turnGravityOff" value="true" />
- <elem key="selfCollide" value="false" />
- </map>
</link>
+ <gazebo reference="handle2_link">
+ <material>PR2/Shiny</material>
+ <laserRetro>3900.0</laserRetro>
+ <turnGravityOff>true</turnGravityOff>
+ <selfCollide>false</selfCollide>
+ </gazebo>
- <link name="handle3_link">
- <parent name="handle_link" />
+ <joint name="handle3_joint" type="fixed">
+ <parent link="handle_link" />
<origin xyz="0.0 0.0 0" rpy="0 0 0" />
- <joint name="handle3_joint" type="fixed" />
+ <child link="handle3_link" />
+ </joint>
+ <link name="handle3_link">
<inertial >
<mass value="0.1" />
<com xyz="0.0 0.0 0.0" />
@@ -354,11 +332,8 @@
</inertial>
<visual >
<origin xyz="0.06 0.0 0.0" rpy="0 ${1*M_PI/2.0} 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material" value="PR2/Shiny" />
- </map>
<geometry name="sholder_roll_mesh_file">
- <mesh scale="0.06 0.06 0.02" />
+ <cylinder radius="0.03" length="0.02" />
</geometry>
</visual>
<collision >
@@ -366,20 +341,21 @@
<geometry name="handle3_collision_geom">
<cylinder radius="0.03" length="0.02" />
</geometry>
- <map name="handle3_intensity" flag="gazebo">
- <elem key="laserRetro" value="3900.0" />
- </map>
</collision>
- <map name="handle3_options" flag="gazebo">
- <elem key="turnGravityOff" value="true" />
- <elem key="selfCollide" value="false" />
- </map>
</link>
+ <gazebo reference="handle3_link">
+ <material>PR2/Shiny</material>
+ <laserRetro>3900.0</laserRetro>
+ <turnGravityOff>true</turnGravityOff>
+ <selfCollide>false</selfCollide>
+ </gazebo>
- <link name="keyhole_link">
- <parent name="door_link" />
+ <joint name="keyhole_joint" type="fixed">
+ <parent link="door_link" />
<origin xyz="-0.05 -0.8 ${handle_height-0.05+0.15}" rpy="${0*M_PI/2.0} 0 0" />
- <joint name="keyhole_joint" type="fixed" />
+ <child link="keyhole_link" />
+ </joint>
+ <link name="keyhole_link">
<inertial >
<mass value="0.1" />
<com xyz="0.0 0.0 0.0" />
@@ -389,11 +365,8 @@
</inertial>
<visual >
<origin xyz="0.0 0.0 0.0" rpy="0 ${1*M_PI/2.0} 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material" value="PR2/Shiny" />
- </map>
<geometry name="sholder_roll_mesh_file">
- <mesh scale="0.06 0.06 0.02" />
+ <cylinder radius="0.03" length="0.02" />
</geometry>
</visual>
<collision >
@@ -401,40 +374,37 @@
<geometry name="keyhole_collision_geom">
<cylinder radius="0.03" length="0.02" />
</geometry>
- <map name="keyhole_intensity" flag="gazebo">
- <elem key="laserRetro" value="3900.0" />
- </map>
</collision>
- <map name="keyhole_options" flag="gazebo">
- <elem key="turnGravityOff" value="true" />
- <elem key="selfCollide" value="false" />
- </map>
</link>
+ <gazebo reference="keyhole_link">
+ <material>PR2/Shiny</material>
+ <laserRetro>3900.0</laserRetro>
+ <turnGravityOff>true</turnGravityOff>
+ <selfCollide>false</selfCollide>
+ </gazebo>
- <map name="sensor" flag="gazebo">
- <verbatim key="door_p3d_block">
- <!-- ros_p3d for position groundtruth -->
- <controller:ros_p3d name="p3d_door_controller" plugin="libros_p3d.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <bodyName>door_link</bodyName>
- <topicName>door_pose</topicName>
- <frameName>map</frameName>
- <interface:position name="p3d_door_position"/>
- </controller:ros_p3d>
-
- <!--
- <controller:gazebo_mechanism_control name="door_mechanism_control" plugin="libgazebo_mechanism_control.so">
+ <gazebo>
+ <!-- ros_p3d for position groundtruth -->
+ <controller:ros_p3d name="p3d_door_controller" plugin="libros_p3d.so">
<alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <robotParam>door_description</robotParam>
- <interface:audio name="gazebo_mechanism_control_dummy_iface" />
- </controller:gazebo_mechanism_control>
- -->
+ <updateRate>100.0</updateRate>
+ <bodyName>door_link</bodyName>
+ <topicName>door_pose</topicName>
+ <frameName>map</frameName>
+ <interface:position name="p3d_door_position"/>
+ </controller:ros_p3d>
- </verbatim>
- </map>
+ <!--
+ <controller:gazebo_mechanism_control name="door_mechanism_control" plugin="libgazebo_mechanism_control.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <robotParam>door_description</robotParam>
+ <interface:audio name="gazebo_mechanism_control_dummy_iface" />
+ </controller:gazebo_mechanism_control>
+ -->
+ </gazebo>
+
<!-- transmission mechanism controls -->
<transmission type="SimpleTransmission" name="door_trans">
<actuator name="door_motor" />
Modified: pkg/trunk/demos/examples_gazebo/dual_link_defs/dual_link.xml
===================================================================
--- pkg/trunk/demos/examples_gazebo/dual_link_defs/dual_link.xml 2009-08-24 16:03:15 UTC (rev 22694)
+++ pkg/trunk/demos/examples_gazebo/dual_link_defs/dual_link.xml 2009-08-24 16:15:23 UTC (rev 22695)
@@ -13,73 +13,55 @@
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics">
- <!-- joint blocks -->
- <joint name="base_block_joint" type="fixed" />
- <!-- joint blocks -->
- <joint name="link1_joint" type="revolute" >
- <axis xyz="0 0 1" />
- <anchor xyz="0 0 0" />
- <limit min="0.0" max="0.0" effort="100" velocity="5"
- k_position="0.0" k_velocity="0.0"
- safety_length_min="0.0" safety_length_max="0.0" />
- <calibration values="1.5 -1 " />
- <joint_properties damping="0.0" />
- </joint>
- <!-- joint blocks -->
- <joint name="link2_joint" type="revolute" >
- <axis xyz="0 1 0" />
- <anchor xyz="0 0 0" />
- <limit effort="100" velocity="5" k_velocity="1000" />
- <calibration values="1.5 -1 " />
- <joint_properties damping="0.0" friction="0.0" />
- </joint>
- <!-- link blocks -->
- <link name="base_block">
- <parent name="world" />
+ <joint name="base_block_joint" type="fixed">
+ <parent link="world" />
<origin xyz="0 0 0" rpy="0 0 0" />
- <joint name="base_block_joint" />
+ <child link="base_block" />
+ </joint>
+ <link name="base_block">
<inertial>
<mass value="1000" />
- <com xyz="0 0 0" />
+ <origin xyz="0 0 0" />
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/GrassFloor</elem>
- </map>
<geometry name="base_block_visual_geom">
- <box scale="0.001 0.001 0.001" />
+ <box size="0.001 0.001 0.001" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0.0 0.0 0.0" />
<geometry name="base_block_collision_geom">
- <box scale="0.001 0.001 0.001" />
+ <box size="0.001 0.001 0.001" />
</geometry>
</collision>
</link>
+ <gazebo reference="base_block">
+ <material>Gazebo/GrassFloor</material>
+ </gazebo>
- <link name="link1">
- <parent name="base_block" />
+ <joint name="link1_joint" type="revolute" >
+ <axis xyz="0 0 1" />
+ <limit lower="0.0" upper="0.0" effort="100" velocity="5" />
+ <parent link="base_block" />
<origin xyz="0 0 2" rpy="0 0 0" />
- <joint name="link1_joint" />
+ <child link="link1" />
+ </joint>
+ <link name="link1">
<inertial >
<mass value="0.1" />
- <com xyz="0 0 -0.5" />
+ <origin xyz="0 0 -0.5" />
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
</inertial>
<visual >
<origin xyz="0 0 -0.5" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Red</elem>
- </map>
<geometry name="link1_visual_geom">
- <mesh scale="0.1 0.1 1.0" />
+ <box size="0.1 0.1 1.0" />
</geometry>
</visual>
<collision >
@@ -88,28 +70,31 @@
<box size="0.1 0.1 1.0" />
</geometry>
</collision>
- <map name="link1_gravity" flag="gazebo">
- <elem key="turnGravityOff">false</elem>
- </map>
</link>
+ <gazebo reference="link1">
+ <material>Gazebo/Red</material>
+ <turnGravityOff>false</turnGravityOff>
+ </gazebo>
- <link name="link2">
- <parent name="link1" />
+ <joint name="link2_joint" type="revolute" >
+ <axis xyz="0 1 0" />
+ <limit effort="100" velocity="5" />
+ <dynamics damping="0.0" friction="0.0" />
+ <parent link="link1" />
<origin xyz="0 0 0" rpy="0 90 0" />
- <joint name="link2_joint" />
+ <child link="link2" />
+ </joint>
+ <link name="link2">
<inertial >
<mass value="1.0" />
- <com xyz="0 0 0.5" />
+ <origin xyz="0 0 0.5" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
</inertial>
<visual >
<origin xyz="0 0 0.5" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Blue</elem>
- </map>
<geometry name="link2_visual_geom">
- <mesh scale="0.1 0.1 1.0" />
+ <cylinder radius="0.05" length="1.0" />
</geometry>
</visual>
<collision >
@@ -118,10 +103,11 @@
<cylinder radius="0.05" length="1.0" />
</geometry>
</collision>
- <map name="link2_gravity" flag="gazebo">
- <elem key="turnGravityOff">false</elem>
- </map>
</link>
+ <gazebo reference="link2">
+ <material>Gazebo/Blue</material>
+ <turnGravityOff>false</turnGravityOff>
+ </gazebo>
<!-- Define groups of links; a link may be part of multiple groups -->
@@ -129,9 +115,7 @@
<!-- mechanism controls -->
<include filename="./transmissions_dual_link.xml" />
- <map name="sensor" flag="gazebo">
- <verbatim key="mechanism_control_simulation">
-
+ <gazebo>
<controller:ros_time name="ros_time" plugin="libros_time.so">
<alwaysOn>true</alwaysOn>
<updateRate>1000.0</updateRate>
@@ -167,7 +151,5 @@
<frameName>map</frameName>
<interface:position name="p3d_link2_position"/>
</controller:ros_p3d>
-
- </verbatim>
- </map>
+ </gazebo>
</robot>
Modified: pkg/trunk/demos/examples_gazebo/multi_link_defs/multi_link.xml
===================================================================
--- pkg/trunk/demos/examples_gazebo/multi_link_defs/multi_link.xml 2009-08-24 16:03:15 UTC (rev 22694)
+++ pkg/trunk/demos/examples_gazebo/multi_link_defs/multi_link.xml 2009-08-24 16:15:23 UTC (rev 22695)
@@ -15,114 +15,54 @@
xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics">
<!-- joint blocks -->
- <joint name="base_block_joint" type="fixed" />
-
- <!-- joint blocks -->
- <joint name="link1_joint" type="revolute" >
- <axis xyz="0 0 1" />
- <anchor xyz="0 0 0" />
- <limit safety_length_min="0" safety_length_max="0" k_position="100.0" k_velocity="100.0" min="-.5" max="0.5" effort="10" velocity="50" />
- <calibration values="1.5 -1 " />
- <joint_properties damping="1000.0" />
+ <joint name="base_block_joint" type="fixed" >
+ <parent link="world" />
+ <origin xyz="0 0 0.002 " rpy="0 0 0" />
+ <child link="base_block" />
</joint>
-
- <!-- joint blocks -->
- <joint name="link2_joint" type="revolute" >
- <axis xyz="0 1 0" />
- <anchor xyz="0.0 0 0" />
- <limit safety_length_min="0" safety_length_max="0" k_position="100.0" k_velocity="100.0" min="-1" max="2" effort="5000" velocity="50" />
- <calibration values="1.5 -1 " />
- <joint_properties damping="1000.0" />
- </joint>
-
- <!-- joint blocks -->
- <joint name="link3_joint" type="revolute" >
- <axis xyz="0 1 0" />
- <anchor xyz="0.0 0 0" />
- <limit safety_length_min="0" safety_length_max="0" k_position="100.0" k_velocity="100.0" min="-1" max="2" effort="5000" velocity="50" />
- <calibration values="1.5 -1 " />
- <joint_properties damping="1000.0" />
- </joint>
-
- <!-- joint blocks -->
- <joint name="link4_joint" type="revolute" >
- <axis xyz="0 1 0" />
- <anchor xyz="0.0 0 0" />
- <limit safety_length_min="0" safety_length_max="0" k_position="100.0" k_velocity="100.0" min="-1" max="2" effort="2000" velocity="50" />
- <calibration values="1.5 -1 " />
- <joint_properties damping="1000.0" />
- </joint>
-
- <!-- joint blocks -->
- <joint name="link5_joint" type="revolute" >
- <axis xyz="0 1 0" />
- <anchor xyz="0.0 0 0" />
- <limit safety_length_min="0" safety_length_max="0" k_position="100.0" k_velocity="100.0" min="-1" max="2" effort="500" velocity="50" />
- <calibration values="1.5 -1 " />
- <joint_properties damping="100.0" />
- </joint>
-
- <!-- joint blocks -->
- <joint name="link6_joint" type="revolute" >
- <axis xyz="0 1 0" />
- <anchor xyz="0.0 0 0" />
- <limit safety_length_min="0" safety_length_max="0" k_position="100.0" k_velocity="100.0" min="-1" max="2" effort="100" velocity="50" />
- <calibration values="1.5 -1 " />
- <joint_properties damping="100.0" />
- </joint>
-
- <!-- joint blocks -->
- <joint name="link7_joint" type="revolute" >
- <axis xyz="0 1 0" />
- <anchor xyz="0.0 0 0" />
- <limit safety_length_min="0" safety_length_max="0" k_position="100.0" k_velocity="100.0" min="-1" max="2" effort="100" velocity="50" />
- <calibration values="1.5 -1 " />
- <joint_properties damping="10.0" />
- </joint>
-
- <!-- link blocks -->
<link name="base_block">
- <parent name="world" />
- <origin xyz="0 0 0.002 " rpy="0 0 0" />
- <joint name="base_block_joint" />
<inertial>
<mass value="1000" />
- <com xyz="0 0 0" />
+ <origin xyz="0 0 0" />
<inertia ixx="1000" ixy="0" ixz="0" iyy="1000" iyz="0" izz="1000" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/GrassFloor</elem>
- </map>
<geometry name="base_block_visual_geom">
- <box scale="0.001 0.001 0.001" />
+ <box size="0.001 0.001 0.001" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0.0 0.0 0.0" />
<geometry name="base_block_collision_geom">
- <box scale="0.001 0.001 0.001" />
+ <box size="0.001 0.001 0.001" />
</geometry>
</collision>
</link>
+ <gazebo reference="base_block">
+ <material>Gazebo/GrassFloor</material>
+ </gazebo>
- <link name="link1">
- <parent name="base_block" />
+ <!-- joint blocks -->
+ <joint name="link1_joint" type="revolute" >
+ <axis xyz="0 0 1" />
+ <limit lower="-.5" upper="0.5" effort="10" velocity="50" />
+ <safety_controller safety_lower_limit="-.5" safety_upper_limit="0.5" k_position="100.0" k_velocity="100.0" />
+ <dynamics damping="1000.0" />
+ <parent link="base_block" />
<origin xyz="0 0 10" rpy="0 0 0" />
- <joint name="link1_joint" />
+ <child link="link1" />
+ </joint>
+ <link name="link1">
<inertial >
<mass value="100.0" />
- <com xyz="0 0 -0.5" />
+ <origin xyz="0 0 -0.5" />
<inertia ixx="200.00" ixy="0.0" ixz="0.0" iyy="200.0" iyz="0.0" izz="100.0" />
</inertial>
<visual >
<origin xyz="0 0 -0.5" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Red</elem>
- </map>
<geometry name="link1_visual_geom">
- <mesh scale="0.1 0.1 1.0" />
+ <box size="0.1 0.1 1.0" />
</geometry>
</visual>
<collision >
@@ -131,28 +71,33 @@
<box size="0.1 0.1 1.0" />
</geometry>
</collision>
- <map name="link1_gravity" flag="gazebo">
- <elem key="turnGravityOff">false</elem>
- </map>
</link>
+ <gazebo reference="link1">
+ <material>Gazebo/Red</material>
+ <turnGravityOff>false</turnGravityOff>
+ </gazebo>
- <link name="link2">
- <parent name="link1" />
+ <!-- joint blocks -->
+ <joint name="link2_joint" type="revolute" >
+ <axis xyz="0 1 0" />
+ <limit lower="-1" upper="2" effort="5000" velocity="50" />
+ <safety_controller safety_lower_limit="-1" safety_upper_limit="2" k_position="100.0" k_velocity="100.0" />
+ <dynamics damping="1000.0" />
+ <parent link="link1" />
<origin xyz="0.0 0 0" rpy="0 0 0" />
- <joint name="link2_joint" />
+ <child link="link2" />
+ </joint>
+ <link name="link2">
<inertial >
<mass value="1" />
- <com xyz="0.5 0 0" />
+ <origin xyz="0.5 0 0" />
<inertia ixx="1.00" ixy="0.0" ixz="0.0" iyy="2.0" iyz="0.0" izz="2.0" />
</inertial>
<visual >
<origin xyz="0.5 0 0" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Blue</elem>
- </map>
<geometry name="link2_visual_geom">
- <mesh scale="1.0 0.1 0.1" />
+ <box size="1.0 0.1 0.1" />
</geometry>
</visual>
<collision >
@@ -161,27 +106,32 @@
<box size="1.0 0.1 0.1" />
</geometry>
</collision>
- <map name="link2_gravity" flag="gazebo">
- <elem key="turnGravityOff">false</elem>
- </map>
</link>
+ <gazebo reference="link2">
+ <material>Gazebo/Blue</material>
+ <turnGravityOff>false</turnGravityOff>
+ </gazebo>
- <link name="link3">
- <parent name="link2" />
+ <!-- joint blocks -->
+ <joint name="link3_joint" type="revolute" >
+ <axis xyz="0 1 0" />
+ <limit lower="-1" upper="2" effort="5000" velocity="50" />
+ <safety_controller safety_lower_limit="-1" safety_upper_limit="2" k_position="100.0" k_velocity="100.0" />
+ <dynamics damping="1000.0" />
+ <parent link="link2" />
<origin xyz="1.0 0 0" rpy="0 0 0" />
- <joint name="link3_joint" />
+ <child link="link3" />
+ </joint>
+ <link name="link3">
<inertial >
<mass value="1" />
- <com xyz="0.5 0 0" />
+ <origin xyz="0.5 0 0" />
<inertia ixx="1.00" ixy="0.0" ixz="0.0" iyy="2.0" iyz="0.0" izz="2.0" />
</inertial>
<visual >
<origin xyz="0.5 0 0" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Green</elem>
- </map>
<geometry name="link3_visual_geom">
- <mesh scale="1.0 0.1 0.1" />
+ <box size="1.0 0.1 0.1" />
</geometry>
</visual>
<collision >
@@ -190,28 +140,33 @@
<box size="1.0 0.1 0.1" />
</geometry>
</collision>
- <map name="link3_gravity" flag="gazebo">
- <elem key="turnGravityOff">false</elem>
- </map>
</link>
+ <gazebo reference="link3">
+ <material>Gazebo/Green</material>
+ <turnGravityOff>false</turnGravityOff>
+ </gazebo>
- <link name="link4">
- <parent name="link3" />
+ <!-- joint blocks -->
+ <joint name="link4_joint" type="revolute" >
+ <axis xyz="0 1 0" />
+ <limit lower="-1" upper="2" effort="2000" velocity="50" />
+ <safety_controller safety_lower_limit="-1" safety_upper_limit="2" k_position="100.0" k_velocity="100.0" />
+ <dynamics damping="1000.0" />
+ <parent link="link3" />
<origin xyz="1.0 0 0" rpy="0 0 0" />
- <joint name="link4_joint" />
+ <child link="link4" />
+ </joint>
+ <link name="link4">
<inertial >
<mass value="1" />
- <com xyz="0.5 0 0" />
+ <origin xyz="0.5 0 0" />
<inertia ixx="1.00" ixy="0.0" ixz="0.0" iyy="2.0" iyz="0.0" izz="2.0" />
</inertial>
<visual >
<origin xyz="0.5 0 0" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Red</elem>
- </map>
<geometry name="link4_visual_geom">
- <mesh scale="1.0 0.1 0.1" />
+ <box size="1.0 0.1 0.1" />
</geometry>
</visual>
<collision >
@@ -220,28 +175,33 @@
<box size="1.0 0.1 0.1" />
</geometry>
</collision>
- <map name="link4_gravity" flag="gazebo">
- <elem key="turnGravityOff">false</elem>
- </map>
</link>
+ <gazebo reference="link4">
+ <material>Gazebo/Red</material>
+ <turnGravityOff>false</turnGravityOff>
+ </gazebo>
- <link name="link5">
- <parent name="link4" />
+ <!-- joint blocks -->
+ <joint name="link5_joint" type="revolute" >
+ <axis xyz="0 1 0" />
+ <limit lower="-1" upper="2" effort="500" velocity="50" />
+ <safety_controller safety_lower_limit="-1" safety_upper_limit="2" k_position="100.0" k_velocity="100.0" />
+ <dynamics damping="100.0" />
+ <parent link="link4" />
<origin xyz="1.0 0 0" rpy="0 0 0" />
- <joint name="link5_joint" />
+ <child link="link5" />
+ </joint>
+ <link name="link5">
<inertial >
<mass value="1" />
- <com xyz="0.5 0 0" />
+ <origin xyz="0.5 0 0" />
<inertia ixx="1.00" ixy="0.0" ixz="0.0" iyy="2.0" iyz="0.0" izz="2.0" />
</inertial>
<visual >
<origin xyz="0.5 0 0" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Blue</elem>
- </map>
<geometry name="link5_visual_geom">
- <mesh scale="1.0 0.1 0.1" />
+ <box size="1.0 0.1 0.1" />
</geometry>
</visual>
<collision >
@@ -250,28 +210,33 @@
<box size="1.0 0.1 0.1" />
</geometry>
</collision>
- <map name="link5_gravity" flag="gazebo">
- <elem key="turnGravityOff">false</elem>
- </map>
</link>
+ <gazebo reference="link5">
+ <material>Gazebo/Blue</material>
+ <turnGravityOff>false</turnGravityOff>
+ </gazebo>
- <link name="link6">
- <parent name="link5" />
+ <!-- joint blocks -->
+ <joint name="link6_joint" type="revolute" >
+ <axis xyz="0 1 0" />
+ <limit lower="-1" upper="2" effort="100" velocity="50" />
+ <safety_controller safety_lower_limit="-1" safety_upper_limit="2" k_position="100.0" k_velocity="100.0" />
+ <dynamics damping="100.0" />
+ <parent link="link5" />
<origin xyz="1.0 0 0" rpy="0 0 0" />
- <joint name="link6_joint" />
+ <child link="link6" />
+ </joint>
+ <link name="link6">
<inertial >
<mass value="1" />
- <com xyz="0.5 0 0" />
+ <origin xyz="0.5 0 0" />
<inertia ixx="1.00" ixy="0.0" ixz="0.0" iyy="2.0" iyz="0.0" izz="2.0" />
</inertial>
<visual >
<origin xyz="0.5 0 0" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Green</elem>
- </map>
<geometry name="link6_visual_geom">
- <mesh scale="1.0 0.1 0.1" />
+ <box size="1.0 0.1 0.1" />
</geometry>
</visual>
<collision >
@@ -280,28 +245,33 @@
<box size="1.0 0.1 0.1" />
</geometry>
</collision>
- <map name="link6_gravity" flag="gazebo">
- <elem key="turnGravityOff">false</elem>
- </map>
</link>
+ <gazebo reference="link6">
+ <material>Gazebo/Green</material>
+ <turnGravityOff>false</turnGravityOff>
+ </gazebo>
- <link name="link7">
- <parent name="link6" />
+ <!-- joint blocks -->
+ <joint name="link7_joint" type="revolute" >
+ <axis xyz="0 1 0" />
+ <limit lower="-1" upper="2" effort="100" velocity="50" />
+ <safety_controller safety_lower_limit="-1" safety_upper_limit="2" k_position="100.0" k_velocity="100.0" />
+ <dynamics damping="10.0" />
+ <parent link="link6" />
<origin xyz="1.0 0 0" rpy="0 0 0" />
- <joint name="link7_joint" />
+ <child link="link7" />
+ </joint>
+ <link name="link7">
<inertial >
<mass value="1" />
- <com xyz="0.5 0 0" />
+ <origin xyz="0.5 0 0" />
<inertia ixx="1.00" ixy="0.0" ixz="0.0" iyy="2.0" iyz="0.0" izz="2.0" />
</inertial>
<visual >
<origin xyz="0.5 0 0" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Red</elem>
- </map>
<geometry name="link7_visual_geom">
- <mesh scale="1.0 0.1 0.1" />
+ <box size="1.0 0.1 0.1" />
</geometry>
</visual>
<collision >
@@ -310,10 +280,11 @@
<box size="1.0 0.1 0.1" />
</geometry>
</collision>
- <map name="link7_gravity" flag="gazebo">
- <elem key="turnGravityOff">false</elem>
- </map>
</link>
+ <gazebo reference="link7">
+ <material>Gazebo/Red</material>
+ <turnGravityOff>false</turnGravityOff>
+ </gazebo>
<!-- Define groups of links; a link may be part of multiple groups -->
@@ -321,8 +292,7 @@
<!-- mechanism controls -->
<include filename="./transmissions_multi_link.xml" />
- <map name="sensor" flag="gazebo">
- <verbatim key="mechanism_control_simulation">
+ <gazebo>
<controller:ros_time name="ros_time" plugin="libros_time.so">
<alwaysOn>true</alwaysOn>
<updateRate>1000.0</updateRate>
@@ -346,7 +316,6 @@
<frameName>map</frameName>
<interface:position name="p3d_link3_position"/>
</controller:ros_p3d>
- </verbatim>
- </map>
+ </gazebo>
</robot>
Modified: pkg/trunk/demos/examples_gazebo/simple_rdf_examples/simple_box.xml
===================================================================
--- pkg/trunk/demos/examples_gazebo/simple_rdf_examples/simple_box.xml 2009-08-24 16:03:15 UTC (rev 22694)
+++ pkg/trunk/demos/examples_gazebo/simple_rdf_examples/simple_box.xml 2009-08-24 16:15:23 UTC (rev 22695)
@@ -1,27 +1,24 @@
<robot name="simple_box">
- <link name="my_box">
- <parent name="world" />
- <!-- initial pose of my_box in the parent frame coordiantes -->
+ <joint name="my_box_joint" type="revolute" >
+ <!-- axis is in the parent link frame coordintates -->
+ <axis xyz="0 1 0" />
+ <parent link="world" />
+ <child link="my_box" />
+ <!-- initial pose of my_box joint/link in the parent frame coordiantes -->
<origin xyz="0 0 2" rpy="0 0 0" />
- <joint name="my_box_joint" type="revolute" >
- <!-- axis is in the parent link frame coordintates -->
- <axis xyz="0 1 0" />
- <anchor xyz="0 0 0" />
- </joint>
+ </joint>
+ <link name="my_box">
<inertial>
<mass value="1.0" />
<!-- center of mass (com) is defined w.r.t. link local coordinate system -->
- <com xyz="1 0 0" />
+ <origin xyz="1 0 0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="100.0" iyz="0.0" izz="1.0" />
</inertial>
<visual>
<!-- visual origin is defined w.r.t. link local coordinate system -->
<origin xyz="1 0 0" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Blue</elem>
- </map>
<geometry name="my_box_visual_geom">
- <mesh scale="0.05 0.05 0.10" />
+ <box size="0.05 0.05 0.10" />
</geometry>
</visual>
<collision>
@@ -31,8 +28,9 @@
<box size="0.05 0.05 0.10" />
</geometry>
</collision>
- <map name="my_box_gravity" flag="gazebo">
- <elem key="turnGravityOff">false</elem>
- </map>
</link>
+ <gazebo reference="my_box">
+ <material>Gazebo/Blue</material>
+ <turnGravityOff>false</turnGravityOff>
+ </gazebo>
</robot>
Modified: pkg/trunk/demos/examples_gazebo/simple_rdf_examples/simple_cylinder.xml
===================================================================
--- pkg/trunk/demos/examples_gazebo/simple_rdf_examples/simple_cylinder.xml 2009-08-24 16:03:15 UTC (rev 22694)
+++ pkg/trunk/demos/examples_gazebo/simple_rdf_examples/simple_cylinder.xml 2009-08-24 16:15:23 UTC (rev 22695)
@@ -1,27 +1,24 @@
<robot name="simple_cylinder">
- <link name="my_cylinder">
- <parent name="world" />
+ <joint name="my_cylinder_joint" type="revolute" >
+ <!-- axis is in the parent link frame coordintates -->
+ <axis xyz="0 1 0" />
+ <parent link="world" />
+ <child link="my_cylinder" />
<!-- initial pose of my_cylinder in the parent frame coordiantes -->
<origin xyz="0 0 2" rpy="0 1.57 0.5" />
- <joint name="my_cylinder_joint" type="revolute" >
- <!-- axis is in the parent link frame coordintates -->
- <axis xyz="0 1 0" />
- <anchor xyz="0 0 0" />
- </joint>
+ </joint>
+ <link name="my_cylinder">
<inertial>
<mass value="1.0" />
<!-- center of mass (com) is defined w.r.t. link local coordinate system -->
- <com xyz="0 0 0.5" />
+ <origin xyz="0 0 0.5" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="100.0" iyz="0.0" izz="1.0" />
</inertial>
<visual>
<!-- visual origin is defined w.r.t. link local coordinate system -->
<origin xyz="0 0 0.5" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Blue</elem>
- </map>
<geometry name="my_cylinder_visual_geom">
- <mesh scale="0.1 0.1 1.0" />
+ <cylinder radius="0.05" length="1.0" />
</geometry>
</visual>
<collision>
@@ -31,8 +28,9 @@
<cylinder radius="0.05" length="1.0" />
</geometry>
</collision>
- <map name="my_cylinder_gravity" flag="gazebo">
- <elem key="turnGravityOff">false</elem>
- </map>
</link>
+ <gazebo reference="my_cylinder">
+ <material>Gazebo/Blue</material>
+ <turnGravityOff>false</turnGravityOff>
+ </gazebo>
</robot>
Modified: pkg/trunk/demos/examples_gazebo/simple_rdf_examples/simple_sphere.xml
===================================================================
--- pkg/trunk/demos/examples_gazebo/simple_rdf_examples/simple_sphere.xml 2009-08-24 16:03:15 UTC (rev 22694)
+++ pkg/trunk/demos/examples_gazebo/simple_rdf_examples/simple_sphere.xml 2009-08-24 16:15:23 UTC (rev 22695)
@@ -1,27 +1,24 @@
<robot name="simple_sphere">
- <link name="my_sphere">
- <parent name="world" />
+ <joint name="my_sphere_joint" type="revolute" >
+ <!-- axis is in the parent link frame coordintates -->
+ <axis xyz="0 1 0" />
+ <parent link="world" />
+ <child link="my_sphere" />
<!-- initial pose of my_sphere in the parent frame coordiantes -->
<origin xyz="0 0 2" rpy="0 0 0" />
- <joint name="my_sphere_joint" type="revolute" >
- <!-- axis is in the parent link frame coordintates -->
- <axis xyz="0 1 0" />
- <anchor xyz="0 0 0" />
- </joint>
+ </joint>
+ <link name="my_sphere">
<inertial>
<mass value="1.0" />
<!-- center of mass (com) is defined w.r.t. link local coordinate system -->
- <com xyz="1 0 0" />
+ <origin xyz="1 0 0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="100.0" iyz="0.0" izz="1.0" />
</inertial>
<visual>
<!-- visual origin is defined w.r.t. link local coordinate system -->
<origin xyz="1 0 0" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Blue</elem>
- </map>
<geometry name="my_sphere_visual_geom">
- <mesh scale="0.05 0.05 0.05" />
+ <sphere radius="0.25" />
</geometry>
</visual>
<collision>
@@ -31,8 +28,9 @@
<sphere radius="0.25" />
</geometry>
</collision>
- <map name="my_sphere_gravity" flag="gazebo">
- <elem key="turnGravityOff">false</elem>
- </map>
</link>
+ <gazebo reference="my_sphere">
+ <material>Gazebo/Blue</material>
+ <turnGravityOff>false</turnGravityOff>
+ </gazebo>
</robot>
Modified: pkg/trunk/demos/examples_gazebo/single_link_defs/single_link.xml
===================================================================
--- pkg/trunk/demos/examples_gazebo/single_link_defs/single_link.xml 2009-08-24 16:03:15 UTC (rev 22694)
+++ pkg/trunk/demos/examples_gazebo/single_link_defs/single_link.xml 2009-08-24 16:15:23 UTC (rev 22695)
@@ -13,60 +13,51 @@
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics">
- <!-- joint blocks -->
- <joint name="link1_joint" type="revolute" >
- <axis xyz="1 0 0" />
- <anchor xyz="0 0 0" />
- <limit min="-3.14159" max="3.14159" effort="100" velocity="5" k_position="1.0" k_velocity="1.0" />
- <calibration values="1.5 -1 " />
- </joint>
-
<joint name="base_block_joint" type="fixed">
+ <parent link="world" />
+ <origin xyz="0 0 0.002 " rpy="0 0 0" />
+ <child link="base_block" />
</joint>
-
- <!-- link blocks -->
<link name="base_block">
- <parent name="world" />
- <origin xyz="0 0 0.002 " rpy="0 0 0" />
- <joint name="base_block_joint" />
<inertial>
<mass value="1000" />
- <com xyz="0 0 0" />
+ <origin xyz="0 0 0" />
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/GrassFloor</elem>
- </map>
<geometry name="base_block_visual_geom">
- <box scale="0.001 0.001 0.001" />
+ <box size="0.001 0.001 0.001" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0.0 0.0 0.0" />
<geometry name="base_block_collision_geom">
- <box scale="0.001 0.001 0.001" />
+ <box size="0.001 0.001 0.001" />
</geometry>
</collision>
</link>
+ <gazebo reference="base_block">
+ <material>Gazebo/GrassFloor</material>
+ </gazebo>
- <link name="link1">
- <parent name="base_block" />
+ <joint name="link1_joint" type="revolute" >
+ <axis xyz="1 0 0" />
+ <limit upper="-3.14159" lower="3.14159" effort="100" velocity="5" />
+ <parent link="base_block" />
<origin xyz="0 0 1" rpy="0 0 0" />
- <joint name="link1_joint" />
+ <child link="link1" />
+ </joint>
+ <link name="link1">
<inertial >
<mass value="10" />
- <com xyz="0 0 0" />
+ <origin xyz="0 0 0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
</inertial>
<visual >
<origin xyz="0 0 0" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Red</elem>
- </map>
<geometry name="sholder_roll_mesh_file">
- <mesh scale="1.0 0.3 0.3" />
+ <box size="1.0 0.3 0.3" />
</geometry>
</visual>
<collision >
@@ -75,13 +66,13 @@
<box size="1.0 0.3 0.3" />
</geometry>
</collision>
- <map name="link1_gravity" flag="gazebo">
- <elem key="turnGravityOff">true</elem>
- </map>
</link>
+ <gazebo reference="link1">
+ <material>Gazebo/Red</material>
+ <turnGravityOff>true</turnGravityOff>
+ </gazebo>
- <map name="sensor" flag="gazebo">
- <verbatim key="mechanism_control_simulation">
+ <gazebo>
<controller:ros_time name="ros_time" plugin="libros_time.so">
<alwaysOn>true</alwaysOn>
<updateRate>100.0</updateRate>
@@ -104,8 +95,7 @@
<frameName>map</frameName>
<interface:position name="p3d_link1_position"/>
</controller:ros_p3d>
- </verbatim>
- </map>
+ </gazebo>
<!-- Define groups of links; a link may be part of multiple groups -->
<include filename="./groups_single_link.xml" />
<!-- mechanism controls -->
Modified: pkg/trunk/demos/examples_gazebo/table_defs/table_defs.xml
===================================================================
--- pkg/trunk/demos/examples_gazebo/table_defs/table_defs.xml 2009-08-24 16:03:15 UTC (rev 22694)
+++ pkg/trunk/demos/examples_gazebo/table_defs/table_defs.xml 2009-08-24 16:15:23 UTC (rev 22695)
@@ -33,34 +33,25 @@
<property name="M_PI" value="3.1415926535897931" />
- <!-- joint blocks -->
- <joint name="table_top_joint" type="planar" />
- <joint name="leg1_joint" type="fixed" />
- <joint name="leg2_joint" type="fixed" />
- <joint name="leg3_joint" type="fixed" />
- <joint name="leg4_joint" type="fixed" />
- <joint name="object_1_joint" type="fixed" />
- <joint name="object_1_base_joint" type="planar" />
<!-- link blocks -->
- <link name="table_top_link">
- <parent name="world" />
+ <joint name="table_top_joint" type="planar" >
+ <parent link="world" />
<origin xyz="${table_x} ${table_y} ${table_z+table_height+0.01}" rpy="0 0 0" />
- <joint name="table_top_joint" />
+ <child link="table_top_link" />
+ </joint>
+ <link name="table_top_link">
<inertial>
<mass value="10" />
- <com xyz="0 0 0.0" />
+ <origin xyz="0 0 0.0" />
<inertia ixx="1" ixy="0" ixz="0"
iyy="1" iyz="0"
izz="1" />
</inertial>
<visual>
<origin xyz="0 0 0.0" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/LightWood</elem>
- </map>
<geometry name="floor_visual_geom">
- <mesh scale="1 1 0.05" />
+ <box size="1 1 0.05" />
</geometry>
</visual>
<collision>
@@ -68,33 +59,33 @@
<geometry name="floor_collision_geom">
<box size="1 1 0.05" />
</geometry>
- <map name="friction_coefficients" flag="gazebo">
- <elem key="mu1" value="50.0" />
- <elem key="mu2" value="50.0" />
- <elem key="kp" value="1000000.0" />
- <elem key="kd" value="1.0" />
- </map>
</collision>
</link>
+ <gazebo reference="table_top_link">
+ <material>Gazebo/LightWood</material>
+ <mu1>50.0</mu1>
+ <mu2>50.0</mu2>
+ <kp>1000000.0</kp>
+ <kd>1.0</kd>
+ </gazebo>
- <link name="leg1_link">
- <parent name="table_top_link" />
+ <joint name="leg1_joint" type="fixed" >
+ <parent link="table_top_link" />
<origin xyz="${table_width/2} ${table_depth/2} 0" rpy="0 0 0" />
- <joint name="leg1_joint" />
+ <child link="leg1_link" />
+ </joint>
+ <link name="leg1_link">
<inertial>
<mass value="100" />
- <com xyz="0 0 ${-table_height/2}" />
+ <origin xyz="0 0 ${-table_height/2}" />
<inertia ixx="0.1" ixy="0" ixz="0"
iyy="0.1" iyz="0"
izz="0.01" />
</inertial>
<visual>
<origin xyz="0.0 0.0 ${-table_height/2}" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Red</elem>
- </map>
<geometry name="leg1_visual_geom">
- <mesh scale="${leg_radius*2} ${leg_radius*2} ${table_height}" />
+ <cylinder radius="${leg_radius}" length="${table_height}" />
</geometry>
</visual>
<collision>
@@ -102,36 +93,34 @@
<geometry name="leg1_collision_geom">
<cylinder radius="${leg_radius}" length="${table_height}" />
</geometry>
- <map name="leg1_collision" flag="gazebo">
- <elem key="mu1" value="1000.0" />
- <elem key="mu2" value="1000.0" />
- <elem key="kp" value="10000000.0" />
- <elem key="kd" value="1.0" />
- </map>
</collision>
- <map name="leg1_collision" flag="gazebo">
- <elem key="selfCollide">true</elem>
- </map>
</link>
+ <gazebo reference="leg1_link">
+ <material>Gazebo/Red</material>
+ <mu1>1000.0</mu1>
+ <mu2>1000.0</mu2>
+ <kp>10000000.0</kp>
+ <kd>1.0</kd>
+ <selfCollide>true</selfCollide>
+ </gazebo>
- <link name="leg2_link">
- <parent name="table_top_link" />
+ <joint name="leg2_joint" type="fixed" >
+ <parent link="table_top_link" />
<origin xyz="${-table_depth/2} ${table_depth/2} 0" rpy="0 0 0" />
- <joint name="leg2_joint" />
+ <child link="leg2_link" />
+ </joint>
+ <link name="leg2_link">
<inertial>
<mass value="100" />
- <com xyz="0 0 ${-table_height/2}" />
+ <origin xyz="0 0 ${-table_height/2}" />
<inertia ixx="0.1" ixy="0" ixz="0"
iyy="0.1" iyz="0"
izz="0.01" />
</inertial>
<visual>
<origin xyz="0.0 0.0 ${-table_height/2}" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Red</elem>
- </map>
<geometry name="leg2_visual_geom">
- <mesh scale="${leg_radius*2} ${leg_radius*2} ${table_height}" />
+ <cylinder radius="${leg_radius}" length="${table_height}" />
</geometry>
</visual>
<collision>
@@ -139,36 +128,34 @@
<geometry name="leg2_collision_geom">
<cylinder radius="${leg_radius}" length="${table_height}" />
</geometry>
- <map name="leg2_collision" flag="gazebo">
- <elem key="mu1" value="1000.0" />
- <elem key="mu2" value="1000.0" />
- <elem key="kp" value="10000000.0" />
- <elem key="kd" value="1.0" />
- </map>
</collision>
- <map name="leg2_collision" flag="gazebo">
- <elem key="selfCollide">true</elem>
- </map>
</link>
+ <gazebo reference="leg2_link">
+ <material>Gazebo/Red</material>
+ <mu1>1000.0</mu1>
+ <mu2>1000.0</mu2>
+ <kp>10000000.0</kp>
+ <kd>1.0</kd>
+ <selfCollide>true</selfCollide>
+ </gazebo>
- <link name="leg3_link">
- <parent name="table_top_link" />
+ <joint name="leg3_joint" type="fixed" >
+ <parent link="table_top_link" />
<origin xyz="${table_depth/2} ${-table_depth/2} 0" rpy="0 0 0" />
- <joint name="leg3_joint" />
+ <child link="leg3_link" />
+ </joint>
+ <link name="leg3_link">
<inertial>
<mass value="100" />
- <com xyz="0 0 ${-table_height/2}" />
+ <origin xyz="0 0 ${-table_height/2}" />
<inertia ixx="0.1" ixy="0" ixz="0"
iyy="0.1" iyz="0"
izz="0.01" />
</inertial>
<visual>
<origin xyz="0.0 0.0 ${-table_height/2}" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Red</elem>
- </map>
<geometry name="leg3_visual_geom">
- <mesh scale="${leg_radius*2} ${leg_radius*2} ${table_height}" />
+ <cylinder radius="${leg_radius}" length="${table_height}" />
</geometry>
</visual>
<collision>
@@ -176,36 +163,34 @@
<geometry name="leg3_collision_geom">
<cylinder radius="${leg_radius}" length="${table_height}" />
</geometry>
- <map name="leg3_collision" flag="gazebo">
- <elem key="mu1" value="1000.0" />
- <elem key="mu2" value="1000.0" />
- <elem key="kp" value="10000000.0" />
- <elem key="kd" value="1.0" />
- </map>
</collision>
- <map name="leg3_collision" flag="gazebo">
- <elem key="selfCollide">true</elem>
- </map>
</link>
+ <gazebo reference="leg3_link">
+ <material>Gazebo/Red</material>
+ <mu1>1000.0</mu1>
+ <mu2>1000.0</mu2>
+ <kp>10000000.0</kp>
+ <kd>1.0</kd>
+ <selfCollide>true</selfCollide>
+ </gazebo>
- <link name="leg4_link">
- <parent name="table_top_link" />
+ <joint name="leg4_joint" type="fixed" >
+ <parent link="table_top_link" />
<origin xyz="${-table_depth/2} ${-table_depth/2} 0" rpy="0 0 0" />
- <joint name="leg4_joint" />
+ <child link="leg4_link" />
+ </joint>
+ <link name="leg4_link">
<inertial>
<mass value="100" />
- <com xyz="0 0 ${-table_height/2}" />
+ <origin xyz="0 0 ${-table_height/2}" />
<inertia ixx="0.1" ixy="0" ixz="0"
iyy="0.1" iyz="0"
izz="0.01" />
</inertial>
<visual>
<origin xyz="0.0 0.0 ${-table_height/2}" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Red</elem>
- </map>
<geometry name="leg4_visual_geom">
- <mesh scale="${leg_radius*2} ${leg_radius*2} ${table_height}" />
+ <cylinder radius="${leg_radius}" length="${table_height}" />
</geometry>
</visual>
<collision>
@@ -213,36 +198,34 @@
<geometry name="leg4_collision_geom">
<cylinder radius="${leg_radius}" length="${table_height}" />
</geometry>
- <map name="leg4_collision" flag="gazebo">
- <elem key="mu1" value="1000.0" />
- <elem key="mu2" value="1000.0" />
- <elem key="kp" value="10000000.0" />
- <elem key="kd" value="1.0" />
- </map>
</collision>
- <map name="leg4_collision" flag="gazebo">
- <elem key="selfCollide">true</elem>
- </map>
</link>
+ <gazebo reference="leg4_link">
+ <material>Gazebo/Red</material>
+ <mu1>1000.0</mu1>
+ <mu2>1000.0</mu2>
+ <kp>10000000.0</kp>
+ <kd>1.0</kd>
+ <selfCollide>...
[truncated message content] |