|
From: <hsu...@us...> - 2008-08-12 18:21:13
|
Revision: 2948
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=2948&view=rev
Author: hsujohnhsu
Date: 2008-08-12 18:21:16 +0000 (Tue, 12 Aug 2008)
Log Message:
-----------
Moved xml files for testing single motor hardware into wg_robot_description/motor_tests.
Renamed RosGazeboNode dependent models to robot_rosgazebo.world.
New pr2_xml.model contains information for the new actuator array plugins.
Moved obsolete robot and pr2 model files into world/tests directory.
Renamed main robot description files: actuators.xml, transmissions.xml, controllers.xml, pr2.xml.
controllers_gazebo.xml : new gazebo_actuators plugin
controllers_gazebo_rosgazebo.xml : old Pr2_Actarray plugin
Updated 2dnav-gazebo demos accordingly, removed botherder starting from xmls, seems to be causing crashes.
Modified Paths:
--------------
pkg/trunk/demos/2dnav-gazebo/2dnav-gazebo-test.xml
pkg/trunk/demos/2dnav-gazebo/2dnav-gazebo-wg.xml
pkg/trunk/demos/2dnav-gazebo/2dnav-gazebo.xml
pkg/trunk/robot_descriptions/gazebo_robot_description/CMakeLists.txt
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_floorobj.world
pkg/trunk/robot_descriptions/wg_robot_description/README
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2_test.xml
Added Paths:
-----------
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_rosgazebo.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_rosgazebo_wg.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/pr2-test.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/pr2.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/pr2_autogen.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/pr2_new_plugins.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/pr2_torque.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/pr2_torque_control.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/pr2_torque_position.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/pr2_tray1.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/pr2_tray2.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/pr2_tray3.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/pr2_tray_hand.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/pr2_trimesh.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/robot_controls.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/robot_new_plugins.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/robot_pioneer.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/robot_torque.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/robot_torque_control.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/robot_torque_position.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/robot_tray.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/robot_trimesh.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/walls-only.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/tests/willow-walls.model
pkg/trunk/robot_descriptions/wg_robot_description/motor_tests/
pkg/trunk/robot_descriptions/wg_robot_description/pr2/actuators.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controller.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_rosgazebo.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2_rosgazebo.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/transmissions.xml
Removed Paths:
-------------
pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2-test.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_autogen.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_new_plugins.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_torque.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_torque_control.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_torque_position.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_tray1.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_tray2.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_tray3.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_tray_hand.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_trimesh.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_controls.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_new_plugins.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_pioneer.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_torque.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_torque_control.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_torque_position.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_tray.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_trimesh.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_wg.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/walls-only.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/willow-walls.model
pkg/trunk/robot_descriptions/wg_robot_description/pr2/actuator_test.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controller_test.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/transmission_test.xml
Modified: pkg/trunk/demos/2dnav-gazebo/2dnav-gazebo-test.xml
===================================================================
--- pkg/trunk/demos/2dnav-gazebo/2dnav-gazebo-test.xml 2008-08-12 17:54:16 UTC (rev 2947)
+++ pkg/trunk/demos/2dnav-gazebo/2dnav-gazebo-test.xml 2008-08-12 18:21:16 UTC (rev 2948)
@@ -1,5 +1,4 @@
<launch>
- <master auto="start"/>
<group name="wg">
<node pkg="namelookup" type="namelookup_server" respawn="false"/>
<include file="$(find wg_robot_description)/send.xml"/>
Modified: pkg/trunk/demos/2dnav-gazebo/2dnav-gazebo-wg.xml
===================================================================
--- pkg/trunk/demos/2dnav-gazebo/2dnav-gazebo-wg.xml 2008-08-12 17:54:16 UTC (rev 2947)
+++ pkg/trunk/demos/2dnav-gazebo/2dnav-gazebo-wg.xml 2008-08-12 18:21:16 UTC (rev 2948)
@@ -1,9 +1,8 @@
<launch>
- <master auto="start"/>
<group name="wg">
<node pkg="namelookup" type="namelookup_server" respawn="false"/>
<include file="$(find wg_robot_description)/send.xml"/>
- <node pkg="pr2_gazebo" type="run-gazebo.sh" args="$(find gazebo_robot_description)/world/robot_wg.world" respawn="true" />
+ <node pkg="pr2_gazebo" type="run-gazebo.sh" args="$(find gazebo_robot_description)/world/robot_rosgazebo_wg.world" respawn="true" />
<node pkg="map_server" type="map_server" args="$(find gazebo_robot_description)/world/Media/materials/textures/willowMap.png 0.1" respawn="false" />
<node pkg="pr2_gazebo" type="run-pr2_gazebo.sh" args="" respawn="true" />
<node pkg="amcl_player" type="amcl_player" args="scan:=base_scan" respawn="false" />
Modified: pkg/trunk/demos/2dnav-gazebo/2dnav-gazebo.xml
===================================================================
--- pkg/trunk/demos/2dnav-gazebo/2dnav-gazebo.xml 2008-08-12 17:54:16 UTC (rev 2947)
+++ pkg/trunk/demos/2dnav-gazebo/2dnav-gazebo.xml 2008-08-12 18:21:16 UTC (rev 2948)
@@ -1,9 +1,8 @@
<launch>
- <master auto="start"/>
<group name="wg">
<node pkg="namelookup" type="namelookup_server" respawn="false"/>
<include file="$(find wg_robot_description)/send.xml"/>
- <node pkg="pr2_gazebo" type="run-gazebo.sh" args="$(find gazebo_robot_description)/world/robot.world" respawn="true" />
+ <node pkg="pr2_gazebo" type="run-gazebo.sh" args="$(find gazebo_robot_description)/world/robot_rosgazebo.world" respawn="true" />
<node pkg="map_server" type="map_server" args="$(find gazebo_robot_description)/world/Media/materials/textures/map3.png 0.1" respawn="false" />
<node pkg="pr2_gazebo" type="run-pr2_gazebo.sh" args="" respawn="true" />
<node pkg="amcl_player" type="amcl_player" args="scan:=base_scan" respawn="false" />
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/CMakeLists.txt
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/CMakeLists.txt 2008-08-12 17:54:16 UTC (rev 2947)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/CMakeLists.txt 2008-08-12 18:21:16 UTC (rev 2948)
@@ -18,10 +18,16 @@
DEPENDS urdf2gazebo
COMMENT "Building Gazebo model for PR2")
-add_custom_target(pr2_gazebo_model_nolimit ALL
- COMMAND ${urdf2gazebo_exe} ${wg_robot_description_PACKAGE_PATH}/pr2/pr2.xml ${gazebo_robot_description_PACKAGE_PATH}/world/pr2_xml_nolimit.model 1
+add_custom_target(pr2_gazebo_model_nolimit_rosgazebo ALL
+ COMMAND ${urdf2gazebo_exe} ${wg_robot_description_PACKAGE_PATH}/pr2/pr2_rosgazebo.xml ${gazebo_robot_description_PACKAGE_PATH}/world/pr2_xml_nolimit.model 1
DEPENDS urdf2gazebo
COMMENT "Building Gazebo model for PR2")
+
+add_custom_target(pr2_gazebo_model_rosgazebo ALL
+ COMMAND ${urdf2gazebo_exe} ${wg_robot_description_PACKAGE_PATH}/pr2/pr2_rosgazebo.xml ${gazebo_robot_description_PACKAGE_PATH}/world/pr2_xml_rosgazebo.model
+ DEPENDS urdf2gazebo
+ COMMENT "Building Gazebo model for PR2")
+
add_custom_target(pr2_gazebo_model_test ALL
COMMAND ${urdf2gazebo_exe} ${wg_robot_description_PACKAGE_PATH}/pr2/pr2_test.xml ${gazebo_robot_description_PACKAGE_PATH}/world/pr2_xml_test.model
DEPENDS urdf2gazebo
Deleted: pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2-test.model
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2-test.model 2008-08-12 17:54:16 UTC (rev 2947)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2-test.model 2008-08-12 18:21:16 UTC (rev 2948)
@@ -1,2001 +0,0 @@
-<?xml version="1.0"?>
-
-<!-- PR2 model -->
-<model:physical name="pr2_model"
- xmlns:model="http://playerstage.sourceforge.net/gazebo/xmlschema/#model"
- xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
- xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body"
- xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom"
- xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#joint"
- xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
- xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
- >
-
- <xyz>0.0 0.0 0.0</xyz>
- <rpy>0.0 0.0 0.0 </rpy>
-
- <body:box name="base_body">
- <xyz>0.175 0.0 0.15 </xyz> <!-- base bottom is h/2 + some height for wheel clearance-->
- <rpy>0.0 0.0 0.0 </rpy>
-
- <!-- report when this body collides with static bodies -->
- <reportStaticCollision>true</reportStaticCollision>
-
- <geom:box name="base_body_geom">
-
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass>70.750964</mass>
- <ixx>5.6522326992070</ixx>
- <ixy>-0.009719934438</ixy>
- <ixz>1.2939882264230</ixz>
- <iyy>5.6694731586520</iyy>
- <iyz>-0.007379583694</iyz>
- <izz>3.6831963517260</izz>
- <cx>-0.061523</cx>
- <cy> 0.000942</cy>
- <cz> 0.293569</cz>
-
-
- <xyz> 0.0 0.00 0.000</xyz>
- <size>0.65 0.65 0.26</size>
- <mul>1</mul>
- <!--color> 0.0 1.0 0.0</color-->
- <visual>
- <xyz>0.0 0.0 -0.13</xyz> <!-- shift center of model to match the actual model -->
- <!--size>0.65 0.65 0.65</size-->
- <scale>0.001 0.001 0.001</scale>
- <rpy> 90.0 0.0 90.0 </rpy>
- <mesh>pr2/pr2_base.mesh</mesh>
- <material>Gazebo/Shell</material>
- </visual>
- </geom:box>
-
- </body:box>
-
-
- <!-- Hokuyo laser body -->
- <body:box name="base_laser_body">
- <xyz>0.45 0.0 0.27</xyz> <!-- from the robot coordinate system (center bottom of base box)-->
- <rpy>0.0 0.0 0.0</rpy>
-
- <geom:box name="base_laser_box">
- <xyz>0.0 0.0 0.02</xyz>
- <rpy>0 0 0</rpy>
- <size>0.05 0.05 0.041</size>
- <mass>0.12</mass>
-
- <visual>
- <scale>0.05 0.05 0.041</scale>
- <mesh>unit_box</mesh>
- <material>Gazebo/Blue</material>
- </visual>
-
- </geom:box>
- <geom:cylinder name="base_laser_cylinder1">
- <xyz>0.0 0.0 0.041</xyz>
- <rpy>0 0 0</rpy>
- <size>0.02 0.013</size>
- <mass>0.02</mass>
-
- <visual>
- <rpy>0 0 0</rpy>
- <scale>0.04 0.04 0.013</scale>
- <mesh>unit_cylinder</mesh>
- <material>Gazebo/Black</material>
- </visual>
-
- </geom:cylinder>
-
- <geom:cylinder name="base_laser_cylinder2">
- <xyz>0.0 0.0 0.054</xyz>
- <rpy>0 0 0</rpy>
- <size>0.018 0.009</size>
- <mass>0.02</mass>
-
- <visual>
- <rpy>0 0 0</rpy>
- <size>0.036 0.036 0.009</size>
- <mesh>unit_cylinder</mesh>
- <material>Gazebo/Black</material>
- </visual>
-
- </geom:cylinder>
-
- <geom:cylinder name="base_laser_cylinder3">
- <xyz>0.0 0.0 0.063</xyz>
- <rpy>0 0 0</rpy>
- <size>0.0175 0.008</size>
- <mass>0.02</mass>
-
- <visual>
- <rpy>0 0 0</rpy>
- <size>0.035 0.035 0.008</size>
- <mesh>unit_cylinder</mesh>
- <material>Gazebo/Shell</material>
- </visual>
-
- </geom:cylinder>
-
-
- <sensor:ray name="base_laser_1">
- <rayCount>68</rayCount>
- <rangeCount>683</rangeCount>
- <laserCount>1</laserCount>
- <origin>0.0 0.0 0.05</origin>
-
- <minAngle>-135</minAngle>
- <maxAngle>135</maxAngle>
-
- <minRange>0.05</minRange>
- <maxRange>10.0</maxRange>
- <updateRate>10.0</updateRate>
- <controller:sicklms200_laser name="base_laser_controller_1">
- <interface:laser name="base_laser_iface_1"/>
- <updateRate>10</updateRate>
- </controller:sicklms200_laser>
- </sensor:ray>
- <!--
- -->
- <!--
- <sensor:ray2 name="base_laser_1">
- <rayCount>683</rayCount>
- <rangeCount>683</rangeCount>
- <laserCount>1</laserCount>
- <origin>0.0 0.0 0.05</origin>
-
- <minAngle>-135</minAngle>
- <maxAngle>135</maxAngle>
-
- <minRange>0.05</minRange>
- <maxRange>10.0</maxRange>
- <controller:sick2lms200_laser name="base_laser_controller_1">
- <interface:laser name="base_laser_iface_1"/>
- <updateRate>10</updateRate>
- </controller:sick2lms200_laser>
- </sensor:ray2>
- -->
- </body:box>
-
- <!-- attach hokuyo to torso -->
- <joint:hinge name="base_laser_torso_attach_joint">
- <body1>base_body</body1>
- <body2>base_laser_body</body2>
- <anchor>base_laser_body</anchor>
- <axis> 1.0 0.0 0.0 </axis>
- <lowStop> 0.0 </lowStop>
- <highStop> 0.0 </highStop>
- </joint:hinge>
-
-
-
-
- <!-- ========== spine and shoulder =========== -->
-
- <body:box name="torso_body">
- <xyz>0.056 0.0 0.45</xyz>
- <rpy>0.0 0.0 0.0</rpy>
-
- <!-- report when this body collides with static bodies -->
- <reportStaticCollision>true</reportStaticCollision>
-
- <geom:box name="torso_geom">
- <xyz> 0.0 0.0 0.0 </xyz>
- <size>0.1 0.2 0.6 </size>
- <mass>1</mass>
- <visual>
- <!-- x y z -->
- <xyz> 0.1 0.0 -0.425 </xyz>
- <!--size>0.6 0.8 0.6 </size-->
- <scale>0.001 0.001 0.001</scale>
- <rpy>90.0 0.0 90.0 </rpy>
- <mesh>pr2/pr2_body.mesh</mesh>
- <material>Gazebo/PioneerBody</material>
- </visual>
- </geom:box>
-
- <geom:box name="shoulder_geom">
- <xyz> 0.1 0.00 0.54</xyz>
- <size>0.3 0.65 0.02</size>
- <mass>1</mass>
- <visual>
- <!--size>0.3 0.65 0.02</size-->
- <size>0.0 0.0 0.0</size>
- <mesh>unit_box</mesh>
- <material>Gazebo/Shell</material>
- </visual>
- </geom:box>
-
- </body:box>
-
- <joint:slider name="torso_spine_slider">
- <body1>base_body</body1>
- <body2>torso_body</body2>
- <anchor>torso_body</anchor>
- <lowStop> 0.0 </lowStop>
- <highStop> 0.5 </highStop>
- <axis>0.0 0.0 1.0 </axis>
- <axisOffset> 0.0 0.0 0.0 </axisOffset>
- </joint:slider>
-
- <!-- ========== Right Arm =========== -->
- <body:cylinder name="shoulder_pan_body_right">
- <xyz> 0.1829361 -0.1329361 0.64 </xyz>
- <rpy> 0.0 0.0 0.0 </rpy>
- <geom:cylinder name="shoulder_pan_body_right_geom">
-
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass> 16.29553 </mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.793291393007 </ixx>
- <ixy> 0.003412032973 </ixy>
- <ixz> 0.0096614481 </ixz>
- <iyy> 0.818419457224</iyy>
- <iyz> -0.033999499551</iyz>
- <izz> 0.13915007406 </izz>
- <cx> -0.005215 </cx>
- <cy> -0.030552 </cy>
- <cz> -0.175743 </cz>
-
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <size> 0.13 0.60</size> <!-- radius and length -->
- <visual>
- <xyz> 0.00 0.0 0.185 </xyz>
- <rpy> 90.0 0.0 90.0 </rpy>
- <!--size> 0.26 0.6 0.36</size-->
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_sh_turret.mesh</mesh>
- <material>Gazebo/Green</material>
- </visual>
- </geom:cylinder>
- </body:cylinder>
-
- <body:cylinder name="upperarm_joint_right">
- <xyz> 0.285 -0.15 0.8269 </xyz>
- <rpy> 90.0 0.0 0.0 </rpy>
- <geom:cylinder name="upperarm_joint_right_geom">
-
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass> 2.41223</mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.016640333585 </ixx>
- <ixy> 0.002696462583 </ixy>
- <ixz> 0.001337742275 </ixz>
- <iyy> 0.017232603914 </iyy>
- <iyz> -0.003605106514 </iyz>
- <izz> 0.018723553425 </izz>
- <cx> -0.035895 </cx>
- <cy> 0.014422 </cy>
- <cz> -0.028263</cz>
-
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <size> 0.12 0.10</size> <!-- radius and length -->
- <visual>
- <xyz> 0.0 0.0 0.0 </xyz>
- <rpy> 0.0 90.0 0.0 </rpy>
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_sh_pitch.mesh</mesh>
- <material>Gazebo/PioneerBody</material>
- </visual>
- </geom:cylinder>
- </body:cylinder>
-
- <body:box name="upperarm_right">
- <xyz> 0.575 -0.15 0.8269 </xyz>
- <rpy> 0.0 0.0 0.0 </rpy>
- <geom:box name="upperarm_right_geom">
-
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass> 4.9481 </mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.073060715309 </ixx>
- <ixy> 0.000547745916 </ixy>
- <ixz> 0.000119476885 </ixz>
- <iyy> 0.072124510748 </iyy>
- <iyz> 0.001544932307 </iyz>
- <izz> 0.013383284908 </izz>
- <cx> 0.001205 </cx>
- <cy> -0.016293 </cy>
- <cz> 0.21227</cz>
-
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <size> 0.35 0.12 0.15</size>
- <visual>
- <xyz> -0.20 0.0 0.0 </xyz>
- <rpy>180.0 -90.0 0.0 </rpy>
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_sh_roll.mesh</mesh>
- <material>Gazebo/Shell</material>
- </visual>
- </geom:box>
- </body:box>
-
- <body:cylinder name="elbow_right">
- <xyz> 0.6850 -0.15 0.8269 </xyz>
- <rpy> 90.0 0.0 0.0 </rpy>
- <geom:cylinder name="elbow_right_geom">
-
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass> 1.689246</mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.003275298548 </ixx>
- <ixy> 0.000292046674 </ixy>
- <ixz> -0.000077359282 </ixz>
- <iyy> 0.003236815206 </iyy>
- <iyz> -0.000001162155 </iyz>
- <izz> 0.00410053774 </izz>
- <cx> -0.011638 </cx>
- <cy> 0.013173 </cy>
- <cz> 0.001228</cz>
-
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <size> 0.08 0.1</size> <!-- radius and length -->
- <visual>
- <xyz> -0.135 0.0 0.0 </xyz>
- <rpy> 0.0 -90.0 0.0 </rpy>
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_elbow_pitch.mesh</mesh>
- <material>Gazebo/PioneerBody</material>
- </visual>
- </geom:cylinder>
- </body:cylinder>
-
- <body:box name="forearm_right">
- <xyz> 0.90225 -0.15 0.8269 </xyz>
- <rpy> 0.0 0.0 0.0 </rpy>
- <geom:box name="forearm_right_geom">
-
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass> 1.804155 </mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.012430552544 </ixx>
- <ixy> -0.000003671102 </ixy>
- <ixz> 0.000029379389 </ixz>
- <iyy> 0.013567548848 </iyy>
- <iyz> -0.000427679042 </iyz>
- <izz> 0.001755089866 </izz>
- <cx> -0.000058 </cx>
- <cy> 0.013779 </cy>
- <cz> 0.179474 </cz>
-
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <size> 0.27 0.12 0.08</size>
- <visual>
- <xyz> 0.11 0.0 0.0 </xyz>
- <rpy> 0.0 -90.0 -90.0 </rpy>
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_forearm_roll.mesh</mesh>
- <material>Gazebo/Shell</material>
- </visual>
- </geom:box>
- </body:box>
-
- <body:cylinder name="wrist_right">
- <xyz> 1.008 -0.15 0.8269 </xyz>
- <rpy> 90.0 0.0 0.0 </rpy>
- <geom:cylinder name="wrist_right_geom">
-
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass> 1.804155 </mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.012430552544 </ixx>
- <ixy> -0.000003671102 </ixy>
- <ixz> 0.000029379389 </ixz>
- <iyy> 0.013567548848 </iyy>
- <iyz> -0.000427679042 </iyz>
- <izz> 0.001755089866 </izz>
- <cx> 0.0 </cx>
- <cy> 0.0 </cy>
- <cz> 0.0 </cz>
-
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <size> 0.031 0.1</size> <!-- radius and length -->
- <visual>
- <xyz> 0.008 0.0 0.0 </xyz>
- <rpy> 90.0 0.0 -90.0 </rpy>
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_wrist_pitch.mesh</mesh>
- <material>Gazebo/PioneerBody</material>
- </visual>
- </geom:cylinder>
- </body:cylinder>
-
- <body:box name="palm_right">
- <xyz> 1.10 -0.15 0.8269</xyz>
- <rpy> 0.0 0.0 0.0 </rpy>
- <geom:box name="palm_right_geom">
-
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass> 1.804155 </mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.012430552544 </ixx>
- <ixy> -0.000003671102 </ixy>
- <ixz> 0.000029379389 </ixz>
- <iyy> 0.013567548848 </iyy>
- <iyz> -0.000427679042 </iyz>
- <izz> 0.001755089866 </izz>
- <cx> 0.0 </cx>
- <cy> 0.0 </cy>
- <cz> 0.0 </cz>
-
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <size> 0.11 0.10 0.05</size>
- <visual>
- <xyz> -0.035 0.0 0.0 </xyz>
- <rpy> 0.0 90.0 90.0 </rpy>
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_wrist_roll.mesh</mesh>
- <material>Gazebo/Shell</material>
- </visual>
- </geom:box>
- </body:box>
-
- <body:box name="finger_1_right">
- <xyz> 1.18 -0.17 0.8269 </xyz>
- <rpy> 0.0 0.0 0.0 </rpy>
- <geom:box name="finger_1_right_geom">
- <kp>100000000.0</kp>
- <kd>1.0</kd>
- <size> 0.05 0.01 0.025</size>
- <mass>0.1</mass>
- <visual>
- <size> 0.05 0.01 0.025</size>
- <mesh>unit_box</mesh>
- <material>Gazebo/PioneerBody</material>
- </visual>
- </geom:box>
- </body:box>
-
- <body:box name="finger_2_right">
- <xyz> 1.18 -0.13 0.8269 </xyz>
- <rpy> 0.0 0.0 0.0 </rpy>
- <geom:box name="finger_2_right_geom">
- <kp>100000000.0</kp>
- <kd>1.0</kd>
- <size> 0.05 0.01 0.025</size>
- <mass>0.1</mass>
- <visual>
- <size> 0.05 0.01 0.025</size>
- <mesh>unit_box</mesh>
- <material>Gazebo/Blue</material>
- </visual>
- </geom:box>
- </body:box>
-
-
-
-
-
-
- <joint:hinge name="shoulder_pan_right">
- <body2>shoulder_pan_body_right</body2>
- <body1>torso_body</body1>
- <anchor>shoulder_pan_body_right</anchor>
- <axis> 0.0 0.0 1.0 </axis>
- </joint:hinge>
-
- <joint:hinge name="upperarm_pitch_joint_right">
- <body1>shoulder_pan_body_right</body1>
- <body2>upperarm_joint_right</body2>
- <anchor>upperarm_joint_right</anchor>
- <axis> 0.0 1.0 0.0 </axis>
- </joint:hinge>
-
- <joint:hinge name="upperarm_roll_joint_right">
- <body1>upperarm_right</body1>
- <body2>upperarm_joint_right</body2>
- <anchor>upperarm_joint_right</anchor>
- <axis> 1.0 0.0 0.0 </axis>
- </joint:hinge>
-
- <joint:hinge name="elbow_pitch_joint_right">
- <body2>elbow_right</body2>
- <body1>upperarm_right</body1>
- <anchor>elbow_right</anchor>
- <axis> 0.0 1.0 0.0 </axis>
- </joint:hinge>
-
- <joint:hinge name="forearm_roll_joint_right">
- <body2>forearm_right</body2>
- <body1>elbow_right</body1>
- <anchor>forearm_right</anchor>
- <axis> 1.0 0.0 0.0 </axis>
- </joint:hinge>
-
- <joint:hinge name="wrist_pitch_joint_right">
- <body2>wrist_right</body2>
- <body1>forearm_right</body1>
- <anchor>wrist_right</anchor>
- <axis> 0.0 1.0 0.0 </axis>
- </joint:hinge>
-
- <joint:hinge name="palm_roll_joint_right">
- <body2>palm_right</body2>
- <body1>wrist_right</body1>
- <anchor>palm_right</anchor>
- <axis> 1.0 0.0 0.0 </axis>
- <axisOffset> 0.0 0.0 0.0 </axisOffset>
- </joint:hinge>
-
- <joint:slider name="finger_1_slider_right">
- <body2>finger_1_right</body2>
- <body1>palm_right</body1>
- <anchor>finger_1_right</anchor>
- <lowStop> -0.02 </lowStop> <!-- red close -->
- <highStop> 0.05 </highStop> <!-- red open -->
- <axis>0.0 1.0 0.0 </axis>
- </joint:slider>
-
- <joint:slider name="finger_2_slider_right">
- <body2>finger_2_right</body2>
- <body1>palm_right</body1>
- <anchor>finger_2_right</anchor>
- <lowStop> -0.05 </lowStop> <!-- white open -->
- <highStop> 0.02 </highStop> <!-- white close -->
- <axis>0.0 1.0 0.0 </axis>
- </joint:slider>
-
- <!-- ========== Left Arm =========== -->
- <body:cylinder name="shoulder_pan_body_left">
- <xyz> 0.1829361 0.1329361 0.64 </xyz>
- <rpy> 0.0 0.0 0.0 </rpy>
- <geom:cylinder name="shoulder_pan_body_left_geom">
-
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass> 16.29553 </mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.793291393007 </ixx>
- <ixy> 0.003412032973 </ixy>
- <ixz> 0.0096614481 </ixz>
- <iyy> 0.818419457224</iyy>
- <iyz> -0.033999499551</iyz>
- <izz> 0.13915007406 </izz>
- <cx> -0.005215 </cx>
- <cy> -0.030552 </cy>
- <cz> -0.175743 </cz>
-
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <size> 0.13 0.6</size> <!-- radius and length -->
- <visual>
- <xyz> 0.00 0.0 0.185 </xyz>
- <rpy> 90.0 0.0 90.0 </rpy>
- <!--size> 0.26 0.6 0.36</size-->
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_sh_turret.mesh</mesh>
- <material>Gazebo/Green</material>
- </visual>
- </geom:cylinder>
- </body:cylinder>
-
- <body:cylinder name="upperarm_joint_left">
- <xyz> 0.285 0.15 0.8269 </xyz>
- <rpy> 90.0 0.0 0.0 </rpy>
- <geom:cylinder name="upperarm_joint_left_geom">
-
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass> 2.41223</mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.016640333585 </ixx>
- <ixy> 0.002696462583 </ixy>
- <ixz> 0.001337742275 </ixz>
- <iyy> 0.017232603914 </iyy>
- <iyz> -0.003605106514 </iyz>
- <izz> 0.018723553425 </izz>
- <cx> -0.035895 </cx>
- <cy> 0.014422 </cy>
- <cz> -0.028263</cz>
-
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <size> 0.12 0.10</size> <!-- radius and length -->
- <visual>
- <xyz> 0.0 0.0 0.0 </xyz>
- <rpy> 0.0 90.0 0.0 </rpy>
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_sh_pitch.mesh</mesh>
- <material>Gazebo/PioneerBody</material>
- </visual>
- </geom:cylinder>
- </body:cylinder>
-
- <body:box name="upperarm_left">
- <xyz> 0.575 0.15 0.8269 </xyz>
- <rpy> 0.0 0.0 0.0 </rpy>
- <geom:box name="upperarm_left_geom">
-
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass> 4.9481 </mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.073060715309 </ixx>
- <ixy> 0.000547745916 </ixy>
- <ixz> 0.000119476885 </ixz>
- <iyy> 0.072124510748 </iyy>
- <iyz> 0.001544932307 </iyz>
- <izz> 0.013383284908 </izz>
- <cx> 0.001205 </cx>
- <cy> -0.016293 </cy>
- <cz> 0.21227</cz>
-
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <size> 0.35 0.12 0.15</size>
- <visual>
- <xyz> -0.20 0.0 0.0 </xyz>
- <rpy>180.0 -90.0 0.0 </rpy>
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_sh_roll.mesh</mesh>
- <material>Gazebo/Shell</material>
- </visual>
- </geom:box>
- </body:box>
-
- <body:cylinder name="elbow_left">
- <xyz> 0.6850 0.15 0.8269 </xyz>
- <rpy> 90.0 0.0 0.0 </rpy>
- <geom:cylinder name="elbow_left_geom">
-
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass> 1.689246</mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.003275298548 </ixx>
- <ixy> 0.000292046674 </ixy>
- <ixz> -0.000077359282 </ixz>
- <iyy> 0.003236815206 </iyy>
- <iyz> -0.000001162155 </iyz>
- <izz> 0.00410053774 </izz>
- <cx> -0.011638 </cx>
- <cy> 0.013173 </cy>
- <cz> 0.001228</cz>
-
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <size> 0.08 0.1</size> <!-- radius and length -->
- <visual>
- <xyz> -0.135 0.0 0.0 </xyz>
- <rpy> 0.0 -90.0 0.0 </rpy>
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_elbow_pitch.mesh</mesh>
- <material>Gazebo/PioneerBody</material>
- </visual>
- </geom:cylinder>
- </body:cylinder>
-
- <body:box name="forearm_left">
- <xyz> 0.90225 0.15 0.8269 </xyz>
- <rpy> 0.0 0.0 0.0 </rpy>
- <geom:box name="forearm_left_geom">
-
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass> 1.804155 </mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.012430552544 </ixx>
- <ixy> -0.000003671102 </ixy>
- <ixz> 0.000029379389 </ixz>
- <iyy> 0.013567548848 </iyy>
- <iyz> -0.000427679042 </iyz>
- <izz> 0.001755089866 </izz>
- <cx> -0.000058 </cx>
- <cy> 0.013779 </cy>
- <cz> 0.179474 </cz>
-
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <size> 0.27 0.12 0.08</size>
- <visual>
- <xyz> 0.11 0.0 0.0 </xyz>
- <rpy> 0.0 -90.0 -90.0 </rpy>
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_forearm_roll.mesh</mesh>
- <material>Gazebo/Shell</material>
- </visual>
- </geom:box>
- </body:box>
-
- <body:cylinder name="wrist_left">
- <xyz> 1.008 0.15 0.8269 </xyz>
- <rpy> 90.0 0.0 0.0 </rpy>
- <geom:cylinder name="wrist_left_geom">
-
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass> 1.804155 </mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.012430552544 </ixx>
- <ixy> -0.000003671102 </ixy>
- <ixz> 0.000029379389 </ixz>
- <iyy> 0.013567548848 </iyy>
- <iyz> -0.000427679042 </iyz>
- <izz> 0.001755089866 </izz>
- <cx> 0.0 </cx>
- <cy> 0.0 </cy>
- <cz> 0.0 </cz>
-
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <size> 0.031 0.1</size> <!-- radius and length -->
- <visual>
- <xyz> 0.003 0.0 0.0 </xyz>
- <rpy> 90.0 0.0 -90.0 </rpy>
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_wrist_pitch.mesh</mesh>
- <material>Gazebo/PioneerBody</material>
- </visual>
- </geom:cylinder>
- </body:cylinder>
-
- <body:box name="palm_left">
- <xyz> 1.10 0.15 0.8269</xyz>
- <rpy> 0.0 0.0 0.0 </rpy>
- <geom:box name="palm_left_geom">
-
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass> 1.804155 </mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.012430552544 </ixx>
- <ixy> -0.000003671102 </ixy>
- <ixz> 0.000029379389 </ixz>
- <iyy> 0.013567548848 </iyy>
- <iyz> -0.000427679042 </iyz>
- <izz> 0.001755089866 </izz>
- <cx> 0.0 </cx>
- <cy> 0.0 </cy>
- <cz> 0.0 </cz>
-
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <size> 0.11 0.10 0.05</size>
- <visual>
- <xyz> -0.035 0.0 0.0 </xyz>
- <rpy> 0.0 90.0 90.0 </rpy>
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_wrist_roll.mesh</mesh>
- <material>Gazebo/Shell</material>
- </visual>
- </geom:box>
- </body:box>
-
- <body:box name="finger_1_left">
- <xyz> 1.18 0.13 0.8269 </xyz>
- <rpy> 0.0 0.0 0.0 </rpy>
- <geom:box name="finger_1_left_geom">
- <kp>100000000.0</kp>
- <kd>1.0</kd>
- <size> 0.05 0.01 0.025</size>
- <mass>0.1</mass>
- <visual>
- <size> 0.05 0.01 0.025</size>
- <mesh>unit_box</mesh>
- <material>Gazebo/PioneerBody</material>
- </visual>
- </geom:box>
- </body:box>
-
- <body:box name="finger_2_left">
- <xyz> 1.18 0.17 0.8269 </xyz>
- <rpy> 0.0 0.0 0.0 </rpy>
- <geom:box name="finger_2_left_geom">
- <kp>100000000.0</kp>
- <kd>1.0</kd>
- <size> 0.05 0.01 0.025</size>
- <mass>0.1</mass>
- <visual>
- <size> 0.05 0.01 0.025</size>
- <mesh>unit_box</mesh>
- <material>Gazebo/Blue</material>
- </visual>
- </geom:box>
- </body:box>
-
-
-
- <joint:hinge name="shoulder_pan_left">
- <body2>shoulder_pan_body_left</body2>
- <body1>torso_body</body1>
- <anchor>shoulder_pan_body_left</anchor>
- <axis> 0.0 0.0 1.0 </axis>
- </joint:hinge>
-
- <joint:hinge name="upperarm_pitch_joint_left">
- <body2>upperarm_joint_left</body2>
- <body1>shoulder_pan_body_left</body1>
- <anchor>upperarm_joint_left</anchor>
- <axis> 0.0 1.0 0.0 </axis>
- </joint:hinge>
-
- <joint:hinge name="upperarm_roll_joint_left">
- <body1>upperarm_left</body1>
- <body2>upperarm_joint_left</body2>
- <anchor>upperarm_joint_left</anchor>
- <axis> 1.0 0.0 0.0 </axis>
- </joint:hinge>
-
- <joint:hinge name="elbow_pitch_joint_left">
- <body2>elbow_left</body2>
- <body1>upperarm_left</body1>
- <anchor>elbow_left</anchor>
- <axis> 0.0 1.0 0.0 </axis>
- </joint:hinge>
-
- <joint:hinge name="forearm_roll_joint_left">
- <body2>forearm_left</body2>
- <body1>elbow_left</body1>
- <anchor>forearm_left</anchor>
- <axis> 1.0 0.0 0.0 </axis>
- </joint:hinge>
-
- <joint:hinge name="wrist_pitch_joint_left">
- <body2>wrist_left</body2>
- <body1>forearm_left</body1>
- <anchor>wrist_left</anchor>
- <axis> 0.0 1.0 0.0 </axis>
- </joint:hinge>
-
- <joint:hinge name="palm_roll_joint_left">
- <body2>palm_left</body2>
- <body1>wrist_left</body1>
- <anchor>palm_left</anchor>
- <axis> 1.0 0.0 0.0 </axis>
- </joint:hinge>
-
- <joint:slider name="finger_1_slider_left">
- <body2>finger_1_left</body2>
- <body1>palm_left</body1>
- <anchor>finger_1_left</anchor>
- <lowStop> -0.02 </lowStop> <!-- red close -->
- <highStop> 0.05 </highStop> <!-- red open -->
- <axis>0.0 1.0 0.0 </axis>
- </joint:slider>
-
- <joint:slider name="finger_2_slider_left">
- <body2>finger_2_left</body2>
- <body1>palm_left</body1>
- <anchor>finger_2_left</anchor>
- <lowStop> -0.05 </lowStop> <!-- white open -->
- <highStop> 0.02 </highStop> <!-- white close -->
- <axis>0.0 1.0 0.0 </axis>
- </joint:slider>
-
-
- <!-- neck body -->
- <body:box name="neck_body">
- <xyz>0.10 0.0 1.03</xyz>
- <rpy>0.0 0.0 0.0</rpy>
- <!--xyz>0.0 0.0 0.0</xyz>
- <rpy>0.0 0.0 0.0</rpy-->
- <geom:box name="neck_geom">
- <!--size>.20 .38 .14</size-->
- <size>0.01 0.01 0.01</size>
- <mass>0.01</mass>
- <visual>
- <mesh>unit_box</mesh>
- <!--size>.20 .38 .14</size-->
- <size>0.01 0.01 0.01</size>
- <material>Gazebo/Black</material>
- </visual>
- </geom:box>
- </body:box>
-
- <!-- attach neck to torso -->
- <joint:hinge name="neck_torso_attach_joint">
- <body1>torso_body</body1>
- <body2>neck_body</body2>
- <anchor>neck_body</anchor>
- <axis> 1.0 0.0 0.0 </axis>
- <lowStop> 0.0 </lowStop>
- <highStop> 0.0 </highStop>
- </joint:hinge>
-
- <body:box name="head_base_body">
- <xyz>0.10 0.0 1.13 </xyz>
- <rpy>0.0 0.0 0.0 </rpy>
- <!-- report when this body collides with static bodies -->
- <reportStaticCollision>true</reportStaticCollision>
- <geom:box name="head_base_geom">
- <xyz> 0.0 0.00 0.000</xyz>
- <size>0.165 0.21 0.003</size>
- <mass>0.1</mass>
- <mul>1</mul>
- <!--color> 0.0 1.0 0.0</color-->
- <visual>
- <size>0.165 0.21 0.003</size>
- <rpy>0.0 0.0 0.0 </rpy>
- <mesh>unit_box</mesh>
- <material>Gazebo/PioneerBody</material>
- </visual>
- </geom:box>
- </body:box>
-
- <body:box name="head_tilt_body">
- <xyz>0.10 0.0 1.07 </xyz>
- <rpy>0.0 0.0 0.0 </rpy>
- <!-- report when this body collides with static bodies -->
- <reportStaticCollision>true</reportStaticCollision>
- <geom:box name="head_tilt_geom">
- <xyz> 0.0 0.00 0.150</xyz>
- <size>0.165 0.21 0.003</size>
- <mass>0.1</mass>
- <mul>1</mul>
- <!--color> 0.0 1.0 0.0</color-->
- <visual>
- <size>0.165 0.21 0.003</size>
- <rpy>0.0 0.0 0.0 </rpy>
- <mesh>unit_box</mesh>
- <material>Gazebo/Black</material>
- </visual>
- </geom:box>
- <geom:box name="head_tilt_left_geom">
- <xyz> 0.0 -0.105 0.10</xyz>
- <size>0.165 0.003 0.10</size>
- <mass>0.1</mass>
- <mul>1</mul>
- <!--color> 0.0 1.0 0.0</color-->
- <visual>
- <size>0.165 0.003 0.10</size>
- <rpy>0.0 0.0 0.0 </rpy>
- <mesh>unit_box</mesh>
- <material>Gazebo/Shell</material>
- </visual>
- </geom:box>
- <geom:box name="head_tilt_right_geom">
- <xyz> 0.0 0.105 0.10</xyz>
- <size>0.165 0.003 0.10</size>
- <mass>0.1</mass>
- <mul>1</mul>
- <!--color> 0.0 1.0 0.0</color-->
- <visual>
- <size>0.165 0.003 0.10</size>
- <rpy>0.0 0.0 0.0 </rpy>
- <mesh>unit_box</mesh>
- <material>Gazebo/Shell</material>
- </visual>
- </geom:box>
- </body:box>
-
- <!-- attach head_base to head_tilt -->
- <joint:hinge name="head_tilt_joint">
- <body2>head_tilt_body</body2>
- <body1>head_base_body</body1>
- <anchor>head_tilt_body</anchor>
- <axis> 0.0 1.0 0.0 </axis>
- </joint:hinge>
-
- <!-- attach head to neck -->
- <joint:hinge name="neck_yaw_joint">
- <body1>neck_body</body1>
- <body2>head_base_body</body2>
- <anchor>head_base_body</anchor>
- <axis> 0.0 0.0 1.0 </axis>
- </joint:hinge>
-
-
- <!-- left camera -->
- <body:box name="ptz_cam_left_body">
- <xyz> 0.15 0.23 1.07 </xyz>
- <rpy> 0.00 0.0 0.00 </rpy>
- <sensor:camera name="ptz_cam_left_sensor">
- <imageSize>640 480</imageSize>
- <hfov>60</hfov>
- <nearClip>0.1</nearClip>
- <farClip>100</farClip>
- <updateRate>15.0</updateRate>
- <controller:generic_camera name="ptz_cam_left_controller">
- <updateRate>15.0</updateRate>
- <interface:camera name="ptz_cam_left_iface" />
- </controller:generic_camera>
- </sensor:camera>
- <geom:box name="ptz_cam_left_geom">
- <xyz> 0.00 0.00 0.00</xyz>
- <size>0.05 0.03 0.04</size>
- <mass>0.1</mass>
- <!--color> 0.0 1.0 0.0</color-->
- <visual>
- <size>0.05 0.03 0.04</size>
- <rpy>0.0 0.0 0.0 </rpy>
- <mesh>unit_box</mesh>
- <material>Gazebo/PioneerBody</material>
- </visual>
- </geom:box>
- </body:box>
- <body:box name="ptz_cam_base_left_body">
- <xyz> 0.15 0.20 1.07 </xyz>
- <rpy> 0.00 0.0 0.00 </rpy>
- <geom:box name="ptz_cam_base_left_geom">
- <xyz> 0.00 0.00 0.00</xyz>
- <size>0.05 0.02 0.02</size>
- <mass>0.1</mass>
- <!--color> 0.0 1.0 0.0</color-->
- <visual>
- <size>0.05 0.02 0.02</size>
- <rpy>0.0 0.0 0.0 </rpy>
- <mesh>unit_box</mesh>
- <material>Gazebo/Shell</material>
- </visual>
- </geom:box>
- </body:box>
-
- <!-- right camera -->
- <body:empty name="ptz_cam_right_body">
- <xyz> 0.15 -0.23 1.07 </xyz>
- <rpy> 0.00 0.0 0.00 </rpy>
- <sensor:camera name="ptz_cam_right_sensor">
- <imageSize>640 480</imageSize>
- <hfov>60</hfov>
- <nearClip>0.1</nearClip>
- <farClip>100</farClip>
- <updateRate>15.0</updateRate>
- <controller:generic_camera name="ptz_cam_right_controller">
- <updateRate>15.0</updateRate>
- <interface:camera name="ptz_cam_right_iface" />
- </controller:generic_camera>
- </sensor:camera>
- <geom:box name="ptz_cam_right_geom">
- <xyz> 0.00 0.00 0.00</xyz>
- <size>0.05 0.03 0.04</size>
- <mass>0.1</mass>
- <!--color> 0.0 1.0 0.0</color-->
- <visual>
- <size>0.05 0.03 0.04</size>
- <rpy>0.0 0.0 0.0 </rpy>
- <mesh>unit_box</mesh>
- <material>Gazebo/PioneerBody</material>
- </visual>
- </geom:box>
- </body:empty>
- <body:box name="ptz_cam_base_right_body">
- <xyz> 0.15 -0.20 1.07 </xyz>
- <rpy> 0.00 0.0 0.00 </rpy>
- <geom:box name="ptz_cam_base_right_geom">
- <xyz> 0.00 0.00 0.00</xyz>
- <size>0.05 0.02 0.02</size>
- <mass>0.1</mass>
- <!--color> 0.0 1.0 0.0</color-->
- <visual>
- <size>0.05 0.02 0.02</size>
- <rpy>0.0 0.0 0.0 </rpy>
- <mesh>unit_box</mesh>
- <material>Gazebo/Shell</material>
- </visual>
- </geom:box>
- </body:box>
-
- <!-- attach neck_body to ptz cameras -->
- <joint:hinge name="ptz_cam_left_yaw_joint">
- <body2>ptz_cam_left_body</body2>
- <body1>ptz_cam_base_left_body</body1>
- <anchor>ptz_cam_left_body</anchor>
- <axis> 0.0 0.0 1.0 </axis>
- </joint:hinge>
- <joint:hinge name="ptz_cam_left_pitch_joint">
- <body2>ptz_cam_base_left_body</body2>
- <body1>neck_body</body1>
- <anchor>ptz_cam_base_left_body</anchor>
- <axis> 0.0 1.0 0.0 </axis>
- </joint:hinge>
- <joint:hinge name="ptz_cam_right_yaw_joint">
- <body2>ptz_cam_right_body</body2>
- <body1>ptz_cam_base_right_body</body1>
- <anchor>ptz_cam_right_body</anchor>
- <axis> 0.0 0.0 1.0 </axis>
- </joint:hinge>
- <joint:hinge name="ptz_cam_right_pitch_joint">
- <body2>ptz_cam_base_right_body</body2>
- <body1>neck_body</body1>
- <anchor>ptz_cam_base_right_body</anchor>
- <axis> 0.0 1.0 0.0 </axis>
- </joint:hinge>
-
-
- <!-- stereo camera -->
- <body:empty name="stereo_camera_body">
- <xyz> 0.10 0.0 1.25 </xyz>
- <rpy> 0.0 0.0 0.0 </rpy>
- <sensor:stereocamera name="stereo_camera_sensor">
- <imageSize>640 480</imageSize>
- <hfov>60</hfov>
- <nearClip>0.1</nearClip>
- <farClip>100</farClip>
- <saveFrames>false</saveFrames>
- <saveFramePath>frames</saveFramePath>
- <baseline>0.2</baseline>
- <updateRate>15.0</updateRate>
- <controller:stereocamera name="stereo_camera_controller">
- <updateRate>15.0</updateRate>
- <interface:stereocamera name="stereo_iface_0" />
- <interface:camera name="camera_iface_0" />
- <interface:camera name="camera_iface_1" />
- <leftcamera>camera_iface_0</leftcamera>
- <rightcamera>camera_iface_1</rightcamera>
- </controller:stereocamera>
- </sensor:stereocamera>
- <geom:box name="stereo_camera_geom">
- <xyz> 0.00 0.00 0.00</xyz>
- <size>0.10 0.15 0.10</size>
- <mass>0.1</mass>
- <visual>
- <size>0.10 0.15 0.10</size>
- <rpy>0.0 0.0 0.0 </rpy>
- <mesh>unit_box</mesh>
- <material>Gazebo/PioneerBody</material>
- </visual>
- </geom:box>
- </body:empty>
-
- <!-- attach stereo_camera to head_tilt -->
- <joint:hinge name="stereo_camera_attach_joint">
- <body2>head_tilt_body</body2>
- <body1>stereo_camera_body</body1>
- <anchor>head_tilt_body</anchor>
- <axis> 1.0 0.0 0.0 </axis>
- <lowStop> 0.0 </lowStop>
- <highStop> 0.0 </highStop>
- </joint:hinge>
-
- <!-- Hokuyo laser body -->
- <body:box name="tilt_laser_body">
- <xyz>0.23 0.0 1.0</xyz>
- <rpy>0.0 0.0 0.0</rpy>
-
- <geom:box name="tilt_laser_box">
- <xyz>0.0 0.0 0.02</xyz>
- <rpy>0 0 0</rpy>
- <size>0.05 0.05 0.041</size>
- <mass>0.12</mass>
-
- <visual>
- <scale>0.05 0.05 0.041</scale>
- <mesh>unit_box</mesh>
- <material>Gazebo/Blue</material>
- </visual>
-
- </geom:box>
- <geom:cylinder name="tilt_laser_cylinder1">
- <xyz>0.0 0.0 0.041</xyz>
- <rpy>0 0 0</rpy>
- <size>0.02 0.013</size>
- <mass>0.02</mass>
-
- <visual>
- <rpy>0 0 0</rpy>
- <scale>0.04 0.04 0.013</scale>
- <mesh>unit_cylinder</mesh>
- <material>Gazebo/Black</material>
- </visual>
-
- </geom:cylinder>
-
- <geom:cylinder name="tilt_laser_cylinder2">
- <xyz>0.0 0.0 0.054</xyz>
- <rpy>0 0 0</rpy>
- <size>0.018 0.009</size>
- <mass>0.02</mass>
-
- <visual>
- <rpy>0 0 0</rpy>
- <size>0.036 0.036 0.009</size>
- <mesh>unit_cylinder</mesh>
- <material>Gazebo/Black</material>
- </visual>
-
- </geom:cylinder>
-
- <geom:cylinder name="tilt_laser_cylinder3">
- <xyz>0.0 0.0 0.063</xyz>
- <rpy>0 0 0</rpy>
- <size>0.0175 0.008</size>
- <mass>0.02</mass>
-
- <visual>
- <rpy>0 0 0</rpy>
- <size>0.035 0.035 0.008</size>
- <mesh>unit_cylinder</mesh>
- <material>Gazebo/Shell</material>
- </visual>
-
- </geom:cylinder>
-
-
- <sensor:ray name="tilt_laser_1">
- <rayCount>68</rayCount>
- <rangeCount>683</rangeCount>
- <laserCount>1</laserCount>
- <origin>0.0 0.0 0.05</origin>
-
- <minAngle>-45</minAngle>
- <maxAngle>45</maxAngle>
-
- <minRange>0.05</minRange>
- <maxRange>10.0</maxRange>
- <updateRate>10</updateRate>
- <controller:sicklms200_laser name="tilt_laser_controller_1">
- <interface:laser name="tilt_laser_iface_1"/>
- <updateRate>10</updateRate>
- </controller:sicklms200_laser>
- </sensor:ray>
- <!--
- -->
- <!--
- <sensor:ray2 name="tilt_laser_1">
- <rayCount>683</rayCount>
- <rangeCount>683</rangeCount>
- <laserCount>1</laserCount>
- <origin>0.0 0.0 0.05</origin>
-
- <minAngle>-135</minAngle>
- <maxAngle>135</maxAngle>
-
- <minRange>0.05</minRange>
- <maxRange>10.0</maxRange>
- <controller:sick2lms200_laser name="tilt_laser_controller_1">
- <interface:laser name="tilt_laser_iface_1"/>
- <updateRate>10</updateRate>
- </controller:sick2lms200_laser>
- </sensor:ray2>
- -->
-
- </body:box>
-
- <!-- attach hokuyo to torso -->
- <joint:hinge name="hokuyo_pitch_joint">
- <body1>neck_body</body1>
- <body2>tilt_laser_body</body2>
- <anchor>tilt_laser_body</anchor>
- <axis> 0.0 1.0 0.0 </axis>
- </joint:hinge>
-
- <!--=========================== caster ===========================-->
- <!--=========================== caster body ===========================-->
- <body:box name="front_left_caster_body">
- <xyz>0.425 0.25 0.16069 </xyz> <!-- caster height + height off ground of base bottom -->
- <rpy> 0.0 0.0 0.0 </rpy>
-
- <!-- report when this body collides with static bodies -->
- <reportStaticCollision>true</reportStaticCollision>
-
- <geom:box name="front_left_caster_geom">
-
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass>3.473082</mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.012411765597 </ixx>
- <ixy> -0.000711733678 </ixy>
- <ixz> 0.00050272983 </ixz>
- <iyy> 0.015218160428 </iyy>
- <iyz> -0.000004273467 </iyz>
- <izz> 0.011763977943 </izz>
- <cx> 0.007342 </cx>
- <cy> 0.00015 </cy>
- <cz> 0.095236 </cz>
-
- <kp>10000000.0</kp>
- <kd>1.0</kd>
- <xyz> 0.0 0.0 -0.08</xyz>
- <size>0.1 0.08 0.1</size> <!-- dx, dy, dz -->
- <visual>
- <xyz> 0.0 0.0 0.0 </xyz>
- <rpy> 90.0 0.0 90.0 </rpy>
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_caster.mesh</mesh>
- <material>Gazebo/PioneerBody</material>
- </visual>
- </geom:box>
- </body:box>
-
- <body:box name="front_right_caster_body">
- <xyz> 0.425 -0.25 0.16069</xyz>
- <rpy> 0.0 0.0 0.0</rpy>
-
- <!-- report when this body collides with static bodies -->
- <reportStaticCollision>true</reportStaticCollision>
-
- <geom:box name="front_right_caster_geom">
-
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass>3.473082</mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.012411765597 </ixx>
- <ixy> -0.000711733678 </ixy>
- <ixz> 0.00050272983 </ixz>
- <iyy> 0.015218160428 </iyy>
- <iyz> -0.000004273467 </iyz>
- <izz> 0.011763977943 </izz>
- <cx> 0.007342 </cx>
- <cy> 0.00015 </cy>
- <cz> 0.095236 </cz>
-
- <kp>10000000.0</kp>
- <kd>1.0</kd>
- <xyz>0 0 -0.08</xyz>
- <size>0.1 0.08 0.1</size> <!-- dx, dy, dz -->
- <visual>
- <xyz> 0.0 0.0 0.0 </xyz>
- <rpy> 90.0 0.0 90.0 </rpy>
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_caster.mesh</mesh>
- <material>Gazebo/PioneerBody</material>
- </visual>
- </geom:box>
- </body:box>
-
- <body:box name="rear_left_caster_body">
- <xyz> -0.075 0.25 0.16069</xyz>
- <rpy> 0.0 0.0 0.0</rpy>
-
- <!-- report when this body collides with static bodies -->
- <reportStaticCollision>true</reportStaticCollision>
-
- <geom:box name="rear_left_caster_geom">
-
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass>3.473082</mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.012411765597 </ixx>
- <ixy> -0.000711733678 </ixy>
- <ixz> 0.00050272983 </ixz>
- <iyy> 0.015218160428 </iyy>
- <iyz> -0.000004273467 </iyz>
- <izz> 0.011763977943 </izz>
- <cx> 0.007342 </cx>
- <cy> 0.00015 </cy>
- <cz> 0.095236 </cz>
-
- <kp>10000000.0</kp>
- <kd>1.0</kd>
- <xyz>0 0 -0.08</xyz>
- <size>0.1 0.08 0.1</size> <!-- dx, dy, dz -->
- <visual>
- <xyz> 0.0 0.0 0.0 </xyz>
- <rpy> 90.0 0.0 90.0 </rpy>
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_caster.mesh</mesh>
- <material>Gazebo/PioneerBody</material>
- </visual>
- </geom:box>
- </body:box>
-
- <body:box name="rear_right_caster_body">
- <xyz>-0.075 -0.25 0.16069</xyz>
- <rpy> 0.0 0.0 0.0</rpy>
- <!-- report when this body collides with static bodies -->
- <reportStaticCollision>true</reportStaticCollision>
-
- <geom:box name="rear_right_caster_geom">
-
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass>3.473082</mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.012411765597 </ixx>
- <ixy> -0.000711733678 </ixy>
- <ixz> 0.00050272983 </ixz>
- <iyy> 0.015218160428 </iyy>
- <iyz> -0.000004273467 </iyz>
- <izz> 0.011763977943 </izz>
- <cx> 0.007342 </cx>
- <cy> 0.00015 </cy>
- <cz> 0.095236 </cz>
-
- <kp>10000000.0</kp>
- <kd>1.0</kd>
- <xyz>0 0 -0.08</xyz>
- <size>0.1 0.08 0.1</size> <!-- dx, dy, dz -->
- <visual>
- <xyz> 0.0 0.0 0.0 </xyz>
- <rpy> 90.0 0.0 90.0 </rpy>
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_caster.mesh</mesh>
- <material>Gazebo/PioneerBody</material>
- </visual>
- </geom:box>
- </body:box>
-
-
- <!--=========================== wheels ===========================-->
- <body:cylinder name="front_left_wheel_l">
- <xyz> 0.425 0.305 0.08</xyz> <!-- basically wheel radius height -->
- <rpy> 90.0 0.0 0.0 </rpy>
- <geom:cylinder name="front_left_wheel_l_geom">
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass> 0.44036 </mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.012411765597 </ixx>
- <ixy> -0.000711733678 </ixy>
- <ixz> 0.00050272983 </ixz>
- <iyy> 0.015218160428 </iyy>
- <iyz> -0.000004273467 </iyz>
- <izz> 0.011763977943 </izz>
- <cx> 0.000008 </cx>
- <cy> 0.000008 </cy>
- <cz> 0.008475 </cz>
-
- <kp>1000000000.0</kp>
- <kd>1.0</kd>
- <mu1>5.0</mu1>
- <mu2>5.0</mu2>
- <size> 0.08 0.03</size> <!-- radius and width -->
- <visual>
- <xyz> 0.0 0.0 0.0 </xyz>
- <rpy> 0.0 0.0 0.0 </rpy>
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_wheel.mesh</mesh>
- <material>Gazebo/Black</material>
- </visual>
- </geom:cylinder>
- </body:cylinder>
-
- <body:cylinder name="front_left_wheel_r">
- <xyz> 0.425 0.195 0.08</xyz>
- <rpy> 90.0 0.0 180.0 </rpy>
- <geom:cylinder name="front_left_wheel_r_geom">
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass> 0.44036 </mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.012411765597 </ixx>
- <ixy> -0.000711733678 </ixy>
- <ixz> 0.00050272983 </ixz>
- <iyy> 0.015218160428 </iyy>
- <iyz> -0.000004273467 </iyz>
- <izz> 0.011763977943 </izz>
- <cx> 0.000008 </cx>
- <cy> 0.000008 </cy>
- <cz> 0.008475 </cz>
-
- <kp>1000000000.0</kp>
- <kd>1.0</kd>
- <mu1>5.0</mu1>
- <mu2>5.0</mu2>
- <size> 0.08 0.03</size> <!-- radius and width -->
- <visual>
- <xyz> 0.0 0.0 0.0 </xyz>
- <rpy> 0.0 0.0 0.0 </rpy>
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_wheel.mesh</mesh>
- <material>Gazebo/Black</material>
- </visual>
- </geom:cylinder>
- </body:cylinder>
-
- <body:cylinder name="front_right_wheel_l">
- <xyz> 0.425 -0.195 0.08</xyz>
- <rpy> 90.0 0.0 0.0 </rpy>
- <geom:cylinder name="front_right_wheel_l_geom">
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass> 0.44036 </mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.012411765597 </ixx>
- <ixy> -0.000711733678 </ixy>
- <ixz> 0.00050272983 </ixz>
- <iyy> 0.015218160428 </iyy>
- <iyz> -0.000004273467 </iyz>
- <izz> 0.011763977943 </izz>
- <cx> 0.000008 </cx>
- <cy> 0.000008 </cy>
- <cz> 0.008475 </cz>
-
- <kp>1000000000.0</kp>
- <kd>1.0</kd>
- <mu1>5.0</mu1>
- <mu2>5.0</mu2>
- <size> 0.08 0.03</size> <!-- radius and width -->
- <visual>
- <xyz> 0.0 0.0 0.0 </xyz>
- <rpy> 0.0 0.0 0.0 </rpy>
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_wheel.mesh</mesh>
- <material>Gazebo/Black</material>
- </visual>
- </geom:cylinder>
- </body:cylinder>
-
- <body:cylinder name="front_right_wheel_r">
- <xyz> 0.425 -0.305 0.08</xyz>
- <rpy> 90.0 0.0 180.0 </rpy>
- <geom:cylinder name="front_right_wheel_r_geom">
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass> 0.44036 </mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.012411765597 </ixx>
- <ixy> -0.000711733678 </ixy>
- <ixz> 0.00050272983 </ixz>
- <iyy> 0.015218160428 </iyy>
- <iyz> -0.000004273467 </iyz>
- <izz> 0.011763977943 </izz>
- <cx> 0.000008 </cx>
- <cy> 0.000008 </cy>
- <cz> 0.008475 </cz>
-
- <kp>1000000000.0</kp>
- <kd>1.0</kd>
- <mu1>5.0</mu1>
- <mu2>5.0</mu2>
- <size> 0.08 0.03</size> <!-- radius and width -->
- <visual>
- <xyz> 0.0 0.0 0.0 </xyz>
- <rpy> 0.0 0.0 0.0 </rpy>
- <scale>0.001 0.001 0.001</scale>
- <mesh>pr2/pr2_wheel.mesh</mesh>
- <material>Gazebo/Black</material>
- </visual>
- </geom:cylinder>
- </body:cylinder>
-
- <body:cylinder name="rear_left_wheel_l">
- <xyz> -0.075 0.305 0.08</xyz>
- <rpy> 90.0 0.0 0.0 </rpy>
- <geom:cylinder name="rear_left_wheel_l_geom">
- <massMatrix>true</massMatrix> <!-- user provide full mass and inertia matrix -->
- <mass> 0.44036 </mass> <!-- who would have thought we have 6 digits of precision!? -->
- <ixx> 0.012411765597 </ixx>
- <ixy> -0.000711733678 </ixy>
- <ixz> 0.00050272983 </ixz>
- <iyy> 0.015218160428 </iyy>
- <iyz> -0.000004273467 </iyz>
- <izz> 0.011763977943 </izz>
- <cx> 0.000008 </cx>
- <cy> 0.000008 </cy>
- <cz> 0.008475 </cz>
-
- <kp>1000000000.0</kp>
- <kd>1.0</kd>
- <mu1>5.0</mu1>
- <mu2>5.0</mu2>
- <size> 0.08 0.03</size> <!-- radius and width -->
- <visual>
- <xyz> 0.0 0.0 0.0 </x...
[truncated message content] |