|
From: <hsu...@us...> - 2008-09-30 21:57:49
|
Revision: 4845
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=4845&view=rev
Author: hsujohnhsu
Date: 2008-09-30 21:57:26 +0000 (Tue, 30 Sep 2008)
Log Message:
-----------
* updates to single link robot, simpler and cleaner.
* updates to documentation.
Modified Paths:
--------------
pkg/trunk/drivers/simulator/gazebo_plugin/doc.dox
pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/actuators_single_link.xml
pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/controllers_single_link.xml
pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/gazebo/controllers_gazebo_single_link.xml
pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/gazebo/gazebo_joints_single_link.xml
pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/groups_single_link.xml
pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/pr2_single_link.xml
pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/transmissions_single_link.xml
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/doc.dox
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/doc.dox 2008-09-30 21:47:24 UTC (rev 4844)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/doc.dox 2008-09-30 21:57:26 UTC (rev 4845)
@@ -73,18 +73,204 @@
$ gazebo `rospack find gazebo_robot_description`/world/robot.world
@endverbatim
-@section parameters PR2 Robot Descriptions
-Robot descriptions are explained in the <a href="http://pr.willowgarage.com/wiki/RobotDescriptionFormat">Robot Description Format</a> page.
-You can find the PR2 XML files in \b ros-pkg/robot_descriptions/wg_robot_description/pr2
+@section parameters Robot Descriptions
+\li PR2 Robot Description
+ Robot descriptions are explained in the <a href="http://pr.willowgarage.com/wiki/RobotDescriptionFormat">Robot Description Format</a> page.
+ You can find the PR2 XML files in \b ros-pkg/robot_descriptions/wg_robot_description/pr2
-To convert \b pr2.xml into Gazebo recognizable format (\b ros-pkg/robot_descriptions/gazebo_robot_description) run the following commands:
-@verbatim
-$ roscd gazebo_robot_description
-$ rosmake
-@endverbatim
-Above generates \b ros-pkg/robot_descriptions/gazebo_robot_description/world/pr2_xml.model, which is included by the world file: \b ros-pkg/robot_descriptions/gazebo_robot_description/world/robot.world.
+ To convert \b pr2.xml into Gazebo recognizable format (\b ros-pkg/robot_descriptions/gazebo_robot_description) run the following commands:
+ @verbatim
+ $ roscd gazebo_robot_description
+ $ rosmake
+ @endverbatim
+ Above generates \b ros-pkg/robot_descriptions/gazebo_robot_description/world/pr2_xml.model, which is included by the world file: \b ros-pkg/robot_descriptions/gazebo_robot_description/world/robot.world.
+\li Another Example: Simple Robot (Not really a robot, single link only)
+ Here is an example demonstrating a simple mechanism control / controller stack for a single DOF.
+ - \b pr2_single_link.xml
+ @verbatim
+ <?xml version="1.0"?>
+ <robot name="pr2"><!-- name of the robot-->
+
+ <!-- joint blocks -->
+ <joint name="single_link_joint" type="revolute" >
+ <axis xyz="1 0 0" />
+ <anchor xyz="0 0 0" />
+ <limit min="-M_PI" max="M_PI" effort="100" velocity="5" />
+ <calibration values="1.5 -1 " />
+ </joint>
+
+ <joint name="base_block_joint" type="planar">
+ </joint>
+
+ <!-- link blocks -->
+ <link name="base_block">
+ <parent name="world" />
+ <origin xyz="0 0 0.002 " rpy="0 0 0" />
+ <joint name="base_block_joint" />
+ <inertial>
+ <mass value="1000" />
+ <com xyz="0 0 0" />
+ <inertia ixx="1000" ixy="0" ixz="0" iyy="1000" iyz="0" izz="1000" />
+ </inertial>
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <map name="gazebo_material" flag="gazebo">
+ <elem key="material">Gazebo/GrassFloor</elem>
+ </map>
+ <geometry name="base_block_visual_geom">
+ <mesh scale="20 20 0.1" />
+ </geometry>
+ </visual>
+ <collision>
+ <origin xyz="0 0 0" rpy="0.0 0.0 0.0" />
+ <geometry name="base_block_collision_geom">
+ <box size="20 20 0.1" />
+ </geometry>
+ </collision>
+ </link>
+
+ <link name="single_link">
+ <parent name="base_block" />
+ <origin xyz="0 0 1" rpy="0 0 0" />
+ <joint name="single_link_joint" />
+ <inertial >
+ <mass value="10" />
+ <com xyz="0 0 0" />
+ <inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
+ </inertial>
+ <visual >
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <map name="gazebo_material" flag="gazebo">
+ <elem key="material">Gazebo/Red</elem>
+ </map>
+ <geometry name="sholder_roll_mesh_file">
+ <mesh scale="1.0 0.1 0.1" />
+ </geometry>
+ </visual>
+ <collision >
+ <origin xyz="0.5 0 0" rpy="0.0 0.0 0.0 " />
+ <geometry name="single_link_collision_geom">
+ <box size="1.0 0.1 0.1" />
+ </geometry>
+ </collision>
+ <map name="single_link_gravity" flag="gazebo">
+ <elem key="turnGravityOff">true</elem>
+ </map>
+ </link>
+ <!-- Define groups of links; a link may be part of multiple groups -->
+ <include>groups_single_link.xml</include>
+ <!-- mechanism controls -->
+ <include>actuators_single_link.xml</include>
+ <include>transmissions_single_link.xml</include>
+
+ <!-- setup for GazeboActuators plugin -->
+ <map name="transmissions_gazebo_actuators" flag="gazebo"> <!-- we can set a name too, but the convertor only cares about the flag -->
+ <verbatim key="transmissions_gazebo_actuators" includes="true"> <!-- The key attribute is needed noly if multiple <xml> tags are in the same <map> tag -->
+ <!-- PR2_ACTARRAY -->
+ <controller:gazebo_actuators name="gazebo_actuators" plugin="libgazebo_actuators.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <robot filename="pr2_single_link.xml" />
+ <gazebo_physics filename="gazebo_joints_single_link.xml" /> <!-- for simulator/physics specific settigs -->
+ <interface:audio name="gazebo_actuators_dummy_iface" />
+ </controller:gazebo_actuators>
+ </verbatim>
+ </map>
+ <!-- setup for a ground truth widget, returns pose/rate information over ROS via P3D plugin -->
+ <map name="controllers" flag="gazebo"> <!-- we can set a name too, but the convertor only cares about the flag -->
+ <verbatim key="controllers"> <!-- The key attribute is needed noly if multiple <xml> tags are in the same <map> tag -->
+
+ <!-- P3D for position groundtruth -->
+ <controller:P3D name="p3d_single_link_controller" plugin="libP3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>single_link</bodyName>
+ <topicName>single_link_pose</topicName>
+ <frameName>single_link_frame</frameName>
+ <interface:position name="p3d_single_link_position"/>
+ </controller:P3D>
+
+ </verbatim>
+ </map>
+ </robot>
+ @endverbatim
+ - where \b gazebo_joints_single_link.xml specifies damping of the joint
+ @verbatim
+ <robot name="pr2">
+ <joint name="single_link_joint" >
+ <explicitDampingCoefficient>1</explicitDampingCoefficient>
+ </joint>
+ </robot>
+ @endverbatim
+ - \b groups_single_link.xml is used by kinematics library to construct a kinematic chain, though meaningless in this example.
+ @verbatim
+ <?xml version="1.0"?>
+ <robot name="pr2"><!-- name of the robot-->
+ <group name="my_group" flags="planning kinematic">
+ roll_link
+ </group>
+ </robot>
+ @endverbatim
+ - \b actuators_single_link.xml
+ @verbatim
+ <?xml version="1.0"?>
+ <robot name="pr2"><!-- name of the robot-->
+ <actuator name="single_link_motor">
+ <motorboardID>12345</motorboardID>
+ <maxCurrent>5</maxCurrent>
+ <motor>MAXON</motor>
+ <ip> 10.12.0.103 </ip>
+ <port> 0 </port>
+ <reduction>10</reduction>
+ <polymap>-1 -0.2 -0.5 </polymap>
+ </actuator>
+ </robot>
+ @endverbatim
+ - \b transmissions_single_link.xml
+ @verbatim
+ <?xml version="1.0"?>
+ <robot name="pr2"><!-- name of the robot-->
+ <transmission type="SimpleTransmission" name="single_link_trans">
+ <actuator name="single_link_motor" />
+ <joint name="single_link_joint" />
+ <mechanicalReduction>1</mechanicalReduction>
+ <motorTorqueConstant>1</motorTorqueConstant>
+ <pulsesPerRevolution>90000</pulsesPerRevolution>
+ </transmission>
+ </robot>
+ @endverbatim
+ - here's a simple controller xml to control the single link \bcontroller_single_link.xml:
+ @verbatim
+ <?xml version="1.0"?>
+ <controllers>
+ <controller name="test_controller" topic="single_link_controller" type="JointPositionControllerNode">
+ <joint name="single_link_joint" >
+ <pid p="2000" d="200" i="0.1" iClamp="1" />
+ </joint>
+ </controller>
+ </controllers>
+ @endverbatim
+ - and finally, to run it all, a roslaunch script can be found in \b ros-pkg/robot_descriptions/gazebo_robot_description/single_link.xml:
+ @verbatim
+ <launch>
+ <group name="wg">
+ <param name="robotdesc/pr2" command="$(find wg_robot_description_parser)/merge "$(find wg_robot_description)/single_link_test/pr2_single_link.xml"" />
+ <node pkg="gazebo" type="gazebo" args="$(find gazebo_robot_description)/world/robot_single_link.world" respawn="false" output="screen">
+ <env name="LD_LIBRARY_PATH" value="$(find gazebo_plugin)/lib:$(find gazebo)/gazebo/lib:$(find Cg)/Cg/lib:$LD_LIBRARY_PATH" />
+ <env name="GAZEBO_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
+ <env name="OGRE_RESOURCE_PATH" value="$(find ogre)/ogre/lib/OGRE" />
+ <env name="MC_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
+ </node>
+ </group>
+ <!-- startup a single controller -->
+ <node pkg="mechanism_control" type="mech.py" args="sp $(find wg_robot_description)/single_link_test/controllers_single_link.xml" respawn="false" output="screen" />
+ <!-- set controller to .5 radians -->
+ <node pkg="robot_mechanism_controllers" type="control.py" args="set test_controller 0.5" respawn="false" output="screen" />
+ </launch>
+ @endverbatim
+
@section topic PR2 ROS topics
Various dynamically loaded plugins have been outfitted for PR2.
Below are the ROS messages actively used by PR2 simulation as described by launch script \b roslaunch \b ros-pkg/robot_descriptions/gazebo_robot_description/pr2_gazebo_actuators.xml.
@@ -325,7 +511,7 @@
@endverbatim
-\li The corresponding XML snippit required to setup the controller:
+\li The corresponding XML snippet required to setup the controller:
@verbatim
<model:physical name="my_model">
<controller:my_plugin name="my_plugin_name" plugin="libmy_plugin.so">
Modified: pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/actuators_single_link.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/actuators_single_link.xml 2008-09-30 21:47:24 UTC (rev 4844)
+++ pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/actuators_single_link.xml 2008-09-30 21:57:26 UTC (rev 4845)
@@ -1,11 +1,6 @@
<?xml version="1.0"?>
-
<robot name="pr2"><!-- name of the robot-->
-
-<!-- Actuators -->
-<!-- ========================================= -->
-<!-- Left Arm -->
- <actuator name="upperarm_roll_left_motor">
+ <actuator name="single_link_motor">
<motorboardID>12345</motorboardID>
<maxCurrent>5</maxCurrent>
<motor>MAXON</motor>
@@ -14,8 +9,6 @@
<reduction>10</reduction>
<polymap>-1 -0.2 -0.5 </polymap>
</actuator>
-<!-- ========================================= -->
-
</robot>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/controllers_single_link.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/controllers_single_link.xml 2008-09-30 21:47:24 UTC (rev 4844)
+++ pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/controllers_single_link.xml 2008-09-30 21:57:26 UTC (rev 4845)
@@ -1,8 +1,7 @@
<?xml version="1.0"?>
-
<controllers>
- <controller name="test_controller" topic="upperarm_roll_left_controller" type="JointPositionControllerNode">
- <joint name="upperarm_roll_left_joint" >
+ <controller name="test_controller" topic="single_link_controller" type="JointPositionControllerNode">
+ <joint name="single_link_joint" >
<pid p="2000" d="200" i="0.1" iClamp="1" />
</joint>
</controller>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/gazebo/controllers_gazebo_single_link.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/gazebo/controllers_gazebo_single_link.xml 2008-09-30 21:47:24 UTC (rev 4844)
+++ pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/gazebo/controllers_gazebo_single_link.xml 2008-09-30 21:57:26 UTC (rev 4845)
@@ -28,13 +28,13 @@
<verbatim key="controllers"> <!-- The key attribute is needed noly if multiple <xml> tags are in the same <map> tag -->
<!-- P3D for position groundtruth -->
- <controller:P3D name="p3d_upperarm_roll_controller" plugin="libP3D.so">
+ <controller:P3D name="p3d_single_link_controller" plugin="libP3D.so">
<alwaysOn>true</alwaysOn>
<updateRate>100.0</updateRate>
- <bodyName>upperarm_roll_left</bodyName>
- <topicName>upperarm_roll_left_pose</topicName>
- <frameName>upperarm_roll_left_frame</frameName>
- <interface:position name="p3d_upperarm_roll_position"/>
+ <bodyName>single_link</bodyName>
+ <topicName>single_link_pose</topicName>
+ <frameName>single_link_frame</frameName>
+ <interface:position name="p3d_single_link_position"/>
</controller:P3D>
</verbatim>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/gazebo/gazebo_joints_single_link.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/gazebo/gazebo_joints_single_link.xml 2008-09-30 21:47:24 UTC (rev 4844)
+++ pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/gazebo/gazebo_joints_single_link.xml 2008-09-30 21:57:26 UTC (rev 4845)
@@ -1,8 +1,5 @@
<robot name="pr2">
- <!-- ========================================= -->
- <!-- left arm array -->
- <joint name="upperarm_roll_left_joint" >
- <explicitDampingCoefficient>1</explicitDampingCoefficient>
- </joint>
-
+ <joint name="single_link_joint" >
+ <explicitDampingCoefficient>1</explicitDampingCoefficient>
+ </joint>
</robot>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/groups_single_link.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/groups_single_link.xml 2008-09-30 21:47:24 UTC (rev 4844)
+++ pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/groups_single_link.xml 2008-09-30 21:57:26 UTC (rev 4845)
@@ -1,10 +1,6 @@
<?xml version="1.0"?>
-
<robot name="pr2"><!-- name of the robot-->
-
- <group name="left_arm" flags="planning kinematic">
- upperarm_roll_left
+ <group name="my_group" flags="planning kinematic">
+ roll_link
</group>
-
-
</robot>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/pr2_single_link.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/pr2_single_link.xml 2008-09-30 21:47:24 UTC (rev 4844)
+++ pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/pr2_single_link.xml 2008-09-30 21:57:26 UTC (rev 4845)
@@ -2,137 +2,75 @@
<robot name="pr2"><!-- name of the robot-->
- <!-- Begin template definitions for ease of reuse -->
-
-
- <const name="upperarm_roll_size_x" value="0.362" /> <!-- for defining collision geometry -->
- <const name="upperarm_roll_size_y" value="0.144" /> <!-- for defining collision geometry -->
- <const name="upperarm_roll_size_z" value="0.157" /> <!-- for defining collision geometry -->
- <const name="upperarm_roll_center_box_center_offset_x" value=".30" /> <!-- from origin of mesh to center of box-geom -->
-
-
- <const name="upperarm_roll_elbow_flex_offset_x" value="0.4" /> <!-- mp 20080801 -->
- <const name="upperarm_roll_min_limit" value="-2.3562" />
- <const name="upperarm_roll_max_limit" value="2.3562" />
-
- <!-- End constant dimensions -->
- <const_block name="pr2_upperarm_roll_joint">
- <axis xyz="1 0 0" /> <!-- direction of the joint in a global coordinate frame -->
- <anchor xyz="0 0 0" /> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
- <limit min="upperarm_roll_min_limit" max="upperarm_roll_max_limit" effort="100" velocity="5" />
- <calibration values="1.5 -1 " /> <!-- Calibration stop/flag indicating location and then direction -->
- </const_block>
-
- <const_block name="pr2_upperarm_roll_inertial">
- <mass value="4.9481" />
- <com xyz="0.21227 0.001205 -0.016293" /> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame --> <!-- FIXME John switched x and z for now -->
- <inertia ixx="1.0" ixy="0.000547745916" ixz="0.000119476885" iyy="1.0" iyz="0.001544932307" izz="1.0" />
- </const_block>
-
- <const_block name="pr2_upperarm_roll_collision">
- <origin xyz="upperarm_roll_center_box_center_offset_x 0 0" rpy="0.0 0.0 0.0 " /> <!-- location defined with respect to the link origin in a local coordinate frame -->
- <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
- <geometry name="pr2_upperarm_roll_collision_geom">
- <box size=" upperarm_roll_size_x upperarm_roll_size_y upperarm_roll_size_z " />
- </geometry>
- </const_block>
-
- <const_block name="pr2_upperarm_roll_visual">
- <origin xyz="0 0 0" rpy="0 0 0 " /> <!-- location defined with respect to the link origin in a local coordinate frame -->
- <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
- <map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Red</elem>
- </map>
- <geometry name="pr2_sholder_roll_mesh_file">
- <mesh filename="upperarm_roll" />
- </geometry>
- </const_block>
-
- <!-- End template definitions for ease of reuse -->
-
- <joint name="upperarm_roll_left_joint" type="revolute" >
- <insert_const_block name="pr2_upperarm_roll_joint"/>
+ <!-- joint blocks -->
+ <joint name="single_link_joint" type="revolute" >
+ <axis xyz="1 0 0" />
+ <anchor xyz="0 0 0" />
+ <limit min="-M_PI" max="M_PI" effort="100" velocity="5" />
+ <calibration values="1.5 -1 " />
</joint>
- <joint name="base_joint" type="planar">
+ <joint name="base_block_joint" type="planar">
</joint>
<!-- link blocks -->
-
- <!-- Begin arm definitions -->
-
- <link name="base"><!-- link specifying the base of the robot -->
-
+ <link name="base_block">
<parent name="world" />
-
- <!-- rotation of a local coordinate frame attached to the link with respect to a global coordinate frame -->
- <origin xyz="0 0 0.002 " rpy="0 0 0" /> <!-- position of a local coordinate frame attached to the link with respect to the parent link's coordinate frame -->
-
- <joint name="base_joint" />
-
+ <origin xyz="0 0 0.002 " rpy="0 0 0" />
+ <joint name="base_block_joint" />
<inertial>
<mass value="1000" />
- <com xyz="0 0 0" /> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
+ <com xyz="0 0 0" />
<inertia ixx="1000" ixy="0" ixz="0" iyy="1000" iyz="0" izz="1000" />
</inertial>
-
<visual>
- <origin xyz="0 0 0" rpy="0 0 0" /> <!-- location defined with respect to the link origin in a local coordinate frame -->
- <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
+ <origin xyz="0 0 0" rpy="0 0 0" />
<map name="gazebo_material" flag="gazebo">
<elem key="material">Gazebo/GrassFloor</elem>
</map>
- <geometry name="pr2_base_visual_geom">
+ <geometry name="base_block_visual_geom">
<mesh scale="20 20 0.1" />
</geometry>
</visual>
-
<collision>
- <origin xyz="0 0 0" rpy="0.0 0.0 0.0 " /> <!-- default box is centered at the origin -->
- <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
- <geometry name="base_collision_geom"> <!-- think about putting mesh here as well -->
+ <origin xyz="0 0 0" rpy="0.0 0.0 0.0" />
+ <geometry name="base_block_collision_geom">
<box size="20 20 0.1" />
</geometry>
</collision>
-
</link>
- <link name="upperarm_roll_left"><!-- link specifying the shoulder of the robot -->
- <parent name="base" />
- <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
- <origin xyz="0 0 1" rpy="0 0 0" /> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
-
- <joint name="upperarm_roll_left_joint" />
+ <link name="single_link">
+ <parent name="base_block" />
+ <origin xyz="0 0 1" rpy="0 0 0" />
+ <joint name="single_link_joint" />
<inertial >
- <insert_const_block name="pr2_upperarm_roll_inertial"/>
+ <mass value="10" />
+ <com xyz="0 0 0" />
+ <inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
</inertial>
<visual >
- <insert_const_block name="pr2_upperarm_roll_visual"/>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <map name="gazebo_material" flag="gazebo">
+ <elem key="material">Gazebo/Red</elem>
+ </map>
+ <geometry name="sholder_roll_mesh_file">
+ <mesh scale="1.0 0.1 0.1" />
+ </geometry>
</visual>
<collision >
- <insert_const_block name="pr2_upperarm_roll_collision"/>
+ <origin xyz="0.5 0 0" rpy="0.0 0.0 0.0 " />
+ <geometry name="single_link_collision_geom">
+ <box size="1.0 0.1 0.1" />
+ </geometry>
</collision>
- <map name="upperarm_roll_gravity" flag="gazebo">
+ <map name="single_link_gravity" flag="gazebo">
<elem key="turnGravityOff">true</elem>
</map>
</link>
-
- <!-- End sensor definitions -->
-
- <!--
- <frame name="test">
- <parent name="finger_l_left" />
- <origin xyz="0 0 0 " rpy="0.0 0.0 0.0 " /> // location defined with respect to the link origin in the sensor's local coordinate frame
- // All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis
- </frame>
- -->
-
-
<!-- Define groups of links; a link may be part of multiple groups -->
-
<include>groups_single_link.xml</include>
-
- <!-- controllers for gazebo -->
+ <!-- mechanism controls -->
<include>actuators_single_link.xml</include>
<include>transmissions_single_link.xml</include>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/transmissions_single_link.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/transmissions_single_link.xml 2008-09-30 21:47:24 UTC (rev 4844)
+++ pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/transmissions_single_link.xml 2008-09-30 21:57:26 UTC (rev 4845)
@@ -1,17 +1,12 @@
<?xml version="1.0"?>
-
<robot name="pr2"><!-- name of the robot-->
-
- <!-- Transmissions -->
- <!-- ========================================= -->
- <transmission type="SimpleTransmission" name="upperarm_roll_left_trans">
- <actuator name="upperarm_roll_left_motor" />
- <joint name="upperarm_roll_left_joint" />
+ <transmission type="SimpleTransmission" name="single_link_trans">
+ <actuator name="single_link_motor" />
+ <joint name="single_link_joint" />
<mechanicalReduction>1</mechanicalReduction>
<motorTorqueConstant>1</motorTorqueConstant>
<pulsesPerRevolution>90000</pulsesPerRevolution>
</transmission>
-<!-- ========================================= -->
</robot>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|