|
From: <hsu...@us...> - 2008-07-29 00:05:30
|
Revision: 2217
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=2217&view=rev
Author: hsujohnhsu
Date: 2008-07-29 00:05:38 +0000 (Tue, 29 Jul 2008)
Log Message:
-----------
name change for pr2 model.
Modified Paths:
--------------
pkg/trunk/drivers/robot/pr2/libpr2HW/src/pr2HW.cpp
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_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_trimesh.model
Modified: pkg/trunk/drivers/robot/pr2/libpr2HW/src/pr2HW.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/libpr2HW/src/pr2HW.cpp 2008-07-28 23:54:01 UTC (rev 2216)
+++ pkg/trunk/drivers/robot/pr2/libpr2HW/src/pr2HW.cpp 2008-07-29 00:05:38 UTC (rev 2217)
@@ -217,7 +217,7 @@
/// Open the laser interface for hokuyo
try
{
- pr2LaserIface->Open(client, "laser_iface_1");
+ pr2LaserIface->Open(client, "tilt_laser_iface_1");
}
catch (std::string e)
{
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2-test.model
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2-test.model 2008-07-28 23:54:01 UTC (rev 2216)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2-test.model 2008-07-29 00:05:38 UTC (rev 2217)
@@ -137,7 +137,7 @@
<!--
-->
<!--
- <sensor:ray2 name="laser_1">
+ <sensor:ray2 name="base_laser_1">
<rayCount>683</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
@@ -148,8 +148,8 @@
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
- <controller:sick2lms200_laser name="laser_controller_1">
- <interface:laser name="laser_iface_1"/>
+ <controller:sick2lms200_laser name="base_laser_controller_1">
+ <interface:laser name="base_laser_iface_1"/>
<updateRate>10</updateRate>
</controller:sick2lms200_laser>
</sensor:ray2>
@@ -157,7 +157,7 @@
</body:box>
<!-- attach hokuyo to torso -->
- <joint:hinge name="tiltlaser_torso_attach_joint">
+ <joint:hinge name="base_laser_torso_attach_joint">
<body1>base_body</body1>
<body2>base_laser_body</body2>
<anchor>base_laser_body</anchor>
@@ -1123,11 +1123,11 @@
</joint:hinge>
<!-- Hokuyo laser body -->
- <body:box name="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="laser_box">
+ <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>
@@ -1140,7 +1140,7 @@
</visual>
</geom:box>
- <geom:cylinder name="laser_cylinder1">
+ <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>
@@ -1155,7 +1155,7 @@
</geom:cylinder>
- <geom:cylinder name="laser_cylinder2">
+ <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>
@@ -1170,7 +1170,7 @@
</geom:cylinder>
- <geom:cylinder name="laser_cylinder3">
+ <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>
@@ -1186,7 +1186,7 @@
</geom:cylinder>
- <sensor:ray name="laser_1">
+ <sensor:ray name="tilt_laser_1">
<rayCount>68</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
@@ -1198,15 +1198,15 @@
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
<updateRate>10</updateRate>
- <controller:sicklms200_laser name="laser_controller_1">
- <interface:laser name="laser_iface_1"/>
+ <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="laser_1">
+ <sensor:ray2 name="tilt_laser_1">
<rayCount>683</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
@@ -1217,8 +1217,8 @@
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
- <controller:sick2lms200_laser name="laser_controller_1">
- <interface:laser name="laser_iface_1"/>
+ <controller:sick2lms200_laser name="tilt_laser_controller_1">
+ <interface:laser name="tilt_laser_iface_1"/>
<updateRate>10</updateRate>
</controller:sick2lms200_laser>
</sensor:ray2>
@@ -1229,8 +1229,8 @@
<!-- attach hokuyo to torso -->
<joint:hinge name="hokuyo_pitch_joint">
<body1>neck_body</body1>
- <body2>laser_body</body2>
- <anchor>laser_body</anchor>
+ <body2>tilt_laser_body</body2>
+ <anchor>tilt_laser_body</anchor>
<axis> 0.0 1.0 0.0 </axis>
</joint:hinge>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2.model
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2.model 2008-07-28 23:54:01 UTC (rev 2216)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2.model 2008-07-29 00:05:38 UTC (rev 2217)
@@ -137,7 +137,7 @@
<!--
-->
<!--
- <sensor:ray2 name="laser_1">
+ <sensor:ray2 name="base_laser_1">
<rayCount>683</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
@@ -148,8 +148,8 @@
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
- <controller:sick2lms200_laser name="laser_controller_1">
- <interface:laser name="laser_iface_1"/>
+ <controller:sick2lms200_laser name="base_laser_controller_1">
+ <interface:laser name="base_laser_iface_1"/>
<updateRate>10</updateRate>
</controller:sick2lms200_laser>
</sensor:ray2>
@@ -1227,12 +1227,12 @@
<highStop> 0.0 </highStop>
</joint:hinge>
- <!-- Hokuyo laser body -->
- <body:box name="laser_body">
+ <!-- Hokuyo tilting 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="laser_box">
+ <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>
@@ -1245,7 +1245,7 @@
</visual>
</geom:box>
- <geom:cylinder name="laser_cylinder1">
+ <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>
@@ -1260,7 +1260,7 @@
</geom:cylinder>
- <geom:cylinder name="laser_cylinder2">
+ <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>
@@ -1275,7 +1275,7 @@
</geom:cylinder>
- <geom:cylinder name="laser_cylinder3">
+ <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>
@@ -1291,8 +1291,8 @@
</geom:cylinder>
- <sensor:ray name="laser_1">
- <rayCount>68</rayCount>
+ <sensor:ray name="tilt_laser_1">
+ <rayCount>683</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
<origin>0.0 0.0 0.05</origin>
@@ -1303,15 +1303,15 @@
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
<updateRate>10</updateRate>
- <controller:sicklms200_laser name="laser_controller_1">
- <interface:laser name="laser_iface_1"/>
+ <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="laser_1">
+ <sensor:ray2 name="tilt_laser_1">
<rayCount>683</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
@@ -1322,8 +1322,8 @@
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
- <controller:sick2lms200_laser name="laser_controller_1">
- <interface:laser name="laser_iface_1"/>
+ <controller:sick2lms200_laser name="tilt_laser_controller_1">
+ <interface:laser name="tilt_laser_iface_1"/>
<updateRate>10</updateRate>
</controller:sick2lms200_laser>
</sensor:ray2>
@@ -1334,8 +1334,8 @@
<!-- attach hokuyo to torso -->
<joint:hinge name="hokuyo_pitch_joint">
<body1>neck_body</body1>
- <body2>laser_body</body2>
- <anchor>laser_body</anchor>
+ <body2>tilt_laser_body</body2>
+ <anchor>tilt_laser_body</anchor>
<axis> 0.0 1.0 0.0 </axis>
</joint:hinge>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_new_plugins.model
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_new_plugins.model 2008-07-28 23:54:01 UTC (rev 2216)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_new_plugins.model 2008-07-29 00:05:38 UTC (rev 2217)
@@ -1169,11 +1169,11 @@
</joint:hinge>
<!-- Hokuyo laser body -->
- <body:box name="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="laser_box">
+ <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>
@@ -1186,7 +1186,7 @@
</visual>
</geom:box>
- <geom:cylinder name="laser_cylinder1">
+ <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>
@@ -1201,7 +1201,7 @@
</geom:cylinder>
- <geom:cylinder name="laser_cylinder2">
+ <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>
@@ -1216,7 +1216,7 @@
</geom:cylinder>
- <geom:cylinder name="laser_cylinder3">
+ <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>
@@ -1232,7 +1232,7 @@
</geom:cylinder>
- <sensor:ray name="tilting_laser">
+ <sensor:ray name="tilt_laser">
<rayCount>68</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
@@ -1244,20 +1244,20 @@
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
<updateRate>10</updateRate>
- <controller:ros_laser name="ros_tilting_laser_controller" plugin="libRos_Laser.so">
+ <controller:ros_laser name="ros_tilt_laser_controller" plugin="libRos_Laser.so">
<updateRate>15.0</updateRate>
- <topicName>tilting_laser</topicName>
- <interface:laser name="ros_tilting_laser_iface" />
+ <topicName>tilt_laser</topicName>
+ <interface:laser name="ros_tilt_laser_iface" />
</controller:ros_laser>
- <controller:sicklms200_laser name="tilting_laser_controller">
- <interface:laser name="tiltiing_laser_iface"/>
+ <controller:sicklms200_laser name="tilt_laser_controller">
+ <interface:laser name="tilt_laser_iface"/>
<updateRate>10</updateRate>
</controller:sicklms200_laser>
</sensor:ray>
<!--
-->
<!--
- <sensor:ray2 name="tilting_laser">
+ <sensor:ray2 name="tilt_laser">
<rayCount>683</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
@@ -1268,7 +1268,7 @@
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
- <controller:sick2lms200_laser name="tilting_laser_controller">
+ <controller:sick2lms200_laser name="tilt_laser_controller">
<interface:laser name="tiltiing_laser_iface"/>
<updateRate>10</updateRate>
</controller:sick2lms200_laser>
@@ -1280,8 +1280,8 @@
<!-- attach hokuyo to torso -->
<joint:hinge name="hokuyo_pitch_joint">
<body1>neck_body</body1>
- <body2>laser_body</body2>
- <anchor>laser_body</anchor>
+ <body2>tilt_laser_body</body2>
+ <anchor>tilt_laser_body</anchor>
<axis> 0.0 1.0 0.0 </axis>
</joint:hinge>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_torque.model
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_torque.model 2008-07-28 23:54:01 UTC (rev 2216)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_torque.model 2008-07-29 00:05:38 UTC (rev 2217)
@@ -138,7 +138,7 @@
<!--
-->
<!--
- <sensor:ray2 name="laser_1">
+ <sensor:ray2 name="base_laser_1">
<rayCount>683</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
@@ -149,8 +149,8 @@
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
- <controller:sick2lms200_laser name="laser_controller_1">
- <interface:laser name="laser_iface_1"/>
+ <controller:sick2lms200_laser name="base_laser_controller_1">
+ <interface:laser name="base_laser_iface_1"/>
<updateRate>10</updateRate>
</controller:sick2lms200_laser>
</sensor:ray2>
@@ -159,7 +159,7 @@
</body:box>
<!-- attach hokuyo to torso -->
- <joint:hinge name="tiltlaser_torso_attach_joint">
+ <joint:hinge name="base_laser_torso_attach_joint">
<body1>base_body</body1>
<body2>base_laser_body</body2>
<anchor>base_laser_body</anchor>
@@ -1125,11 +1125,11 @@
</joint:hinge>
<!-- Hokuyo laser body -->
- <body:box name="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="laser_box">
+ <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>
@@ -1142,7 +1142,7 @@
</visual>
</geom:box>
- <geom:cylinder name="laser_cylinder1">
+ <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>
@@ -1157,7 +1157,7 @@
</geom:cylinder>
- <geom:cylinder name="laser_cylinder2">
+ <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>
@@ -1172,7 +1172,7 @@
</geom:cylinder>
- <geom:cylinder name="laser_cylinder3">
+ <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>
@@ -1188,7 +1188,7 @@
</geom:cylinder>
- <sensor:ray name="laser_1">
+ <sensor:ray name="tilt_laser_1">
<rayCount>68</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
@@ -1200,15 +1200,15 @@
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
<updateRate>10</updateRate>
- <controller:sicklms200_laser name="laser_controller_1">
- <interface:laser name="laser_iface_1"/>
+ <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="laser_1">
+ <sensor:ray2 name="tilt_laser_1">
<rayCount>683</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
@@ -1219,8 +1219,8 @@
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
- <controller:sick2lms200_laser name="laser_controller_1">
- <interface:laser name="laser_iface_1"/>
+ <controller:sick2lms200_laser name="tilt_laser_controller_1">
+ <interface:laser name="tilt_laser_iface_1"/>
<updateRate>10</updateRate>
</controller:sick2lms200_laser>
</sensor:ray2>
@@ -1231,8 +1231,8 @@
<!-- attach hokuyo to torso -->
<joint:hinge name="hokuyo_pitch_joint">
<body1>neck_body</body1>
- <body2>laser_body</body2>
- <anchor>laser_body</anchor>
+ <body2>tilt_laser_body</body2>
+ <anchor>tilt_laser_body</anchor>
<axis> 0.0 1.0 0.0 </axis>
</joint:hinge>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_torque_control.model
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_torque_control.model 2008-07-28 23:54:01 UTC (rev 2216)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_torque_control.model 2008-07-29 00:05:38 UTC (rev 2217)
@@ -138,7 +138,7 @@
<!--
-->
<!--
- <sensor:ray2 name="laser_1">
+ <sensor:ray2 name="base_laser_1">
<rayCount>683</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
@@ -149,8 +149,8 @@
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
- <controller:sick2lms200_laser name="laser_controller_1">
- <interface:laser name="laser_iface_1"/>
+ <controller:sick2lms200_laser name="base_laser_controller_1">
+ <interface:laser name="base_laser_iface_1"/>
<updateRate>10</updateRate>
</controller:sick2lms200_laser>
</sensor:ray2>
@@ -159,7 +159,7 @@
</body:box>
<!-- attach hokuyo to torso -->
- <joint:hinge name="tiltlaser_torso_attach_joint">
+ <joint:hinge name="base_laser_torso_attach_joint">
<body1>base_body</body1>
<body2>base_laser_body</body2>
<anchor>base_laser_body</anchor>
@@ -1124,11 +1124,11 @@
</joint:hinge>
<!-- Hokuyo laser body -->
- <body:box name="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="laser_box">
+ <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>
@@ -1141,7 +1141,7 @@
</visual>
</geom:box>
- <geom:cylinder name="laser_cylinder1">
+ <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>
@@ -1156,7 +1156,7 @@
</geom:cylinder>
- <geom:cylinder name="laser_cylinder2">
+ <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>
@@ -1171,7 +1171,7 @@
</geom:cylinder>
- <geom:cylinder name="laser_cylinder3">
+ <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>
@@ -1187,7 +1187,7 @@
</geom:cylinder>
- <sensor:ray name="laser_1">
+ <sensor:ray name="tilt_laser_1">
<rayCount>68</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
@@ -1199,15 +1199,15 @@
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
<updateRate>10</updateRate>
- <controller:sicklms200_laser name="laser_controller_1">
- <interface:laser name="laser_iface_1"/>
+ <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="laser_1">
+ <sensor:ray2 name="tilt_laser_1">
<rayCount>683</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
@@ -1218,8 +1218,8 @@
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
- <controller:sick2lms200_laser name="laser_controller_1">
- <interface:laser name="laser_iface_1"/>
+ <controller:sick2lms200_laser name="tilt_laser_controller_1">
+ <interface:laser name="tilt_laser_iface_1"/>
<updateRate>10</updateRate>
</controller:sick2lms200_laser>
</sensor:ray2>
@@ -1230,8 +1230,8 @@
<!-- attach hokuyo to torso -->
<joint:hinge name="hokuyo_pitch_joint">
<body1>neck_body</body1>
- <body2>laser_body</body2>
- <anchor>laser_body</anchor>
+ <body2>tilt_laser_body</body2>
+ <anchor>tilt_laser_body</anchor>
<axis> 0.0 1.0 0.0 </axis>
</joint:hinge>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_torque_position.model
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_torque_position.model 2008-07-28 23:54:01 UTC (rev 2216)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_torque_position.model 2008-07-29 00:05:38 UTC (rev 2217)
@@ -138,7 +138,7 @@
<!--
-->
<!--
- <sensor:ray2 name="laser_1">
+ <sensor:ray2 name="base_laser_1">
<rayCount>683</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
@@ -149,8 +149,8 @@
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
- <controller:sick2lms200_laser name="laser_controller_1">
- <interface:laser name="laser_iface_1"/>
+ <controller:sick2lms200_laser name="base_laser_controller_1">
+ <interface:laser name="base_laser_iface_1"/>
<updateRate>10</updateRate>
</controller:sick2lms200_laser>
</sensor:ray2>
@@ -159,7 +159,7 @@
</body:box>
<!-- attach hokuyo to torso -->
- <joint:hinge name="tiltlaser_torso_attach_joint">
+ <joint:hinge name="base_laser_torso_attach_joint">
<body1>base_body</body1>
<body2>base_laser_body</body2>
<anchor>base_laser_body</anchor>
@@ -1123,11 +1123,11 @@
</joint:hinge>
<!-- Hokuyo laser body -->
- <body:box name="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="laser_box">
+ <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>
@@ -1140,7 +1140,7 @@
</visual>
</geom:box>
- <geom:cylinder name="laser_cylinder1">
+ <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>
@@ -1155,7 +1155,7 @@
</geom:cylinder>
- <geom:cylinder name="laser_cylinder2">
+ <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>
@@ -1170,7 +1170,7 @@
</geom:cylinder>
- <geom:cylinder name="laser_cylinder3">
+ <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>
@@ -1186,7 +1186,7 @@
</geom:cylinder>
- <sensor:ray name="laser_1">
+ <sensor:ray name="tilt_laser_1">
<rayCount>68</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
@@ -1198,15 +1198,15 @@
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
<updateRate>10</updateRate>
- <controller:sicklms200_laser name="laser_controller_1">
- <interface:laser name="laser_iface_1"/>
+ <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="laser_1">
+ <sensor:ray2 name="tilt_laser_1">
<rayCount>683</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
@@ -1217,8 +1217,8 @@
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
- <controller:sick2lms200_laser name="laser_controller_1">
- <interface:laser name="laser_iface_1"/>
+ <controller:sick2lms200_laser name="tilt_laser_controller_1">
+ <interface:laser name="tilt_laser_iface_1"/>
<updateRate>10</updateRate>
</controller:sick2lms200_laser>
</sensor:ray2>
@@ -1229,8 +1229,8 @@
<!-- attach hokuyo to torso -->
<joint:hinge name="hokuyo_pitch_joint">
<body1>neck_body</body1>
- <body2>laser_body</body2>
- <anchor>laser_body</anchor>
+ <body2>tilt_laser_body</body2>
+ <anchor>tilt_laser_body</anchor>
<axis> 0.0 1.0 0.0 </axis>
</joint:hinge>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_trimesh.model
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_trimesh.model 2008-07-28 23:54:01 UTC (rev 2216)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/pr2_trimesh.model 2008-07-29 00:05:38 UTC (rev 2217)
@@ -134,7 +134,7 @@
<!--
-->
<!--
- <sensor:ray2 name="laser_1">
+ <sensor:ray2 name="base_laser_1">
<rayCount>683</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
@@ -145,8 +145,8 @@
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
- <controller:sick2lms200_laser name="laser_controller_1">
- <interface:laser name="laser_iface_1"/>
+ <controller:sick2lms200_laser name="base_laser_controller_1">
+ <interface:laser name="base_laser_iface_1"/>
<updateRate>10</updateRate>
</controller:sick2lms200_laser>
</sensor:ray2>
@@ -154,7 +154,7 @@
</body:box>
<!-- attach hokuyo to torso -->
- <joint:hinge name="tiltlaser_torso_attach_joint">
+ <joint:hinge name="base_laser_torso_attach_joint">
<body1>base_body</body1>
<body2>base_laser_body</body2>
<anchor>base_laser_body</anchor>
@@ -1123,11 +1123,11 @@
</joint:hinge>
<!-- Hokuyo laser body -->
- <body:box name="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="laser_box">
+ <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>
@@ -1140,7 +1140,7 @@
</visual>
</geom:box>
- <geom:cylinder name="laser_cylinder1">
+ <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>
@@ -1155,7 +1155,7 @@
</geom:cylinder>
- <geom:cylinder name="laser_cylinder2">
+ <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>
@@ -1170,7 +1170,7 @@
</geom:cylinder>
- <geom:cylinder name="laser_cylinder3">
+ <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>
@@ -1186,7 +1186,7 @@
</geom:cylinder>
- <sensor:ray name="laser_1">
+ <sensor:ray name="tilt_laser_1">
<rayCount>68</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
@@ -1198,15 +1198,15 @@
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
<updateRate>10</updateRate>
- <controller:sicklms200_laser name="laser_controller_1">
- <interface:laser name="laser_iface_1"/>
+ <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="laser_1">
+ <sensor:ray2 name="tilt_laser_1">
<rayCount>683</rayCount>
<rangeCount>683</rangeCount>
<laserCount>1</laserCount>
@@ -1217,8 +1217,8 @@
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
- <controller:sick2lms200_laser name="laser_controller_1">
- <interface:laser name="laser_iface_1"/>
+ <controller:sick2lms200_laser name="tilt_laser_controller_1">
+ <interface:laser name="tilt_laser_iface_1"/>
<updateRate>10</updateRate>
</controller:sick2lms200_laser>
</sensor:ray2>
@@ -1229,8 +1229,8 @@
<!-- attach hokuyo to torso -->
<joint:hinge name="hokuyo_pitch_joint">
<body1>neck_body</body1>
- <body2>laser_body</body2>
- <anchor>laser_body</anchor>
+ <body2>tilt_laser_body</body2>
+ <anchor>tilt_laser_body</anchor>
<axis> 0.0 1.0 0.0 </axis>
</joint:hinge>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|