|
From: <hsu...@us...> - 2009-07-10 17:23:15
|
Revision: 18622
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18622&view=rev
Author: hsujohnhsu
Date: 2009-07-10 17:23:09 +0000 (Fri, 10 Jul 2009)
Log Message:
-----------
fix mesh file path names in urdf.
Modified Paths:
--------------
pkg/trunk/drivers/simulator/gazebo_plugin/src/urdf2gazebo.cpp
pkg/trunk/stacks/pr2/pr2_defs/defs/arm_defs.xml
pkg/trunk/stacks/pr2/pr2_defs/defs/arm_grav_defs.xml
pkg/trunk/stacks/pr2/pr2_defs/defs/base_defs.xml
pkg/trunk/stacks/pr2/pr2_defs/defs/body_defs.xml
pkg/trunk/stacks/pr2/pr2_defs/defs/gripper_defs.xml
pkg/trunk/stacks/pr2/pr2_defs/defs/head_defs.xml
pkg/trunk/stacks/pr2/pr2_defs/defs/ptz_defs.xml
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/urdf2gazebo.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/urdf2gazebo.cpp 2009-07-10 17:15:57 UTC (rev 18621)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/urdf2gazebo.cpp 2009-07-10 17:23:09 UTC (rev 18622)
@@ -250,7 +250,7 @@
int pos1 = mesh->filename.find(tmp_extension,0);
mesh->filename.replace(pos1,mesh->filename.size()-pos1+1,std::string(""));
// add mesh filename
- addKeyValue(geom, "mesh", "models/pr2/" + mesh->filename + ".mesh");
+ addKeyValue(geom, "mesh", mesh->filename + ".mesh");
}
else
@@ -294,7 +294,7 @@
if (mesh->filename.empty())
addKeyValue(visual, "mesh", "unit_" + type);
else
- addKeyValue(visual, "mesh", "models/pr2/" + mesh->filename + ".mesh");
+ addKeyValue(visual, "mesh", mesh->filename + ".mesh");
}
else
Modified: pkg/trunk/stacks/pr2/pr2_defs/defs/arm_defs.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_defs/defs/arm_defs.xml 2009-07-10 17:15:57 UTC (rev 18621)
+++ pkg/trunk/stacks/pr2/pr2_defs/defs/arm_defs.xml 2009-07-10 17:23:09 UTC (rev 18622)
@@ -67,13 +67,13 @@
<elem key="material" value="PR2/Blue" />
</map>
<geometry name="${side}_shoulder_pan_visual">
- <mesh filename="shoulder_yaw" />
+ <mesh filename="pr2/shoulder_yaw" />
</geometry>
</visual>
<collision>
<origin xyz="0.0 0 0.0" rpy="0 0 0" />
<geometry name="${side}_shoulder_pan_collision">
- <mesh filename="convex/shoulder_yaw_convex.stlb" />
+ <mesh filename="pr2/convex/shoulder_yaw_convex.stlb" />
</geometry>
</collision>
<map name="${side}_shoulder_pan_sensor" flag="gazebo">
@@ -137,13 +137,13 @@
<elem key="material" value="PR2/Grey" />
</map>
<geometry name="${side}_shoulder_lift_visual">
- <mesh filename="shoulder_lift" />
+ <mesh filename="pr2/shoulder_lift" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${side}_shoulder_lift_collision">
- <mesh filename="convex/shoulder_lift_convex.stlb" />
+ <mesh filename="pr2/convex/shoulder_lift_convex.stlb" />
</geometry>
</collision>
<map name="${side}_shoulder_lift_sensor" flag="gazebo">
@@ -208,7 +208,7 @@
<elem key="material" value="PR2/RollLinks" />
</map>
<geometry name="${side}_upper_arm_roll_visual">
- <mesh filename="upper_arm_roll" />
+ <mesh filename="pr2/upper_arm_roll" />
</geometry>
</visual>
<collision> <!-- TODO: collision tag should be optional -->
@@ -262,14 +262,14 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${side}_upper_arm_visual">
- <mesh filename="upper_arm" />
+ <mesh filename="pr2/upper_arm" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${side}_upper_arm_collision">
- <mesh filename="convex/upper_arm_convex.stlb" />
+ <mesh filename="pr2/convex/upper_arm_convex.stlb" />
</geometry>
</collision>
@@ -329,13 +329,13 @@
<elem key="material" value="PR2/Grey" />
</map>
<geometry name="${side}_elbow_flex_visual">
- <mesh filename="elbow_flex" />
+ <mesh filename="pr2/elbow_flex" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${side}_elbow_flex_collision">
- <mesh filename="convex/elbow_flex_convex.stlb" />
+ <mesh filename="pr2/convex/elbow_flex_convex.stlb" />
</geometry>
</collision>
<map name="${side}_elbow_flex_sensor" flag="gazebo">
@@ -439,7 +439,7 @@
<elem key="material" value="PR2/RollLinks" />
</map>
<geometry name="${side}_forearm_roll_visual">
- <mesh filename="forearm_roll" />
+ <mesh filename="pr2/forearm_roll" />
</geometry>
</visual>
<collision> <!-- TODO: collision tag should be optional -->
@@ -484,13 +484,13 @@
<elem key="material" value="PR2/Blue" />
</map>
<geometry name="${side}_forearm_visual">
- <mesh filename="forearm" />
+ <mesh filename="pr2/forearm" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${side}_forearm_collision">
- <mesh filename="convex/forearm_convex.stlb" />
+ <mesh filename="pr2/convex/forearm_convex.stlb" />
</geometry>
</collision>
<map name="${side}_forearm_sensor" flag="gazebo">
@@ -547,13 +547,13 @@
<elem key="material" value="PR2/Grey" />
</map>
<geometry name="${side}_wrist_flex_visual">
- <mesh filename="wrist_flex" />
+ <mesh filename="pr2/wrist_flex" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${side}_wrist_flex_collision">
- <mesh filename="convex/wrist_flex_convex.stlb" />
+ <mesh filename="pr2/convex/wrist_flex_convex.stlb" />
</geometry>
</collision>
<map name="${side}_wrist_flex_sensor" flag="gazebo">
@@ -607,7 +607,7 @@
<elem key="material" value="PR2/RollLinks" />
</map>
<geometry name="${side}_wrist_roll_visual">
- <mesh filename="wrist_roll" />
+ <mesh filename="pr2/wrist_roll" />
</geometry>
</visual>
<collision>
Modified: pkg/trunk/stacks/pr2/pr2_defs/defs/arm_grav_defs.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_defs/defs/arm_grav_defs.xml 2009-07-10 17:15:57 UTC (rev 18621)
+++ pkg/trunk/stacks/pr2/pr2_defs/defs/arm_grav_defs.xml 2009-07-10 17:23:09 UTC (rev 18622)
@@ -49,7 +49,7 @@
<elem key="material">PR2/Blue</elem>
</map>
<geometry name="${side}_shoulder_pan_visual">
- <mesh filename="shoulder_yaw" />
+ <mesh filename="pr2/shoulder_yaw" />
</geometry>
</visual>
<collision>
@@ -113,7 +113,7 @@
<elem key="material">PR2/Grey</elem>
</map>
<geometry name="${side}_shoulder_lift_visual">
- <mesh filename="shoulder_lift" />
+ <mesh filename="pr2/shoulder_lift" />
</geometry>
</visual>
<collision>
@@ -180,7 +180,7 @@
<elem key="material">PR2/Green</elem>
</map>
<geometry name="${side}_upper_arm_roll_visual">
- <mesh filename="upper_arm" />
+ <mesh filename="pr2/upper_arm" />
</geometry>
</visual>
@@ -248,7 +248,7 @@
<elem key="material">PR2/Grey</elem>
</map>
<geometry name="${side}_elbow_flex_visual">
- <mesh filename="elbow_flex" />
+ <mesh filename="pr2/elbow_flex" />
</geometry>
</visual>
<collision>
@@ -361,7 +361,7 @@
<elem key="material">PR2/Blue</elem>
</map>
<geometry name="${side}_forearm_roll_visual">
- <mesh filename="forearm" />
+ <mesh filename="pr2/forearm" />
</geometry>
</visual>
<collision>
@@ -426,7 +426,7 @@
<elem key="material">PR2/Grey</elem>
</map>
<geometry name="${side}_wrist_flex_visual">
- <mesh filename="wrist_flex" />
+ <mesh filename="pr2/wrist_flex" />
</geometry>
</visual>
<collision>
@@ -482,7 +482,7 @@
<elem key="material">PR2/Red</elem>
</map>
<geometry name="${side}_wrist_roll_visual">
- <mesh filename="wrist_roll" />
+ <mesh filename="pr2/wrist_roll" />
</geometry>
</visual>
<collision>
Modified: pkg/trunk/stacks/pr2/pr2_defs/defs/base_defs.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_defs/defs/base_defs.xml 2009-07-10 17:15:57 UTC (rev 18621)
+++ pkg/trunk/stacks/pr2/pr2_defs/defs/base_defs.xml 2009-07-10 17:23:09 UTC (rev 18622)
@@ -36,7 +36,7 @@
<elem key="material" value="PR2/${parent}_${suffix}_wheel_link" />
</map>
<geometry name="${parent}_${suffix}_wheel_visual">
- <mesh filename="wheel" />
+ <mesh filename="pr2/wheel" />
</geometry>
</visual>
@@ -102,7 +102,7 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${suffix}_caster_rotation_visual">
- <mesh filename="caster" scale="1 1 1"/>
+ <mesh filename="pr2/caster" scale="1 1 1"/>
</geometry>
</visual>
@@ -153,7 +153,7 @@
<elem key="material" value="PR2/${parent}_${suffix}_wheel_link" />
</map>
<geometry name="${parent}_${suffix}_wheel_visual">
- <mesh filename="wheel" />
+ <mesh filename="pr2/wheel" />
</geometry>
</visual>
@@ -219,7 +219,7 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${suffix}_caster_rotation_visual">
- <mesh filename="caster" scale="1 1 1"/>
+ <mesh filename="pr2/caster" scale="1 1 1"/>
</geometry>
</visual>
@@ -265,7 +265,7 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${name}_visual">
- <mesh filename="base" />
+ <mesh filename="pr2/base" />
</geometry>
</visual>
@@ -417,7 +417,7 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${name}_visual">
- <mesh filename="base" />
+ <mesh filename="pr2/base" />
</geometry>
</visual>
Modified: pkg/trunk/stacks/pr2/pr2_defs/defs/body_defs.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_defs/defs/body_defs.xml 2009-07-10 17:15:57 UTC (rev 18621)
+++ pkg/trunk/stacks/pr2/pr2_defs/defs/body_defs.xml 2009-07-10 17:23:09 UTC (rev 18622)
@@ -41,7 +41,7 @@
<elem key="material" value="PR2/Grey2" />
</map>
<geometry name="${name}_visual">
- <mesh filename="torso" />
+ <mesh filename="pr2/torso" />
</geometry>
</visual>
Modified: pkg/trunk/stacks/pr2/pr2_defs/defs/gripper_defs.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_defs/defs/gripper_defs.xml 2009-07-10 17:15:57 UTC (rev 18621)
+++ pkg/trunk/stacks/pr2/pr2_defs/defs/gripper_defs.xml 2009-07-10 17:23:09 UTC (rev 18622)
@@ -79,13 +79,13 @@
<elem key="material" value="PR2/Grey" />
</map>
<geometry name="${prefix}_l_finger_visual">
- <mesh filename="upper_finger_l" />
+ <mesh filename="pr2/upper_finger_l" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${prefix}_l_finger_collision">
- <mesh filename="convex/upper_finger_l_convex.stlb" />
+ <mesh filename="pr2/convex/upper_finger_l_convex.stlb" />
</geometry>
<verbose value="Yes" />
<map flag="collision" name="mesh">
@@ -163,13 +163,13 @@
<elem key="material" value="PR2/Grey" />
</map>
<geometry name="${prefix}_r_finger_visual">
- <mesh filename="upper_finger_r" />
+ <mesh filename="pr2/upper_finger_r" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${prefix}_r_finger_collision">
- <mesh filename="convex/upper_finger_r_convex.stlb" />
+ <mesh filename="pr2/convex/upper_finger_r_convex.stlb" />
</geometry>
<verbose value="Yes" />
<map flag="collision" name="mesh">
@@ -244,13 +244,13 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${prefix}_l_finger_tip_visual">
- <mesh filename="finger_tip_l" />
+ <mesh filename="pr2/finger_tip_l" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${prefix}_l_finger_tip_collision">
- <mesh filename="convex/finger_tip_l_convex.stlb" />
+ <mesh filename="pr2/convex/finger_tip_l_convex.stlb" />
</geometry>
<verbose value="Yes" />
<map flag="collision" name="mesh">
@@ -326,13 +326,13 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${prefix}_r_finger_tip_visual">
- <mesh filename="finger_tip_r" />
+ <mesh filename="pr2/finger_tip_r" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${prefix}_r_finger_tip_collision">
- <mesh filename="convex/finger_tip_r_convex.stlb" />
+ <mesh filename="pr2/convex/finger_tip_r_convex.stlb" />
</geometry>
<verbose value="Yes" />
<map flag="collision" name="mesh">
@@ -476,13 +476,13 @@
<elem key="material" value="PR2/Red" />
</map>
<geometry name="${side}_gripper_palm_visual">
- <mesh filename="gripper_palm" />
+ <mesh filename="pr2/gripper_palm" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${side}_gripper_palm_collision">
- <mesh filename="convex/gripper_palm_convex.stlb" />
+ <mesh filename="pr2/convex/gripper_palm_convex.stlb" />
</geometry>
<verbose value="Yes" />
<map flag="collision" name="mesh">
@@ -701,13 +701,13 @@
<elem key="material" value="PR2/Red" />
</map>
<geometry name="${side}_gripper_palm_visual">
- <mesh filename="gripper_palm" />
+ <mesh filename="pr2/gripper_palm" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${side}_gripper_palm_collision">
- <mesh filename="convex/gripper_palm_convex.stlb" />
+ <mesh filename="pr2/convex/gripper_palm_convex.stlb" />
</geometry>
<verbose value="Yes" />
<map flag="collision" name="mesh">
Modified: pkg/trunk/stacks/pr2/pr2_defs/defs/head_defs.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_defs/defs/head_defs.xml 2009-07-10 17:15:57 UTC (rev 18621)
+++ pkg/trunk/stacks/pr2/pr2_defs/defs/head_defs.xml 2009-07-10 17:23:09 UTC (rev 18622)
@@ -36,7 +36,7 @@
<elem key="material" value="PR2/Red" />
</map>
<geometry name="${name}_mount_visual">
- <mesh filename="hok_tilt" />
+ <mesh filename="pr2/hok_tilt" />
</geometry>
</visual>
@@ -417,7 +417,7 @@
<elem key="material" value="PR2/Blue" />
</map>
<geometry name="${name}_visual">
- <mesh filename="head_pan" />
+ <mesh filename="pr2/head_pan" />
</geometry>
</visual>
@@ -467,7 +467,7 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${name}_visual">
- <mesh filename="head_tilt" />
+ <mesh filename="pr2/head_tilt" />
</geometry>
</visual>
@@ -559,7 +559,7 @@
<elem key="material" value="PR2/Red" />
</map>
<geometry name="${name}_mount_visual">
- <mesh filename="hok_tilt" />
+ <mesh filename="pr2/hok_tilt" />
</geometry>
</visual>
@@ -677,7 +677,7 @@
<elem key="material" value="PR2/Blue" />
</map>
<geometry name="${name}_visual">
- <mesh filename="head_pan" />
+ <mesh filename="pr2/head_pan" />
</geometry>
</visual>
@@ -726,7 +726,7 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${name}_visual">
- <mesh filename="head_tilt" />
+ <mesh filename="pr2/head_tilt" />
</geometry>
</visual>
@@ -774,7 +774,7 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${name}_visual">
- <mesh filename="head_tilt" />
+ <mesh filename="pr2/head_tilt" />
</geometry>
</visual>
@@ -821,7 +821,7 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${name}_visual">
- <mesh filename="head_tilt" />
+ <mesh filename="pr2/head_tilt" />
</geometry>
</visual>
Modified: pkg/trunk/stacks/pr2/pr2_defs/defs/ptz_defs.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_defs/defs/ptz_defs.xml 2009-07-10 17:15:57 UTC (rev 18621)
+++ pkg/trunk/stacks/pr2/pr2_defs/defs/ptz_defs.xml 2009-07-10 17:23:09 UTC (rev 18622)
@@ -33,7 +33,7 @@
<elem key="material" value="PR2/Blue" />
</map>
<geometry name="${side}_ptz_pan_visual">
- <mesh filename="ptz_base_${side}" />
+ <mesh filename="pr2/ptz_base_${side}" />
</geometry>
</visual>
@@ -71,7 +71,7 @@
<elem key="material" value="PR2/Red" />
</map>
<geometry name="${side}_ptz_tilt_visual">
- <mesh filename="ptz_top_${side}" />
+ <mesh filename="pr2/ptz_top_${side}" />
</geometry>
</visual>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|