|
From: <hsu...@us...> - 2009-07-15 21:59:44
|
Revision: 18892
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18892&view=rev
Author: hsujohnhsu
Date: 2009-07-15 21:59:38 +0000 (Wed, 15 Jul 2009)
Log Message:
-----------
*added extension to urdf mesh filename in robot visual tag; <mesh filename="*.stlb"/>
*added <map> for gazebo collision mesh
*update urdf2gazebo parser to deal with the changes
*update rviz urdf .mesh extraction to deal with the changes
Modified Paths:
--------------
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/urdf2gazebo.h
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/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
pkg/trunk/stacks/visualization/rviz/src/rviz/robot/robot_link.cpp
Removed Paths:
-------------
pkg/trunk/stacks/pr2/pr2_defs/defs/arm_grav_defs.xml
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/urdf2gazebo.h
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/urdf2gazebo.h 2009-07-15 21:42:11 UTC (rev 18891)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/urdf2gazebo.h 2009-07-15 21:59:38 UTC (rev 18892)
@@ -68,6 +68,8 @@
void copyGazeboMap(const robot_desc::URDF::Map& data, TiXmlElement *elem, const std::vector<std::string> *tags);
+ void copyOgreMap(const robot_desc::URDF::Map& data, TiXmlElement *elem, const std::vector<std::string> *tags);
+
std::string getGeometrySize(robot_desc::URDF::Link::Geometry* geometry, int *sizeCount, double *sizeVals);
void convertLink(TiXmlElement *root, robot_desc::URDF::Link *link, const btTransform &transform, bool enforce_limits);
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/urdf2gazebo.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/urdf2gazebo.cpp 2009-07-15 21:42:11 UTC (rev 18891)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/urdf2gazebo.cpp 2009-07-15 21:59:38 UTC (rev 18892)
@@ -118,6 +118,33 @@
}
}
+void URDF2Gazebo::copyOgreMap(const robot_desc::URDF::Map& data, TiXmlElement *elem, const std::vector<std::string> *tags = NULL)
+{
+ std::vector<std::string> ogre_names;
+ data.getMapTagNames("ogre", ogre_names);
+ for (unsigned int k = 0 ; k < ogre_names.size() ; ++k)
+ {
+ std::map<std::string, std::string> m = data.getMapTagValues("ogre", ogre_names[k]);
+ std::vector<std::string> accepted_tags;
+ if (tags)
+ accepted_tags = *tags;
+ else
+ for (std::map<std::string, std::string>::iterator it = m.begin() ; it != m.end() ; it++)
+ accepted_tags.push_back(it->first);
+
+ for (unsigned int i = 0 ; i < accepted_tags.size() ; ++i)
+ if (m.find(accepted_tags[i]) != m.end())
+ addKeyValue(elem, accepted_tags[i], m[accepted_tags[i]]);
+
+ std::map<std::string, const TiXmlElement*> x = data.getMapTagXML("ogre", ogre_names[k]);
+ for (std::map<std::string, const TiXmlElement*>::iterator it = x.begin() ; it != x.end() ; it++)
+ {
+ for (const TiXmlNode *child = it->second->FirstChild() ; child ; child = child->NextSibling())
+ elem->LinkEndChild(child->Clone());
+ }
+ }
+}
+
std::string URDF2Gazebo::getGeometrySize(robot_desc::URDF::Link::Geometry* geometry, int *sizeCount, double *sizeVals)
{
std::string type;
@@ -294,7 +321,15 @@
if (mesh->filename.empty())
addKeyValue(visual, "mesh", "unit_" + type);
else
- addKeyValue(visual, "mesh", mesh->filename + ".mesh");
+ {
+ // skipping this block as we test the copyOgreMap function
+ // // strip extension from filename
+ // std::string tmp_extension(".stl");
+ // int pos1 = mesh->filename.find(tmp_extension,0);
+ // mesh->filename.replace(pos1,mesh->filename.size()-pos1+1,std::string(""));
+ // // add mesh filename
+ // addKeyValue(visual, "mesh", mesh->filename + ".mesh");
+ }
}
else
@@ -307,6 +342,9 @@
}
copyGazeboMap(link->visual->data, visual);
+
+ // ogre mesh map for all trimeshes visualized
+ copyOgreMap(link->visual->data, visual);
}
/* end create visual node */
Modified: pkg/trunk/stacks/pr2/pr2_defs/defs/arm_defs.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_defs/defs/arm_defs.xml 2009-07-15 21:42:11 UTC (rev 18891)
+++ pkg/trunk/stacks/pr2/pr2_defs/defs/arm_defs.xml 2009-07-15 21:59:38 UTC (rev 18892)
@@ -67,14 +67,20 @@
<elem key="material" value="PR2/Blue" />
</map>
<geometry name="${side}_shoulder_pan_visual">
- <mesh filename="shoulder_yaw" />
+ <mesh filename="shoulder_yaw.stlb" />
</geometry>
+ <map name="${side}_shoulder_pan_visual_mesh" flag="ogre">
+ <elem key="mesh" value="shoulder_yaw.mesh" />
+ </map>
</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" />
</geometry>
+ <map name="${side}_shoulder_pan_collision_mesh" flag="ogre">
+ <elem key="mesh" value="convex/shoulder_yaw_convex.mesh" />
+ </map>
</collision>
<map name="${side}_shoulder_pan_sensor" flag="gazebo">
<verbatim key="${side}_shoulder_pan_bumper_sensor">
@@ -137,14 +143,20 @@
<elem key="material" value="PR2/Grey" />
</map>
<geometry name="${side}_shoulder_lift_visual">
- <mesh filename="shoulder_lift" />
+ <mesh filename="shoulder_lift.stlb" />
</geometry>
+ <map name="${side}_shoulder_lift_visual_mesh" flag="ogre">
+ <elem key="mesh" value="shoulder_lift.mesh" />
+ </map>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${side}_shoulder_lift_collision">
<mesh filename="convex/shoulder_lift_convex.stlb" />
</geometry>
+ <map name="${side}_shoulder_lift_collision_mesh" flag="ogre">
+ <elem key="mesh" value="convex/shoulder_lift_convex.mesh" />
+ </map>
</collision>
<map name="${side}_shoulder_lift_sensor" flag="gazebo">
<verbatim key="${side}_shoulder_lift_bumper_sensor">
@@ -171,7 +183,7 @@
<mechanicalReduction>${61.89/cal_r_shoulder_lift_gearing}</mechanicalReduction>
</transmission>
- <!-- Upperarm roll -->
+ <!-- Upperarm roll: internal fixed attchment point for upper arm -->
<joint name="${side}_upper_arm_roll_joint" type="revolute">
<axis xyz="1 0 0" />
@@ -208,8 +220,11 @@
<elem key="material" value="PR2/RollLinks" />
</map>
<geometry name="${side}_upper_arm_roll_visual">
- <mesh filename="upper_arm_roll" />
+ <mesh filename="upper_arm_roll.stlb" />
</geometry>
+ <map name="${side}_upper_arm_roll_visual_mesh" flag="ogre">
+ <elem key="mesh" value="upper_arm_roll.mesh" />
+ </map>
</visual>
<collision> <!-- TODO: collision tag should be optional -->
<origin xyz="0.0 0 0" rpy="0 0 0" />
@@ -262,8 +277,11 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${side}_upper_arm_visual">
- <mesh filename="upper_arm" />
+ <mesh filename="upper_arm.stlb" />
</geometry>
+ <map name="${side}_upper_arm_visual_mesh" flag="ogre">
+ <elem key="mesh" value="upper_arm.mesh" />
+ </map>
</visual>
<collision>
@@ -271,6 +289,9 @@
<geometry name="${side}_upper_arm_collision">
<mesh filename="convex/upper_arm_convex.stlb" />
</geometry>
+ <map name="${side}_upper_arm_collision_mesh" flag="ogre">
+ <elem key="mesh" value="convex/upper_arm_convex.mesh" />
+ </map>
</collision>
<map name="${side}_upper_arm_sensor" flag="gazebo">
@@ -329,14 +350,20 @@
<elem key="material" value="PR2/Grey" />
</map>
<geometry name="${side}_elbow_flex_visual">
- <mesh filename="elbow_flex" />
+ <mesh filename="elbow_flex.stlb" />
</geometry>
+ <map name="${side}_elbow_flex_visual_mesh" flag="ogre">
+ <elem key="mesh" value="elbow_flex.mesh" />
+ </map>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${side}_elbow_flex_collision">
<mesh filename="convex/elbow_flex_convex.stlb" />
</geometry>
+ <map name="${side}_elbow_flex_collision_mesh" flag="ogre">
+ <elem key="mesh" value="convex/elbow_flex_convex.mesh" />
+ </map>
</collision>
<map name="${side}_elbow_flex_sensor" flag="gazebo">
<verbatim key="${side}_elbow_flex_bumper_sensor">
@@ -439,8 +466,11 @@
<elem key="material" value="PR2/RollLinks" />
</map>
<geometry name="${side}_forearm_roll_visual">
- <mesh filename="forearm_roll" />
+ <mesh filename="forearm_roll.stlb" />
</geometry>
+ <map name="${side}_forearm_roll_visual_mesh" flag="ogre">
+ <elem key="mesh" value="forearm_roll.mesh" />
+ </map>
</visual>
<collision> <!-- TODO: collision tag should be optional -->
<origin xyz="0 0 0" rpy="0 0 0" />
@@ -484,14 +514,20 @@
<elem key="material" value="PR2/Blue" />
</map>
<geometry name="${side}_forearm_visual">
- <mesh filename="forearm" />
+ <mesh filename="forearm.stlb" />
</geometry>
+ <map name="${side}_forearm_visual_mesh" flag="ogre">
+ <elem key="mesh" value="forearm.mesh" />
+ </map>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${side}_forearm_collision">
<mesh filename="convex/forearm_convex.stlb" />
</geometry>
+ <map name="${side}_forearm_collision_mesh" flag="ogre">
+ <elem key="mesh" value="convex/forearm_convex.mesh" />
+ </map>
</collision>
<map name="${side}_forearm_sensor" flag="gazebo">
<verbatim key="${side}_forearm_bumper_sensor">
@@ -547,14 +583,20 @@
<elem key="material" value="PR2/Grey" />
</map>
<geometry name="${side}_wrist_flex_visual">
- <mesh filename="wrist_flex" />
+ <mesh filename="wrist_flex.stlb" />
</geometry>
+ <map name="${side}_wrist_flex_visual_mesh" flag="ogre">
+ <elem key="mesh" value="wrist_flex.mesh" />
+ </map>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${side}_wrist_flex_collision">
<mesh filename="convex/wrist_flex_convex.stlb" />
</geometry>
+ <map name="${side}_wrist_flex_collision_mesh" flag="ogre">
+ <elem key="mesh" value="convex/wrist_flex_convex.mesh" />
+ </map>
</collision>
<map name="${side}_wrist_flex_sensor" flag="gazebo">
<verbatim key="${side}_wrist_flex_bumper_sensor">
@@ -607,8 +649,11 @@
<elem key="material" value="PR2/RollLinks" />
</map>
<geometry name="${side}_wrist_roll_visual">
- <mesh filename="wrist_roll" />
+ <mesh filename="wrist_roll.stlb" />
</geometry>
+ <map name="${side}_wrist_roll_visual_mesh" flag="ogre">
+ <elem key="mesh" value="wrist_roll.mesh" />
+ </map>
</visual>
<collision>
<origin xyz="0.0 0 0" rpy="0 0 0" />
Deleted: pkg/trunk/stacks/pr2/pr2_defs/defs/arm_grav_defs.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_defs/defs/arm_grav_defs.xml 2009-07-15 21:42:11 UTC (rev 18891)
+++ pkg/trunk/stacks/pr2/pr2_defs/defs/arm_grav_defs.xml 2009-07-15 21:59:38 UTC (rev 18892)
@@ -1,630 +0,0 @@
-<?xml version="1.0"?>
-<robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
- xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
- xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface">
-
- <property name="M_PI" value="3.1415926535897931" />
- <property name="VELOCITY_LIMIT_SCALE" value="0.6" />
-
- <property name="shoulder_lift_length" value="0.10" />
- <property name="shoulder_lift_radius" value="0.12" />
-
-
-
-
-
-
-
-
- <macro name="pr2_upper_arm" params="side parent reflect *origin">
-
- <!-- Shoulder pan -->
-
- <joint name="${side}_shoulder_pan_joint" type="revolute">
- <axis xyz="0 0 1" />
-
- <limit min="${reflect*M_PI/4-1.5}" max="${reflect*M_PI/4+1.5}"
- effort="30" velocity="${VELOCITY_LIMIT_SCALE*3.48}"
- k_position="100" k_velocity="10"
- safety_length_min="0.15" safety_length_max="0.15" />
- <calibration reference_position="${reflect*M_PI/4}" values="1.5 -1" />
-
- <joint_properties damping="10.0" />
- </joint>
-
- <link name="${side}_shoulder_pan_link">
- <parent name="${parent}_link" />
- <insert_block name="origin" />
- <joint name="${side}_shoulder_pan_joint" />
- <inertial>
- <mass value="16.29553" />
- <com xyz="-0.005215 -0.030552 -0.175743" />
- <inertia ixx="0.793291393007" ixy="0.003412032973" ixz="0.0096614481"
- iyy="0.818419457224" iyz="-0.033999499551"
- izz="0.13915007406" />
- </inertial>
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">PR2/Blue</elem>
- </map>
- <geometry name="${side}_shoulder_pan_visual">
- <mesh filename="shoulder_yaw" />
- </geometry>
- </visual>
- <collision>
- <origin xyz="0.05 0 -0.2" rpy="0 0 0 " />
- <geometry name="${side}_shoulder_pan_collision">
- <box size="0.347 0.254 0.646" />
- </geometry>
- </collision>
- <map name="${side}_shoulder_pan_sensor" flag="gazebo">
- <verbatim key="${side}_shoulder_pan_bumper_sensor">
- <sensor:contact name="${side}_shoulder_pan_contact_sensor">
- <geom>${side}_shoulder_pan_collision</geom>
- <updateRate>100.0</updateRate>
- <controller:ros_bumper name="${side}_shoulder_pan_ros_bumper_controller" plugin="libros_bumper.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <bumperTopicName>${side}_shoulder_pan_bumper</bumperTopicName>
- <interface:bumper name="${side}_shoulder_pan_ros_bumper_iface" />
- </controller:ros_bumper>
- </sensor:contact>
- </verbatim>
- </map>
- <map name="${side}_shoulder_pan_gravity" flag="gazebo">
- <elem key="turnGravityOff">false</elem>
- </map>
- </link>
-
- <transmission type="SimpleTransmission" name="${side}_shoulder_pan_trans">
- <actuator name="${side}_shoulder_pan_motor" />
- <joint name="${side}_shoulder_pan_joint" />
- <mechanicalReduction>63.16</mechanicalReduction>
- </transmission>
-
- <!-- Shoulder lift -->
-
- <joint name="${side}_shoulder_lift_joint" type="revolute">
- <axis xyz="0 1 0" />
- <anchor xyz="0 0 0" />
-
- <limit min="-0.4" max="1.5" effort="30" velocity="${VELOCITY_LIMIT_SCALE*3.47}"
- k_position="100" k_velocity="10"
- safety_length_min="0.1" safety_length_max="0.1" />
- <calibration reference_position="0" values="1.5 -1 " />
-
- <joint_properties damping="100.0" />
- </joint>
-
- <link name="${side}_shoulder_lift_link">
- <parent name="${side}_shoulder_pan_link" />
- <origin xyz="0.1 0 0" rpy="0 0 0" />
- <joint name="${side}_shoulder_lift_joint" />
- <inertial>
- <mass value="2.41223" />
- <com xyz="-0.035895 0.014422 -0.028263" />
- <inertia ixx="0.016640333585" ixy="0.002696462583" ixz="0.001337742275"
- iyy="0.017232603914" iyz="-0.003605106514" izz="0.018723553425" />
- </inertial>
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">PR2/Grey</elem>
- </map>
- <geometry name="${side}_shoulder_lift_visual">
- <mesh filename="shoulder_lift" />
- </geometry>
- </visual>
- <collision>
- <origin xyz="0 0 0 " rpy="${M_PI/2} 0 0" />
- <geometry name="${side}_shoulder_lift_collision">
- <cylinder radius="${shoulder_lift_radius}" length="${shoulder_lift_length}" />
- </geometry>
- </collision>
- <map name="${side}_shoulder_lift_sensor" flag="gazebo">
- <verbatim key="${side}_shoulder_lift_bumper_sensor">
- <sensor:contact name="${side}_shoulder_lift_contact_sensor">
- <geom>${side}_shoulder_lift_collision</geom>
- <updateRate>100.0</updateRate>
- <controller:ros_bumper name="${side}_shoulder_lift_ros_bumper_controller" plugin="libros_bumper.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <bumperTopicName>${side}_shoulder_lift_bumper</bumperTopicName>
- <interface:bumper name="${side}_shoulder_lift_ros_bumper_iface" />
- </controller:ros_bumper>
- </sensor:contact>
- </verbatim>
- </map>
- <map name="${side}_shoulder_lift_gravity" flag="gazebo">
- <elem key="turnGravityOff">false</elem>
- </map>
- </link>
-
- <transmission type="SimpleTransmission" name="${side}_shoulder_lift_trans">
- <actuator name="${side}_shoulder_lift_motor" />
- <joint name="${side}_shoulder_lift_joint" />
- <mechanicalReduction>57.36</mechanicalReduction>
- </transmission>
-
- <!-- Upperarm roll -->
-
- <joint name="${side}_upper_arm_roll_joint" type="revolute">
- <axis xyz="1 0 0" />
- <anchor xyz="0 0 0" />
-
- <limit min="-3.9" max="0.8" effort="30" velocity="${VELOCITY_LIMIT_SCALE*5.45}"
- k_position="100" k_velocity="2"
- safety_length_min="0.15" safety_length_max="0.15" />
- <calibration reference_position="${-M_PI/2}" values="1.5 -1 " />
-
- <joint_properties damping="1.0" />
- </joint>
-
- <link name="${side}_upper_arm_roll_link">
- <parent name="${side}_shoulder_lift_link" />
- <origin xyz="0 0 0" rpy="0 0 0" />
- <joint name="${side}_upper_arm_roll_joint" />
-
- <inertial>
- <mass value="4.9481" />
- <com xyz=" 0.21227 0.001205 -0.016293 " /> <!-- x becomes y, y becomes z, z becomes x, not sure about the signs -->
- <inertia ixx="0.01338328491" ixy="0.00011947689" ixz="0.00154493231"
- iyy="0.07306071531" iyz="0.00054774592"
- izz="0.07212451075" /> <!-- x becomes y, y becomes z, z becomes x, not sure about the signs -->
- </inertial>
-
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">PR2/Green</elem>
- </map>
- <geometry name="${side}_upper_arm_roll_visual">
- <mesh filename="upper_arm" />
- </geometry>
- </visual>
-
- <collision>
- <origin xyz="0.3 0 0" rpy="0 0 0" />
- <geometry name="${side}_upper_arm_roll_collision">
- <box size="0.362 0.144 0.157" />
- </geometry>
- </collision>
- <map name="${side}_upper_arm_roll_sensor" flag="gazebo">
- <verbatim key="${side}_upper_arm_roll_bumper_sensor">
- <sensor:contact name="${side}_upper_arm_roll_contact_sensor">
- <geom>${side}_upper_arm_roll_collision</geom>
- <updateRate>100.0</updateRate>
- <controller:ros_bumper name="${side}_upper_arm_roll_ros_bumper_controller" plugin="libros_bumper.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <bumperTopicName>${side}_upper_arm_roll_bumper</bumperTopicName>
- <interface:bumper name="${side}_upper_arm_roll_ros_bumper_iface" />
- </controller:ros_bumper>
- </sensor:contact>
- </verbatim>
- </map>
-
- <map name="${side}_upper_arm_roll_gravity" flag="gazebo">
- <elem key="turnGravityOff">false</elem>
- </map>
- </link>
-
- <transmission type="SimpleTransmission" name="${side}_upper_arm_roll_trans">
- <actuator name="${side}_upper_arm_roll_motor" />
- <joint name="${side}_upper_arm_roll_joint" />
- <mechanicalReduction>32.65</mechanicalReduction>
- </transmission>
-
- <!-- Elbow flex -->
-
- <joint name="${side}_elbow_flex_joint" type="revolute">
- <axis xyz="0 -1 0" />
- <anchor xyz="0 0 0" />
-
- <limit min="-0.1" max="2.3" effort="30" velocity="${VELOCITY_LIMIT_SCALE*5.5}"
- k_position="100" k_velocity="3"
- safety_length_min="0.1" safety_length_max="0.4" />
- <calibration reference_position="1.1" values="1.5 -1" />
-
- <joint_properties damping="10.0" />
- </joint>
-
- <link name="${side}_elbow_flex_link">
- <parent name="${side}_upper_arm_roll_link" />
- <origin xyz="0.4 0 0" rpy="0 0 0" />
- <joint name="${side}_elbow_flex_joint" />
-
- <inertial>
- <mass value="1.689246" />
- <com xyz="0.013173 0.001228 -0.011638" /> <!-- switching y to x, z to y, x to z -->
- <inertia ixx="0.00323681521" ixy="-0.00000116216" ixz="0.00029204667"
- iyy="0.00410053774" iyz="-0.00007735928"
- izz="0.00327529855" /> <!-- switching y to x, z to y, x to z -->
- </inertial>
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">PR2/Grey</elem>
- </map>
- <geometry name="${side}_elbow_flex_visual">
- <mesh filename="elbow_flex" />
- </geometry>
- </visual>
- <collision>
- <origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
- <geometry name="${side}_elbow_flex_collision">
- <cylinder radius="0.1" length="0.08" />
- </geometry>
- </collision>
- <map name="${side}_elbow_flex_sensor" flag="gazebo">
- <verbatim key="${side}_elbow_flex_bumper_sensor">
- <sensor:contact name="${side}_elbow_flex_contact_sensor">
- <geom>${side}_elbow_flex_collision</geom>
- <updateRate>100.0</updateRate>
- <controller:ros_bumper name="${side}_elbow_flex_ros_bumper_controller" plugin="libros_bumper.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <bumperTopicName>${side}_elbow_flex_bumper</bumperTopicName>
- <interface:bumper name="${side}_elbow_flex_ros_bumper_iface" />
- </controller:ros_bumper>
- </sensor:contact>
- </verbatim>
- </map>
- <map name="${side}_elbow_flex_gravity" flag="gazebo">
- <elem key="turnGravityOff">false</elem>
- </map>
- </link>
-
- <transmission type="SimpleTransmission" name="${side}_elbow_flex_trans">
- <actuator name="${side}_elbow_flex_motor" />
- <joint name="${side}_elbow_flex_joint" />
- <mechanicalReduction>36.17</mechanicalReduction>
- </transmission>
-
- <map name="sensor" flag="gazebo">
- <verbatim key="p3d_${side}_upper_arm">
- <!--
- <controller:ros_p3d name="p3d_${side}_shoulder_pan_controller" plugin="libros_p3d.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <bodyName>${side}_shoulder_pan_link</bodyName>
- <topicName>${side}_shoulder_pan_pose_ground_truth</topicName>
- <gaussianNoise>0.0</gaussianNoise>
- <frameName>map</frameName>
- <interface:position name="p3d_${side}_shoulder_pan_position_iface" />
- </controller:ros_p3d>
- <controller:ros_p3d name="p3d_${side}_shoulder_lift_controller" plugin="libros_p3d.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <bodyName>${side}_shoulder_lift_link</bodyName>
- <topicName>${side}_shoulder_lift_pose_ground_truth</topicName>
- <gaussianNoise>0.0</gaussianNoise>
- <frameName>map</frameName>
- <interface:position name="p3d_${side}_shoulder_lift_position_iface" />
- </controller:ros_p3d>
- <controller:ros_p3d name="p3d_${side}_upper_arm_roll_controller" plugin="libros_p3d.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <bodyName>${side}_upper_arm_roll_link</bodyName>
- <topicName>${side}_upper_arm_roll_pose_ground_truth</topicName>
- <gaussianNoise>0.0</gaussianNoise>
- <frameName>map</frameName>
- <interface:position name="p3d_${side}_upper_arm_roll_position_iface" />
- </controller:ros_p3d>
- <controller:ros_p3d name="p3d_${side}_elbow_flex_controller" plugin="libros_p3d.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <bodyName>${side}_elbow_flex_link</bodyName>
- <topicName>${side}_elbow_flex_pose_ground_truth</topicName>
- <gaussianNoise>0.0</gaussianNoise>
- <frameName>map</frameName>
- <interface:position name="p3d_${side}_elbow_flex_position_iface" />
- </controller:ros_p3d>
- -->
- </verbatim>
- </map>
-
-
- </macro>
-
-
-
- <macro name="pr2_forearm" params="side parent reflect">
-
- <!-- Forearm roll -->
-
- <joint name="${side}_forearm_roll_joint" type="revolute">
- <axis xyz="-1 0 0" />
- <anchor xyz="0 0 0" />
-
- <limit effort="30" velocity="${VELOCITY_LIMIT_SCALE*6}" k_velocity="1" />
- <calibration reference_position="0" values="1.5 -1" />
-
- <joint_properties damping="1.0" />
- </joint>
-
- <link name="${side}_forearm_roll_link">
- <parent name="${parent}_link" />
- <origin xyz="0 0 0" rpy="0 0 0" />
- <joint name="${side}_forearm_roll_joint" />
- <inertial>
- <mass value="1.804155" />
- <com xyz="0.179474 -0.000058 0.013779" /> <!-- z to x, x to y, y to z -->
- <inertia ixx="0.00175508987" ixy="0.00002937939" ixz="-0.00042767904"
- iyy="0.01243055254" iyz="-0.00000367110"
- izz="0.01356754885" /> <!-- z to x, x to y, y to z -->
- </inertial>
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">PR2/Blue</elem>
- </map>
- <geometry name="${side}_forearm_roll_visual">
- <mesh filename="forearm" />
- </geometry>
- </visual>
- <collision>
- <origin xyz="0.22 0 0" rpy="0 0 0" />
- <geometry name="${side}_forearm_roll_collision">
- <box size="0.27 0.12 0.08" />
- </geometry>
- </collision>
- <map name="${side}_forearm_roll_sensor" flag="gazebo">
- <verbatim key="${side}_forearm_roll_bumper_sensor">
- <sensor:contact name="${side}_forearm_roll_contact_sensor">
- <geom>${side}_forearm_roll_collision</geom>
- <updateRate>100.0</updateRate>
- <controller:ros_bumper name="${side}_forearm_roll_ros_bumper_controller" plugin="libros_bumper.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <bumperTopicName>${side}_forearm_roll_bumper</bumperTopicName>
- <interface:bumper name="${side}_forearm_roll_ros_bumper_iface" />
- </controller:ros_bumper>
- </sensor:contact>
- </verbatim>
- </map>
- <map name="${side}_forearm_roll_gravity" flag="gazebo">
- <elem key="turnGravityOff">false</elem>
- </map>
- </link>
-
- <transmission type="SimpleTransmission" name="${side}_forearm_roll_trans">
- <actuator name="${side}_forearm_roll_motor" />
- <joint name="${side}_forearm_roll_joint" />
- <mechanicalReduction>${576/25*55/14}</mechanicalReduction>
- </transmission>
-
- <!-- Wrist flex -->
-
- <joint name="${side}_wrist_flex_joint" type="revolute">
- <axis xyz="0 -1 0" />
- <anchor xyz="0 0 0" />
-
- <limit min="-0.1" max="2.2" effort="200" velocity="${VELOCITY_LIMIT_SCALE*5.13}"
- k_position="20" k_velocity="4"
- safety_length_min="0.2" safety_length_max="0.2" />
- <calibration reference_position="0.4" values="1.5 -1" />
-
- <joint_properties damping="1.0" />
- </joint>
-
- <link name="${side}_wrist_flex_link">
- <parent name="${side}_forearm_roll_link" />
- <origin xyz="0.32025 0 0" rpy="0 0 0" />
- <joint name="${side}_wrist_flex_joint" />
- <inertial>
- <mass value="0.80305" />
- <com xyz="0.012193 0.000017 -0.004929" /> <!-- my best guess z to z, y to x, x to y -->
- <inertia ixx="0.00077829551" ixy="0.00018491414" ixz="-0.00000036897"
- iyy="0.00108384500" iyz="0.00000017027"
- izz="0.00071460255" /> <!-- my best guess z to z, y to x, x to y -->
- </inertial>
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">PR2/Grey</elem>
- </map>
- <geometry name="${side}_wrist_flex_visual">
- <mesh filename="wrist_flex" />
- </geometry>
- </visual>
- <collision>
- <origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
- <geometry name="${side}_wrist_flex_collision">
- <cylinder radius="0.033" length="0.103" />
- </geometry>
- </collision>
- <map name="${side}_wrist_flex_sensor" flag="gazebo">
- <verbatim key="${side}_wrist_flex_bumper_sensor">
- <sensor:contact name="${side}_wrist_flex_contact_sensor">
- <geom>${side}_wrist_flex_collision</geom>
- <updateRate>100.0</updateRate>
- <controller:ros_bumper name="${side}_wrist_flex_ros_bumper_controller" plugin="libros_bumper.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <bumperTopicName>${side}_wrist_flex_bumper</bumperTopicName>
- <interface:bumper name="${side}_wrist_flex_ros_bumper_iface" />
- </controller:ros_bumper>
- </sensor:contact>
- </verbatim>
- </map>
- <map name="${side}_wrist_flex_gravity" flag="gazebo">
- <elem key="turnGravityOff">false</elem>
- </map>
- </link>
-
- <!-- Wrist roll -->
-
- <joint name="${side}_wrist_roll_joint" type="revolute">
- <axis xyz="1 0 0" />
- <anchor xyz="0 0 0" />
- <limit effort="10" velocity="${VELOCITY_LIMIT_SCALE*6}" k_velocity="2" />
- <calibration reference_position="1.27" values="1.5 -1" />
- <joint_properties damping="0.1" />
- </joint>
-
-
- <link name="${side}_wrist_roll_link">
- <parent name="${side}_wrist_flex_link" />
- <origin xyz="0 0 0" rpy="0 0 0" />
- <joint name="${side}_wrist_roll_joint" />
- <inertial>
- <mass value="0.1" />
- <com xyz="0 0 0" />
- <inertia ixx="0.01" ixy="0" ixz="0"
- iyy="0.01" iyz="0"
- izz="0.01" />
- </inertial>
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">PR2/Red</elem>
- </map>
- <geometry name="${side}_wrist_roll_visual">
- <mesh filename="wrist_roll" />
- </geometry>
- </visual>
- <collision>
- <origin xyz="0.0 0 0" rpy="0 0 0" />
- <geometry name="${side}_wrist_roll_collision">
- <box size="0.01 0.01 0.01" />
- </geometry>
- <verbose value="Yes" />
- </collision>
- <map name="${side}_wrist_roll_sensor" flag="gazebo">
- <verbatim key="${side}_wrist_roll_bumper_sensor">
- <sensor:contact name="${side}_wrist_roll_contact_sensor">
- <geom>${side}_wrist_roll_collision</geom>
- <updateRate>100.0</updateRate>
- <controller:ros_bumper name="${side}_wrist_roll_ros_bumper_controller" plugin="libros_bumper.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <bumperTopicName>${side}_wrist_roll_bumper</bumperTopicName>
- <interface:bumper name="${side}_wrist_roll_ros_bumper_iface" />
- </controller:ros_bumper>
- </sensor:contact>
- </verbatim>
- </map>
- <map name="${side}_wrist_roll_gravity" flag="gazebo">
- <elem key="turnGravityOff">false</elem>
- </map>
- </link>
-
- <transmission type="WristTransmission" name="${side}_wrist_trans">
- <rightActuator name="${side}_wrist_r_motor" />
- <leftActuator name="${side}_wrist_l_motor" />
- <flexJoint name="${side}_wrist_flex_joint" mechanicalReduction="${624/35*54/16}" />
- <rollJoint name="${side}_wrist_roll_joint" mechanicalReduction="${624/35*54/16}" />
- </transmission>
-
- <map name="sensor" flag="gazebo">
- <verbatim key="p3d_${side}_forearm">
- <!--
- <controller:ros_p3d name="p3d_${side}_forearm_roll_controller" plugin="libros_p3d.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <bodyName>${side}_forearm_roll_link</bodyName>
- <topicName>${side}_forearm_roll_pose_ground_truth</topicName>
- <gaussianNoise>0.0</gaussianNoise>
- <frameName>map</frameName>
- <interface:position name="p3d_${side}_forearm_roll_position_iface" />
- </controller:ros_p3d>
- <controller:ros_p3d name="p3d_${side}_wrist_flex_controller" plugin="libros_p3d.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <bodyName>${side}_wrist_flex_link</bodyName>
- <topicName>${side}_wrist_flex_pose_ground_truth</topicName>
- <gaussianNoise>0.0</gaussianNoise>
- <frameName>map</frameName>
- <interface:position name="p3d_${side}_wrist_flex_position_iface" />
- </controller:ros_p3d>
- <controller:ros_p3d name="p3d_${side}_wrist_roll_controller" plugin="libros_p3d.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <bodyName>${side}_wrist_roll_link</bodyName>
- <topicName>${side}_wrist_roll_pose_ground_truth</topicName>
- <gaussianNoise>0.0</gaussianNoise>
- <frameName>map</frameName>
- <interface:position name="p3d_${side}_wrist_roll_position_iface" />
- </controller:ros_p3d>
- -->
- </verbatim>
- </map>
-
- </macro>
-
-
-
- <macro name="pr2_arm" params="side parent reflect *origin">
- <pr2_upper_arm side="${side}" reflect="${reflect}" parent="${parent}">
- <insert_block name="origin" />
- </pr2_upper_arm>
- <pr2_forearm side="${side}" reflect="${reflect}" parent="${side}_elbow_flex" />
- </macro>
-
-
-
- <!-- Calibration -->
-
-
- <macro name="upper_arm_calibrator" params="side">
- <controller name="${side}_cal_shoulder_pan" topic="${side}_cal_shoulder_pan"
- type="JointCalibrationControllerNode">
- <calibrate joint="${side}_shoulder_pan_joint"
- actuator="${side}_shoulder_pan_motor"
- transmission="${side}_shoulder_pan_trans"
- velocity="1.0" />
- <pid p="7" i="0.5" d="0" iClamp="1.0" />
- </controller>
-
- <controller name="cal_shoulder_lift_${side}" topic="cal_shoulder_lift_${side}"
- type="JointCalibrationControllerNode">
- <calibrate joint="${side}_shoulder_lift_joint"
- actuator="${side}_shoulder_lift_motor"
- transmission="${side}_shoulder_lift_trans"
- velocity="-1.0" />
- <pid p="7" i="0.5" d="0" iClamp="1.0" />
- </controller>
-
- <controller name="cal_${side}_upper_arm_roll" topic="cal_${side}_upper_arm_roll"
- type="JointCalibrationControllerNode">
- <calibrate joint="${side}_upper_arm_roll_joint"
- actuator="${side}_upper_arm_roll_motor"
- transmission="${side}_upper_arm_roll_trans"
- velocity="1.0" />
- <pid p="6" i="0.2" d="0" iClamp="2.0" />
- </controller>
-
- <controller name="cal_${side}_elbow_flex" topic="cal_${side}_elbow_flex"
- type="JointCalibrationControllerNode">
- <calibrate joint="${side}_elbow_flex_joint"
- actuator="${side}_elbow_flex_motor"
- transmission="${side}_elbow_flex_trans"
- velocity="1.0" />
- <pid p="6" i="0.2" d="0" iClamp="1.0" />
- </controller>
- </macro>
-
-
- <macro name="forearm_calibrator" params="side">
- <controller name="cal_${side}_forearm_roll" type="JointCalibrationControllerNode">
- <calibrate joint="${side}_forearm_roll_joint"
- actuator="${side}_forearm_roll_motor"
- transmission="${side}_forearm_roll_trans"
- velocity="-1.2" />
- <pid p="5.0" i="0" d="0" iClamp="0" />
- </controller>
-
- <controller type="WristCalibrationControllerNode" name="cal_wrist">
- <calibrate transmission="${side}_wrist_trans"
- actuator_l="${side}_wrist_l_motor" actuator_r="${side}_wrist_r_motor"
- flex_joint="${side}_wrist_flex_joint" roll_joint="${side}_wrist_roll_joint"
- velocity="1.2" />
- <pid p="3.0" i="0.2" d="0" iClamp="2.0" />
- </controller>
- </macro>
-
-
-
-</robot>
Modified: pkg/trunk/stacks/pr2/pr2_defs/defs/base_defs.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_defs/defs/base_defs.xml 2009-07-15 21:42:11 UTC (rev 18891)
+++ pkg/trunk/stacks/pr2/pr2_defs/defs/base_defs.xml 2009-07-15 21:59:38 UTC (rev 18892)
@@ -57,8 +57,11 @@
<elem key="material" value="PR2/${parent}_${suffix}_wheel_link" />
</map>
<geometry name="${parent}_${suffix}_wheel_visual">
- <mesh filename="pr2_wheel" />
+ <mesh filename="pr2_wheel.stlb" />
</geometry>
+ <map name="${parent}_${suffix}_wheel_visual_mesh" flag="ogre">
+ <elem key="mesh" value="pr2_wheel.mesh" />
+ </map>
</visual>
<collision>
@@ -123,8 +126,11 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${suffix}_caster_rotation_visual">
- <mesh filename="caster" scale="1 1 1"/>
+ <mesh filename="caster.stlb" />
</geometry>
+ <map name="${suffix}_caster_rotation_visual_mesh" flag="ogre">
+ <elem key="mesh" value="caster.mesh" />
+ </map>
</visual>
<collision>
@@ -174,8 +180,11 @@
<elem key="material" value="PR2/${parent}_${suffix}_wheel_link" />
</map>
<geometry name="${parent}_${suffix}_wheel_visual">
- <mesh filename="pr2_wheel" />
+ <mesh filename="pr2_wheel.stlb" />
</geometry>
+ <map name="${parent}_${suffix}_wheel_visual_mesh" flag="ogre">
+ <elem key="mesh" value="pr2_wheel.mesh" />
+ </map>
</visual>
<collision>
@@ -240,8 +249,11 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${suffix}_caster_rotation_visual">
- <mesh filename="caster" scale="1 1 1"/>
+ <mesh filename="caster.stlb" />
</geometry>
+ <map name="${suffix}_caster_rotation_visual_mesh" flag="ogre">
+ <elem key="mesh" value="caster.mesh" />
+ </map>
</visual>
<collision>
@@ -286,8 +298,11 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${name}_visual">
- <mesh filename="base" />
+ <mesh filename="base.stlb" />
</geometry>
+ <map name="${name}_visual_mesh" flag="ogre" >
+ <elem key="mesh" value="base.mesh" />
+ </map>
</visual>
<collision>
@@ -432,8 +447,11 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${name}_visual">
- <mesh filename="base" />
+ <mesh filename="base.stlb" />
</geometry>
+ <map name="${name}_visual_mesh" flag="ogre">
+ <elem key="mesh" value="base.mesh" />
+ </map>
</visual>
<collision>
Modified: pkg/trunk/stacks/pr2/pr2_defs/defs/body_defs.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_defs/defs/body_defs.xml 2009-07-15 21:42:11 UTC (rev 18891)
+++ pkg/trunk/stacks/pr2/pr2_defs/defs/body_defs.xml 2009-07-15 21:59:38 UTC (rev 18892)
@@ -41,8 +41,11 @@
<elem key="material" value="PR2/Grey2" />
</map>
<geometry name="${name}_visual">
- <mesh filename="torso" />
+ <mesh filename="torso.stlb" />
</geometry>
+ <map name="${name}_visual_mesh" flag="ogre">
+ <elem key="mesh" value="torso.mesh" />
+ </map>
</visual>
<collision>
Modified: pkg/trunk/stacks/pr2/pr2_defs/defs/gripper_defs.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_defs/defs/gripper_defs.xml 2009-07-15 21:42:11 UTC (rev 18891)
+++ pkg/trunk/stacks/pr2/pr2_defs/defs/gripper_defs.xml 2009-07-15 21:59:38 UTC (rev 18892)
@@ -30,7 +30,6 @@
<property name="finger_joint_effort_limit" value="100.0" />
<macro name="pr2_finger_limits" params="reflect">
- <!-- IMPORTANT: k_velocity and k_position of 1 will induce instability on the acutal joint -->
<limit effort="${finger_joint_effort_limit}" velocity="0.5"
min="${gripper_min_angle}" max="${gripper_max_angle}"
k_velocity="100.0" k_position="100.0"
@@ -79,14 +78,20 @@
<elem key="material" value="PR2/Grey" />
</map>
<geometry name="${prefix}_l_finger_visual">
- <mesh filename="upper_finger_l" />
+ <mesh filename="upper_finger_l.stlb" />
</geometry>
+ <map name="${prefix}_l_finger_visual_mesh" flag="ogre">
+ <elem key="mesh" value="upper_finger_l.mesh" />
+ </map>
</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" />
</geometry>
+ <map name="${prefix}_l_finger_collision_mesh" flag="ogre">
+ <elem key="mesh" value="convex/upper_finger_l_convex.mesh" />
+ </map>
<verbose value="Yes" />
<map flag="collision" name="mesh">
<elem key="type" value="visual"/>
@@ -163,14 +168,20 @@
<elem key="material" value="PR2/Grey" />
</map>
<geometry name="${prefix}_r_finger_visual">
- <mesh filename="upper_finger_r" />
+ <mesh filename="upper_finger_r.stlb" />
</geometry>
+ <map name="${prefix}_r_finger_visual_mesh" flag="ogre">
+ <elem key="mesh" value="upper_finger_r.mesh" />
+ </map>
</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" />
</geometry>
+ <map name="${prefix}_r_finger_collision_mesh" flag="ogre">
+ <elem key="mesh" value="convex/upper_finger_r_convex.mesh" />
+ </map>
<verbose value="Yes" />
<map flag="collision" name="mesh">
<elem key="type" value="visual"/>
@@ -244,14 +255,20 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${prefix}_l_finger_tip_visual">
- <mesh filename="finger_tip_l" />
+ <mesh filename="finger_tip_l.stlb" />
</geometry>
+ <map name="${prefix}_l_finger_tip_visual_mesh" flag="ogre">
+ <elem key="mesh" value="finger_tip_l.mesh" />
+ </map>
</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" />
</geometry>
+ <map name="${prefix}_l_finger_tip_collision_mesh" flag="ogre">
+ <elem key="mesh" value="convex/finger_tip_l_convex.mesh" />
+ </map>
<verbose value="Yes" />
<map flag="collision" name="mesh">
<elem key="type" value="visual"/>
@@ -326,14 +343,20 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${prefix}_r_finger_tip_visual">
- <mesh filename="finger_tip_r" />
+ <mesh filename="finger_tip_r.stlb" />
</geometry>
+ <map name="${prefix}_r_finger_tip_visual_mesh" flag="ogre">
+ <elem key="mesh" value="finger_tip_r.mesh" />
+ </map>
</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" />
</geometry>
+ <map name="${prefix}_r_finger_tip_collision_mesh" flag="ogre">
+ <elem key="mesh" value="convex/finger_tip_r_convex.mesh" />
+ </map>
<verbose value="Yes" />
<map flag="collision" name="mesh">
<elem key="type" value="visual"/>
@@ -476,14 +499,20 @@
<elem key="material" value="PR2/Red" />
</map>
<geometry name="${side}_gripper_palm_visual">
- <mesh filename="gripper_palm" />
+ <mesh filename="gripper_palm.stlb" />
</geometry>
+ <map name="${side}_gripper_palm_visual_mesh" flag="ogre">
+ <elem key="mesh" value="gripper_palm.mesh" />
+ </map>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${side}_gripper_palm_collision">
<mesh filename="convex/gripper_palm_convex.stlb" />
</geometry>
+ <map name="${side}_gripper_palm_collision_mesh" flag="ogre">
+ <elem key="mesh" value="convex/gripper_palm_convex.mesh" />
+ </map>
<verbose value="Yes" />
<map flag="collision" name="mesh">
<elem key="type" value="visual"/>
@@ -701,14 +730,20 @@
<elem key="material" value="PR2/Red" />
</map>
<geometry name="${side}_gripper_palm_visual">
- <mesh filename="gripper_palm" />
+ <mesh filename="gripper_palm.stlb" />
</geometry>
+ <map name="${side}_gripper_palm_visual_mesh" flag="ogre">
+ <elem key="mesh" value="gripper_palm.mesh" />
+ </map>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${side}_gripper_palm_collision">
<mesh filename="convex/gripper_palm_convex.stlb" />
</geometry>
+ <map name="${side}_gripper_palm_collision_mesh" flag="ogre">
+ <elem key="mesh" value="convex/gripper_palm_convex.mesh" />
+ </map>
<verbose value="Yes" />
<map flag="collision" name="mesh">
<elem key="type" value="visual"/>
Modified: pkg/trunk/stacks/pr2/pr2_defs/defs/head_defs.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_defs/defs/head_defs.xml 2009-07-15 21:42:11 UTC (rev 18891)
+++ pkg/trunk/stacks/pr2/pr2_defs/defs/head_defs.xml 2009-07-15 21:59:38 UTC (rev 18892)
@@ -36,8 +36,11 @@
<elem key="material" value="PR2/Red" />
</map>
<geometry name="${name}_mount_visual">
- <mesh filename="hok_tilt" />
+ <mesh filename="hok_tilt.stlb" />
</geometry>
+ <map name="${name}_mount_visual_mesh" flag="ogre">
+ <elem key="mesh" value="hok_tilt.mesh" />
+ </map>
</visual>
<collision>
@@ -417,8 +420,11 @@
<elem key="material" value="PR2/Blue" />
</map>
<geometry name="${name}_visual">
- <mesh filename="head_pan" />
+ <mesh filename="head_pan.stlb" />
</geometry>
+ <map name="${name}_visual_mesh" flag="ogre">
+ <elem key="mesh" value="head_pan.mesh" />
+ </map>
</visual>
<collision>
@@ -467,8 +473,11 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${name}_visual">
- <mesh filename="head_tilt" />
+ <mesh filename="head_tilt.stlb" />
</geometry>
+ <map name="${name}_visual_mesh" flag="ogre">
+ <elem key="mesh" value="head_tilt.mesh" />
+ </map>
</visual>
<collision>
@@ -559,8 +568,11 @@
<elem key="material" value="PR2/Red" />
</map>
<geometry name="${name}_mount_visual">
- <mesh filename="hok_tilt" />
+ <mesh filename="hok_tilt.stlb" />
</geometry>
+ <map name="${name}_mount_visual_mesh" flag="ogre">
+ <elem key="mesh" value="hok_tilt.mesh" />
+ </map>
</visual>
<collision>
@@ -677,8 +689,11 @@
<elem key="material" value="PR2/Blue" />
</map>
<geometry name="${name}_visual">
- <mesh filename="head_pan" />
+ <mesh filename="head_pan.stlb" />
</geometry>
+ <map name="${name}_visual_mesh" flag="ogre">
+ <elem key="mesh" value="head_pan.mesh" />
+ </map>
</visual>
<collision>
@@ -726,8 +741,11 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${name}_visual">
- <mesh filename="head_tilt" />
+ <mesh filename="head_tilt.stlb" />
</geometry>
+ <map name="${name}_visual_mesh" flag="ogre">
+ <elem key="mesh" value="head_tilt.mesh" />
+ </map>
</visual>
<collision>
@@ -774,8 +792,11 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${name}_visual">
- <mesh filename="head_tilt" />
+ <mesh filename="head_tilt.stlb" />
</geometry>
+ <map name="${name}_visual_mesh" flag="ogre">
+ <elem key="mesh" value="head_tilt.mesh" />
+ </map>
</visual>
<collision>
@@ -821,8 +842,11 @@
<elem key="material" value="PR2/Green" />
</map>
<geometry name="${name}_visual">
- <mesh filename="head_tilt" />
+ <mesh filename="head_tilt.stlb" />
</geometry>
+ <map name="${name}_visual_mesh" flag="ogre">
+ <elem key="mesh" value="head_tilt.mesh" />
+ </map>
</visual>
<collision>
@@ -874,6 +898,9 @@
<geometry name="${name}_plate_frame_collision">
<box size="0.01 0.01 0.01" />
</geometry>
+ <map name="${name}_plate_frame_collision_mesh" flag="gazebo">
+ <elem key="mesh">unit_box</elem>
+ </map>
</collision>
</link>
Modified: pkg/trunk/stacks/pr2/pr2_defs/defs/ptz_defs.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_defs/defs/ptz_defs.xml 2009-07-15 21:42:11 UTC (rev 18891)
+++ pkg/trunk/stacks/pr2/pr2_defs/defs/ptz_defs.xml 2009-07-15 21:59:38 UTC (rev 18892)
@@ -33,8 +33,11 @@
<elem key="material" value="PR2/Blue" />
</map>
<geometry name="${side}_ptz_pan_visual">
- <mesh filename="ptz_base_${side}" />
+ <mesh filename="ptz_base_${side}.stlb" />
</geometry>
+ <map name="${side}_ptz_pan_visual_mesh" flag="ogre">
+ <elem key="mesh" value="ptz_base_${side}.mesh" />
+ </map>
</visual>
<collision>
@@ -71,8 +74,11 @@
<elem key="material" value="PR2/Red" />
</map>
<geometry name="${side}_ptz_tilt_visual">
- <mesh filename="ptz_top_${side}" />
+ <mesh filename="ptz_top_${side}.stlb" />
</geometry>
+ <map name="${side}_ptz_tilt_visual_mesh" flag="ogre">
+ <elem key="mesh" value="ptz_top_${side}.mesh" />
+ </map>
</visual>
<collision>
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/robot/robot_link.cpp
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/robot/robot_link.cpp 2009-07-15 21:42:11 UTC (rev 18891)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/robot/robot_link.cpp 2009-07-15 21:59:38 UTC (rev 18892)
@@ -262,7 +262,10 @@
if ( mesh->filename_.empty() )
return;
- std::string model_name = mesh->filename_ + ".mesh";
+ std::string model_name = mesh->filename_;
+ // replace extension with .mesh
+ model_name.replace(model_name.find(std::string(".stl"),0),
+ model_name.size()-model_name.find(std::string(".stl"),0)+1,std::string(".mesh"));
static int count = 0;
std::stringstream ss;
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|