|
From: <hsu...@us...> - 2008-11-08 00:56:03
|
Revision: 6422
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=6422&view=rev
Author: hsujohnhsu
Date: 2008-11-08 00:55:51 +0000 (Sat, 08 Nov 2008)
Log Message:
-----------
no more controllers_gazebo_*.xml
controllers moved into world file, pending move to urdf2gazebo.
Modified Paths:
--------------
pkg/trunk/demos/arm_gazebo/arm.launch
pkg/trunk/demos/examples_gazebo/dual_link.xml
pkg/trunk/demos/examples_gazebo/multi_link.xml
pkg/trunk/demos/examples_gazebo/pr2d2.xml
pkg/trunk/demos/examples_gazebo/single_link.xml
pkg/trunk/demos/pr2_gazebo/pr2.launch
pkg/trunk/demos/pr2_gazebo/pr2_wg.launch
pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1.launch
pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1_controllers.launch
pkg/trunk/drivers/simulator/gazebo_plugin/CMakeLists.txt
pkg/trunk/robot_descriptions/gazebo_robot_description/CMakeLists.txt
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_arm_test.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_dual_link.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_multi_link.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_prototype1.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_single_link.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_wg.world
pkg/trunk/robot_descriptions/wg_robot_description/pr2/backup/pr2.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/base_defs.xml
Added Paths:
-----------
pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_head_tilt_laser_torso_gazebo.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/pr2_prototype1_xacroed.xml
Removed Paths:
-------------
pkg/trunk/robot_descriptions/wg_robot_description/dual_link_test/gazebo/
pkg/trunk/robot_descriptions/wg_robot_description/multi_link_test/gazebo/
pkg/trunk/robot_descriptions/wg_robot_description/pr2/gazebo/
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/gazebo/
pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/gazebo/controllers_gazebo_prototype1.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/gazebo/controllers_head_tilt_laser_torso_gazebo.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/gazebo/pr2_prototype1.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/gazebo/pr2_prototype1_gazebo_actuators.xml
pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/gazebo/
Modified: pkg/trunk/demos/arm_gazebo/arm.launch
===================================================================
--- pkg/trunk/demos/arm_gazebo/arm.launch 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/demos/arm_gazebo/arm.launch 2008-11-08 00:55:51 UTC (rev 6422)
@@ -1,5 +1,8 @@
<launch>
<group name="wg">
+ <!-- create model file for gazebo -->
+ <node pkg="gazebo_robot_description" type="urdf2gazebo" args="$(find wg_robot_description)/pr2_arm_test/pr2_arm.xml $(find gazebo_robot_description)/world/pr2_xml_arm.model" />
+ <!-- send pr2_arm.xml to param server -->
<param name="robotdesc/pr2" command="$(find wg_robot_description_parser)/merge "$(find wg_robot_description)/pr2_arm_test/pr2_arm.xml"" />
<!-- -g flag runs gazebo in gui-less mode -->
<node pkg="gazebo" type="gazebo" args="-n $(find gazebo_robot_description)/world/robot_arm_test.world" respawn="false" output="screen">
Modified: pkg/trunk/demos/examples_gazebo/dual_link.xml
===================================================================
--- pkg/trunk/demos/examples_gazebo/dual_link.xml 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/demos/examples_gazebo/dual_link.xml 2008-11-08 00:55:51 UTC (rev 6422)
@@ -1,5 +1,8 @@
<launch>
<group name="wg">
+ <!-- create model file for gazebo -->
+ <node pkg="gazebo_robot_description" type="urdf2gazebo" args="$(find wg_robot_description)/dual_link_test/pr2_dual_link.xml $(find gazebo_robot_description)/world/pr2_xml_dual_link.model" />
+ <!-- send pr2_arm.xml to param server -->
<param name="robotdesc/pr2" command="$(find wg_robot_description_parser)/merge "$(find wg_robot_description)/dual_link_test/pr2_dual_link.xml"" />
<node pkg="gazebo" type="gazebo" args="$(find gazebo_robot_description)/world/robot_dual_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" />
Modified: pkg/trunk/demos/examples_gazebo/multi_link.xml
===================================================================
--- pkg/trunk/demos/examples_gazebo/multi_link.xml 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/demos/examples_gazebo/multi_link.xml 2008-11-08 00:55:51 UTC (rev 6422)
@@ -1,5 +1,8 @@
<launch>
<group name="wg">
+ <!-- create model file for gazebo -->
+ <node pkg="gazebo_robot_description" type="urdf2gazebo" args="$(find wg_robot_description)/multi_link_test/pr2_multi_link.xml $(find gazebo_robot_description)/world/pr2_xml_multi_link.model" />
+ <!-- send pr2_arm.xml to param server -->
<param name="robotdesc/pr2" command="$(find wg_robot_description_parser)/merge "$(find wg_robot_description)/multi_link_test/pr2_multi_link.xml"" />
<node pkg="gazebo" type="gazebo" args="$(find gazebo_robot_description)/world/robot_multi_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" />
Modified: pkg/trunk/demos/examples_gazebo/pr2d2.xml
===================================================================
--- pkg/trunk/demos/examples_gazebo/pr2d2.xml 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/demos/examples_gazebo/pr2d2.xml 2008-11-08 00:55:51 UTC (rev 6422)
@@ -2,6 +2,9 @@
<!-- this launch file corresponds to robot model in ros-pkg/robot_descriptions/wg_robot_description/pr2_arm -->
<master auto="start" />
<group name="wg">
+ <!-- create model file for gazebo -->
+ <node pkg="gazebo_robot_description" type="urdf2gazebo" args="$(find wg_robot_description)/pr2_arm/pr2d2.xml $(find gazebo_robot_description)/world/pr2d2_xml.model" />
+ <!-- send pr2_arm.xml to param server -->
<param name="robotdesc/pr2" command="$(find wg_robot_description_parser)/merge "$(find wg_robot_description)/pr2_arm/pr2d2.xml"" />
<node pkg="gazebo" type="gazebo" args="-n $(find gazebo_robot_description)/world/robot_pr2d2.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" />
Modified: pkg/trunk/demos/examples_gazebo/single_link.xml
===================================================================
--- pkg/trunk/demos/examples_gazebo/single_link.xml 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/demos/examples_gazebo/single_link.xml 2008-11-08 00:55:51 UTC (rev 6422)
@@ -1,5 +1,8 @@
<launch>
<group name="wg">
+ <!-- create model file for gazebo -->
+ <node pkg="gazebo_robot_description" type="urdf2gazebo" args="$(find wg_robot_description)/single_link_test/pr2_single_link.xml $(find gazebo_robot_description)/world/pr2_xml_single_link.model" />
+ <!-- send pr2_arm.xml to param server -->
<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" />
Modified: pkg/trunk/demos/pr2_gazebo/pr2.launch
===================================================================
--- pkg/trunk/demos/pr2_gazebo/pr2.launch 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/demos/pr2_gazebo/pr2.launch 2008-11-08 00:55:51 UTC (rev 6422)
@@ -1,6 +1,9 @@
<launch>
<!-- this launch file corresponds to robot model in ros-pkg/robot_descriptions/wg_robot_description/pr2 -->
<group name="wg">
+ <!-- create model file for gazebo -->
+ <node pkg="gazebo_robot_description" type="urdf2gazebo" args="$(find wg_robot_description)/pr2/pr2.xml $(find gazebo_robot_description)/world/pr2_xml.model" />
+ <node pkg="gazebo_robot_description" type="urdf2gazebo" args="$(find wg_robot_description)/pr2/pr2.xml $(find gazebo_robot_description)/world/pr2_xml_nolimit.model 1" />
<param name="robotdesc/pr2" command="$(find wg_robot_description_parser)/merge "$(find wg_robot_description)/pr2/pr2.xml"" />
<node pkg="gazebo" type="gazebo" args="-n $(find gazebo_robot_description)/world/robot.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" />
Modified: pkg/trunk/demos/pr2_gazebo/pr2_wg.launch
===================================================================
--- pkg/trunk/demos/pr2_gazebo/pr2_wg.launch 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/demos/pr2_gazebo/pr2_wg.launch 2008-11-08 00:55:51 UTC (rev 6422)
@@ -1,5 +1,8 @@
<launch>
<group name="wg">
+ <!-- create model file for gazebo -->
+ <node pkg="gazebo_robot_description" type="urdf2gazebo" args="$(find wg_robot_description)/pr2/pr2.xml $(find gazebo_robot_description)/world/pr2_xml.model" />
+ <node pkg="gazebo_robot_description" type="urdf2gazebo" args="$(find wg_robot_description)/pr2/pr2.xml $(find gazebo_robot_description)/world/pr2_xml_nolimit.model 1" />
<param name="robotdesc/pr2" command="$(find wg_robot_description_parser)/merge "$(find wg_robot_description)/pr2/pr2.xml"" />
<!-- -g flag runs gazebo in gui-less mode -->
<node pkg="gazebo" type="gazebo" args="-n $(find gazebo_robot_description)/world/robot_wg.world" respawn="false" output="screen">
Modified: pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1.launch
===================================================================
--- pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1.launch 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1.launch 2008-11-08 00:55:51 UTC (rev 6422)
@@ -2,9 +2,12 @@
<!-- this launch file corresponds to robot model in ros-pkg/robot_descriptions/wg_robot_description/pr2 -->
<!-- if needed, group tag allows pushing components into namespace via ns="namespace" -->
<group name="wg">
+ <!-- create model file for gazebo -->
+ <!--node pkg="xacro" type="xacro.py" args="$(find wg_robot_description)/pr2_prototype1/pr2_prototype1.xml $(find wg_robot_description)/pr2_prototype1/pr2_prototype1_xacroed.xml" /-->
+ <node pkg="gazebo_robot_description" type="urdf2gazebo" args="$(find wg_robot_description)/pr2_prototype1/pr2_prototype1_xacroed.xml $(find gazebo_robot_description)/world/pr2_xml_prototype1.model" />
<!-- send pr2.xml to parameter server as a string, allow retrieval by various components whe needs it
(Mechanism Control, BaseControllerNode, etc...) -->
- <param name="robotdesc/pr2" command="$(find wg_robot_description_parser)/merge "$(find wg_robot_description)/pr2_prototype1/gazebo/pr2_prototype1.xml"" />
+ <param name="robotdesc/pr2" command="$(find wg_robot_description_parser)/merge "$(find wg_robot_description)/pr2_prototype1/pr2_prototype1_xacroed.xml"" />
<!-- assign environment variables for gazebo and startup gazebo with argument containing the world file. -->
<node pkg="gazebo" type="gazebo" args="-n $(find gazebo_robot_description)/world/robot_prototype1.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" />
Modified: pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1_controllers.launch
===================================================================
--- pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1_controllers.launch 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1_controllers.launch 2008-11-08 00:55:51 UTC (rev 6422)
@@ -2,7 +2,7 @@
<!-- use mech.py to spawn all controllers listed in controllers.xml -->
<param name="base_controller/odom_publish_rate" value="10" />
<node pkg="mechanism_control" type="mech.py" args="sp $(find wg_robot_description)/pr2_prototype1/controllers_base_lab.xml" output="screen"/>
- <node pkg="mechanism_control" type="mech.py" args="sp $(find wg_robot_description)/pr2_prototype1/gazebo/controllers_head_tilt_laser_torso_gazebo.xml" output="screen"/>
+ <node pkg="mechanism_control" type="mech.py" args="sp $(find wg_robot_description)/pr2_prototype1/controllers_head_tilt_laser_torso_gazebo.xml" output="screen"/>
<!-- start tilting Hokuyo laser by sending it a preset code of 46, this means sawtooth profile sweep.
for details of the profile, rates, see controller::LaserScannerControllerNode. -->
<node pkg="pr2_mechanism_controllers" type="control_laser.py" args="tilt_laser_controller sine 20 0.872 0.3475" respawn="false" output="screen" />
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/CMakeLists.txt
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/CMakeLists.txt 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/CMakeLists.txt 2008-11-08 00:55:51 UTC (rev 6422)
@@ -6,8 +6,8 @@
gensrv()
include_directories(srv/cpp)
-add_definitions(-Wall -DNDEBUG -O3)
-#set(ROS_BUILD_TYPE Release)
+#add_definitions(-Wall -DNDEBUG -O3)
+set(ROS_BUILD_TYPE Release)
rospack_add_library(Ros_Stereo_Camera src/Ros_Stereo_Camera.cc)
rospack_add_library(Ros_Camera src/Ros_Camera.cc)
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/CMakeLists.txt
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/CMakeLists.txt 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/CMakeLists.txt 2008-11-08 00:55:51 UTC (rev 6422)
@@ -12,51 +12,3 @@
message(${wg_robot_description_PACKAGE_PATH}/pr2/pr2.xml)
message(${gazebo_robot_description_PACKAGE_PATH}/world/pr2_xml.model)
-# we do not know all the dependencies of pr2.xml so we always build the target
-add_custom_target(pr2_gazebo_model ALL
- COMMAND ${urdf2gazebo_exe} ${wg_robot_description_PACKAGE_PATH}/pr2/gazebo/pr2_gazebo_actuators.xml ${gazebo_robot_description_PACKAGE_PATH}/world/pr2_xml.model
- DEPENDS urdf2gazebo
- COMMENT "Building Gazebo model for PR2 Standard Model")
-
-add_custom_target(pr2_gazebo_model_nolimit ALL
- COMMAND ${urdf2gazebo_exe} ${wg_robot_description_PACKAGE_PATH}/pr2/gazebo/pr2_gazebo_actuators.xml ${gazebo_robot_description_PACKAGE_PATH}/world/pr2_xml_nolimit.model 1
- DEPENDS urdf2gazebo
- COMMENT "Building Gazebo model for PR2 Gazebo Actuators with no limits")
-
-#pr2_arm
-add_custom_target(pr2d2 ALL
- COMMAND ${urdf2gazebo_exe} ${wg_robot_description_PACKAGE_PATH}/pr2_arm/pr2d2.xml ${gazebo_robot_description_PACKAGE_PATH}/world/pr2d2_xml.model
- DEPENDS urdf2gazebo
- COMMENT "Building Gazebo model for PR2D2 Arm Test")
-
-# pr2_arm_test
-add_custom_target(pr2_gazebo_model_arm ALL
- COMMAND ${urdf2gazebo_exe} ${wg_robot_description_PACKAGE_PATH}/pr2_arm_test/gazebo/pr2_arm_gazebo_actuators.xml ${gazebo_robot_description_PACKAGE_PATH}/world/pr2_xml_arm.model
- DEPENDS urdf2gazebo
- COMMENT "Building Gazebo model for PR2 Arm Test")
-
-# single_link_test
-add_custom_target(pr2_gazebo_model_single_link ALL
- COMMAND ${urdf2gazebo_exe} ${wg_robot_description_PACKAGE_PATH}/single_link_test/gazebo/pr2_single_link_gazebo_actuators.xml ${gazebo_robot_description_PACKAGE_PATH}/world/pr2_xml_single_link.model
- DEPENDS urdf2gazebo
- COMMENT "Building Gazebo model for Single Link Test")
-
-# dual_link_test
-add_custom_target(pr2_gazebo_model_dual_link ALL
- COMMAND ${urdf2gazebo_exe} ${wg_robot_description_PACKAGE_PATH}/dual_link_test/gazebo/pr2_dual_link_gazebo_actuators.xml ${gazebo_robot_description_PACKAGE_PATH}/world/pr2_xml_dual_link.model
- DEPENDS urdf2gazebo
- COMMENT "Building Gazebo model for Dual Link Test")
-
-# multi_link_test
-add_custom_target(pr2_gazebo_model_multi_link ALL
- COMMAND ${urdf2gazebo_exe} ${wg_robot_description_PACKAGE_PATH}/multi_link_test/gazebo/pr2_multi_link_gazebo_actuators.xml ${gazebo_robot_description_PACKAGE_PATH}/world/pr2_xml_multi_link.model
- DEPENDS urdf2gazebo
- COMMENT "Building Gazebo model for Multi Link Test")
-
-# pr2_prototype1
-add_custom_target(pr2_prototype1 ALL
- COMMAND ${urdf2gazebo_exe} ${wg_robot_description_PACKAGE_PATH}/pr2_prototype1/gazebo/pr2_prototype1_gazebo_actuators.xml ${gazebo_robot_description_PACKAGE_PATH}/world/pr2_xml_prototype1.model
- DEPENDS urdf2gazebo
- COMMENT "Building Gazebo model for PR2 Prototype1 Test")
-
-
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot.world 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot.world 2008-11-08 00:55:51 UTC (rev 6422)
@@ -333,6 +333,116 @@
<xi:include href="pr2_xml.model" />
</include>
+ <!-- PR2_ACTARRAY -->
+ <controller:gazebo_mechanism_control name="gazebo_mechanism_control" plugin="libgazebo_mechanism_control.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <interface:audio name="gazebo_mechanism_control_dummy_iface" />
+ </controller:gazebo_mechanism_control>
+
+ <!-- battery controls -->
+ <controller:gazebo_battery name="gazebo_battery_controller" plugin="libgazebo_battery.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1.0</updateRate>
+ <timeout>5</timeout>
+ <diagnostic_rate>1.0</diagnostic_rate>
+ <battery_state_rate>1.0</battery_state_rate>
+ <full_charge_energy>120.0</full_charge_energy>
+ <diagnosticTopicName>diagnostic</diagnosticTopicName>
+ <stateTopicName>battery_state</stateTopicName>
+ <selfTestServiceName>self_test</selfTestServiceName>
+ <interface:audio name="battery_dummy_interface" />
+ </controller:gazebo_battery>
+
+ <!-- ptz camera controls -->
+ <controller:Ros_PTZ name="ptz_cam_left_controller" plugin="libRos_PTZ.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>15.0</updateRate>
+ <panJoint>ptz_pan_left_joint</panJoint>
+ <tiltJoint>ptz_tilt_left_joint</tiltJoint>
+ <commandTopicName>axis_left/ptz_cmd</commandTopicName>
+ <stateTopicName>axis_left/ptz_state</stateTopicName>
+ <interface:ptz name="ptz_left_iface" />
+ </controller:Ros_PTZ>
+
+ <controller:Ros_PTZ name="ptz_cam_right_controller" plugin="libRos_PTZ.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>15.0</updateRate>
+ <panJoint>ptz_pan_right_joint</panJoint>
+ <tiltJoint>ptz_tilt_right_joint</tiltJoint>
+ <commandTopicName>axis_right/ptz_cmd</commandTopicName>
+ <stateTopicName>axis_right/ptz_state</stateTopicName>
+ <interface:ptz name="ptz_right_iface" />
+ </controller:Ros_PTZ>
+
+ <!-- P3D for position groundtruth -->
+ <controller:P3D name="p3d_right_wrist_controller" plugin="libP3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <bodyName>gripper_roll_right</bodyName>
+ <topicName>gripper_roll_right_pose_ground_truth</topicName>
+ <frameName>map</frameName>
+ <interface:position name="p3d_right_wrist_position"/>
+ </controller:P3D>
+
+ <controller:P3D name="p3d_left_wrist_controller" plugin="libP3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <bodyName>gripper_roll_left</bodyName>
+ <topicName>gripper_roll_left_pose_ground_truth</topicName>
+ <frameName>map</frameName>
+ <interface:position name="p3d_left_wrist_position"/>
+ </controller:P3D>
+
+ <controller:P3D name="p3d_base_controller" plugin="libP3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <bodyName>base</bodyName>
+ <topicName>base_pose_ground_truth</topicName>
+ <frameName>map</frameName>
+ <xyzOffsets>25.65 25.65 0</xyzOffsets> <!-- initialize odometry for fake localization-->
+ <rpyOffsets>0 0 0</rpyOffsets>
+ <interface:position name="p3d_base_position"/>
+ </controller:P3D>
+
+ <controller:F3D name="f3d_finger_tip_l_left_controller" plugin="libF3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <bodyName>finger_tip_l_left</bodyName>
+ <topicName>finger_tip_l_left_ground_truth</topicName>
+ <frameName>map</frameName>
+ <interface:position name="f3d_finger_tip_l_left_position"/>
+ </controller:F3D>
+
+ <controller:F3D name="f3d_finger_tip_r_left_controller" plugin="libF3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <bodyName>finger_tip_r_left</bodyName>
+ <topicName>finger_tip_r_left_ground_truth</topicName>
+ <frameName>map</frameName>
+ <interface:position name="f3d_finger_tip_r_left_position"/>
+ </controller:F3D>
+
+ <controller:F3D name="f3d_finger_tip_l_right_controller" plugin="libF3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <bodyName>finger_tip_l_right</bodyName>
+ <topicName>finger_tip_l_right_ground_truth</topicName>
+ <frameName>map</frameName>
+ <interface:position name="f3d_finger_tip_l_right_position"/>
+ </controller:F3D>
+
+ <controller:F3D name="f3d_finger_tip_r_right_controller" plugin="libF3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <bodyName>finger_tip_r_right</bodyName>
+ <topicName>finger_tip_r_right_ground_truth</topicName>
+ <frameName>map</frameName>
+ <interface:position name="f3d_finger_tip_r_right_position"/>
+ </controller:F3D>
+
+
+
</model:physical>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_arm_test.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_arm_test.world 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_arm_test.world 2008-11-08 00:55:51 UTC (rev 6422)
@@ -173,6 +173,24 @@
<xi:include href="pr2_xml_arm.model" />
</include>
+ <!-- PR2_ACTARRAY -->
+ <controller:gazebo_mechanism_control name="gazebo_mechanism_control" plugin="libgazebo_mechanism_control.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+
+ <interface:audio name="gazebo_mechanism_control_dummy_iface" />
+ </controller:gazebo_mechanism_control>
+
+ <!-- P3D for position groundtruth -->
+ <controller:P3D name="p3d_left_wrist_controller" plugin="libP3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <bodyName>gripper_roll_left</bodyName>
+ <topicName>gripper_roll_left_pose_ground_truth</topicName>
+ <frameName>map</frameName>
+ <interface:position name="p3d_left_wrist_position"/>
+ </controller:P3D>
+
</model:physical>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_dual_link.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_dual_link.world 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_dual_link.world 2008-11-08 00:55:51 UTC (rev 6422)
@@ -169,6 +169,36 @@
<xi:include href="pr2_xml_dual_link.model" />
</include>
+ <!-- pr2_actarray -->
+ <controller:gazebo_mechanism_control name="gazebo_mechanism_control" plugin="libgazebo_mechanism_control.so">
+ <alwayson>true</alwayson>
+ <updaterate>1000.0</updaterate>
+
+ <interface:audio name="gazebo_mechanism_control_dummy_iface" />
+ </controller:gazebo_mechanism_control>
+
+ <!-- P3D for position groundtruth -->
+ <controller:P3D name="p3d_link1_controller" plugin="libP3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <bodyName>link1</bodyName>
+ <topicName>link1_pose</topicName>
+ <frameName>link1_frame</frameName>
+ <xyzOffsets>0 0 0.5</xyzOffsets> <!-- at pivot of link2 -->
+ <rpyOffsets>0 0 0.0</rpyOffsets>
+ <interface:position name="p3d_link1_position"/>
+ </controller:P3D>
+
+ <!-- P3D for position groundtruth -->
+ <controller:P3D name="p3d_link2_controller" plugin="libP3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <bodyName>link2</bodyName>
+ <topicName>link2_pose</topicName>
+ <frameName>link2_frame</frameName>
+ <interface:position name="p3d_link2_position"/>
+ </controller:P3D>
+
</model:physical>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_multi_link.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_multi_link.world 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_multi_link.world 2008-11-08 00:55:51 UTC (rev 6422)
@@ -169,6 +169,24 @@
<xi:include href="pr2_xml_multi_link.model" />
</include>
+ <!-- PR2_ACTARRAY -->
+ <controller:gazebo_mechanism_control name="gazebo_mechanism_control" plugin="libgazebo_mechanism_control.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+
+ <interface:audio name="gazebo_mechanism_control_dummy_iface" />
+ </controller:gazebo_mechanism_control>
+
+ <!-- P3D for position groundtruth -->
+ <controller:P3D name="p3d_link3_controller" plugin="libP3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <bodyName>link3</bodyName>
+ <topicName>link3_pose</topicName>
+ <frameName>link3_frame</frameName>
+ <interface:position name="p3d_link3_position"/>
+ </controller:P3D>
+
</model:physical>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_prototype1.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_prototype1.world 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_prototype1.world 2008-11-08 00:55:51 UTC (rev 6422)
@@ -111,11 +111,43 @@
<xi:include href="pr2_xml_prototype1.model" />
</include>
+ <!-- PR2_ACTARRAY -->
+ <controller:gazebo_mechanism_control name="gazebo_mechanism_control" plugin="libgazebo_mechanism_control.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+
+ <interface:audio name="gazebo_mechanism_control_dummy_iface" />
+ </controller:gazebo_mechanism_control>
+
+ <!-- battery controls -->
+ <controller:gazebo_battery name="gazebo_battery_controller" plugin="libgazebo_battery.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1.0</updateRate>
+ <timeout>5</timeout>
+ <diagnostic_rate>1.0</diagnostic_rate>
+ <battery_state_rate>1.0</battery_state_rate>
+ <full_charge_energy>120.0</full_charge_energy>
+ <diagnosticTopicName>diagnostic</diagnosticTopicName>
+ <stateTopicName>battery_state</stateTopicName>
+ <selfTestServiceName>self_test</selfTestServiceName>
+ <interface:audio name="battery_dummy_interface" />
+ </controller:gazebo_battery>
+
+ <controller:P3D name="p3d_base_controller" plugin="libP3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>base</bodyName>
+ <topicName>base_pose_ground_truth</topicName>
+ <frameName>map</frameName>
+ <xyzOffsets>25.65 25.65 0</xyzOffsets> <!-- initialize odometry for fake localization-->
+ <rpyOffsets>0 0 0</rpyOffsets>
+ <interface:position name="p3d_base_position"/>
+ </controller:P3D>
+
</model:physical>
<!-- White Directional light -->
- <!--
<model:renderable name="directional_white">
<light>
<type>directional</type>
@@ -125,7 +157,6 @@
<attenuation>1 0.0 1.0 0.4</attenuation>
</light>
</model:renderable>
- -->
</gazebo:world>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_single_link.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_single_link.world 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_single_link.world 2008-11-08 00:55:51 UTC (rev 6422)
@@ -183,6 +183,24 @@
<xi:include href="pr2_xml_single_link.model" />
</include>
+ <!-- PR2_ACTARRAY -->
+ <controller:gazebo_mechanism_control name="gazebo_mechanism_control" plugin="libgazebo_mechanism_control.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+
+ <interface:audio name="gazebo_mechanism_control_dummy_iface" />
+ </controller:gazebo_mechanism_control>
+
+ <!-- P3D for position groundtruth -->
+ <controller:P3D name="p3d_link1_controller" plugin="libP3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>link1</bodyName>
+ <topicName>link1_pose</topicName>
+ <frameName>link1_frame</frameName>
+ <interface:position name="p3d_link1_position"/>
+ </controller:P3D>
+
</model:physical>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_wg.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_wg.world 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_wg.world 2008-11-08 00:55:51 UTC (rev 6422)
@@ -29,7 +29,7 @@
<cfm>0.0000000001</cfm>
<erp>0.2</erp>
<quickStep>true</quickStep>
- <quickStepIters>3</quickStepIters>
+ <quickStepIters>6</quickStepIters>
<quickStepW>1.3</quickStepW>
</physics:ode>
@@ -111,11 +111,118 @@
<xi:include href="pr2_xml.model" />
</include>
+ <!-- PR2_ACTARRAY -->
+ <controller:gazebo_mechanism_control name="gazebo_mechanism_control" plugin="libgazebo_mechanism_control.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <interface:audio name="gazebo_mechanism_control_dummy_iface" />
+ </controller:gazebo_mechanism_control>
+
+ <!-- battery controls -->
+ <controller:gazebo_battery name="gazebo_battery_controller" plugin="libgazebo_battery.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1.0</updateRate>
+ <timeout>5</timeout>
+ <diagnostic_rate>1.0</diagnostic_rate>
+ <battery_state_rate>1.0</battery_state_rate>
+ <full_charge_energy>120.0</full_charge_energy>
+ <diagnosticTopicName>diagnostic</diagnosticTopicName>
+ <stateTopicName>battery_state</stateTopicName>
+ <selfTestServiceName>self_test</selfTestServiceName>
+ <interface:audio name="battery_dummy_interface" />
+ </controller:gazebo_battery>
+
+ <!-- ptz camera controls -->
+ <controller:Ros_PTZ name="ptz_cam_left_controller" plugin="libRos_PTZ.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>15.0</updateRate>
+ <panJoint>ptz_pan_left_joint</panJoint>
+ <tiltJoint>ptz_tilt_left_joint</tiltJoint>
+ <commandTopicName>axis_left/ptz_cmd</commandTopicName>
+ <stateTopicName>axis_left/ptz_state</stateTopicName>
+ <interface:ptz name="ptz_left_iface" />
+ </controller:Ros_PTZ>
+
+ <controller:Ros_PTZ name="ptz_cam_right_controller" plugin="libRos_PTZ.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>15.0</updateRate>
+ <panJoint>ptz_pan_right_joint</panJoint>
+ <tiltJoint>ptz_tilt_right_joint</tiltJoint>
+ <commandTopicName>axis_right/ptz_cmd</commandTopicName>
+ <stateTopicName>axis_right/ptz_state</stateTopicName>
+ <interface:ptz name="ptz_right_iface" />
+ </controller:Ros_PTZ>
+
+ <!-- P3D for position groundtruth -->
+ <controller:P3D name="p3d_right_wrist_controller" plugin="libP3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <bodyName>gripper_roll_right</bodyName>
+ <topicName>gripper_roll_right_pose_ground_truth</topicName>
+ <frameName>map</frameName>
+ <interface:position name="p3d_right_wrist_position"/>
+ </controller:P3D>
+
+ <controller:P3D name="p3d_left_wrist_controller" plugin="libP3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <bodyName>gripper_roll_left</bodyName>
+ <topicName>gripper_roll_left_pose_ground_truth</topicName>
+ <frameName>map</frameName>
+ <interface:position name="p3d_left_wrist_position"/>
+ </controller:P3D>
+
+ <controller:P3D name="p3d_base_controller" plugin="libP3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <bodyName>base</bodyName>
+ <topicName>base_pose_ground_truth</topicName>
+ <frameName>map</frameName>
+ <xyzOffsets>25.65 25.65 0</xyzOffsets> <!-- initialize odometry for fake localization-->
+ <rpyOffsets>0 0 0</rpyOffsets>
+ <interface:position name="p3d_base_position"/>
+ </controller:P3D>
+
+ <controller:F3D name="f3d_finger_tip_l_left_controller" plugin="libF3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <bodyName>finger_tip_l_left</bodyName>
+ <topicName>finger_tip_l_left_ground_truth</topicName>
+ <frameName>map</frameName>
+ <interface:position name="f3d_finger_tip_l_left_position"/>
+ </controller:F3D>
+
+ <controller:F3D name="f3d_finger_tip_r_left_controller" plugin="libF3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <bodyName>finger_tip_r_left</bodyName>
+ <topicName>finger_tip_r_left_ground_truth</topicName>
+ <frameName>map</frameName>
+ <interface:position name="f3d_finger_tip_r_left_position"/>
+ </controller:F3D>
+
+ <controller:F3D name="f3d_finger_tip_l_right_controller" plugin="libF3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <bodyName>finger_tip_l_right</bodyName>
+ <topicName>finger_tip_l_right_ground_truth</topicName>
+ <frameName>map</frameName>
+ <interface:position name="f3d_finger_tip_l_right_position"/>
+ </controller:F3D>
+
+ <controller:F3D name="f3d_finger_tip_r_right_controller" plugin="libF3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <bodyName>finger_tip_r_right</bodyName>
+ <topicName>finger_tip_r_right_ground_truth</topicName>
+ <frameName>map</frameName>
+ <interface:position name="f3d_finger_tip_r_right_position"/>
+ </controller:F3D>
+
</model:physical>
<!-- White Directional light -->
- <!--
<model:renderable name="directional_white">
<light>
<type>directional</type>
@@ -125,7 +232,6 @@
<attenuation>1 0.0 1.0 0.4</attenuation>
</light>
</model:renderable>
- -->
</gazebo:world>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/backup/pr2.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/backup/pr2.xml 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/backup/pr2.xml 2008-11-08 00:55:51 UTC (rev 6422)
@@ -578,7 +578,7 @@
<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/Shell</elem>
+ <elem key="material">Gazebo/Grey</elem>
</map>
<geometry name="pr2_finger_l_mesh_file">
<mesh filename="finger-l" />
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xml 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xml 2008-11-08 00:55:51 UTC (rev 6422)
@@ -578,7 +578,7 @@
<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/Shell</elem>
+ <elem key="material">Gazebo/Grey</elem>
</map>
<geometry name="pr2_finger_l_mesh_file">
<mesh filename="finger-l" />
Copied: pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_head_tilt_laser_torso_gazebo.xml (from rev 6407, pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/gazebo/controllers_head_tilt_laser_torso_gazebo.xml)
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_head_tilt_laser_torso_gazebo.xml (rev 0)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_head_tilt_laser_torso_gazebo.xml 2008-11-08 00:55:51 UTC (rev 6422)
@@ -0,0 +1,34 @@
+<?xml version="1.0"?>
+
+<controllers>
+
+
+ <!-- ========================================= -->
+ <!-- torso array -->
+ <controller name="torso_controller" topic="torso_controller" type="JointPositionControllerNode">
+ <joint name="torso_joint">
+ <pid p="1000" d="0" i="0" iClamp="0" />
+ </joint>
+ </controller>
+ <!-- ========================================= -->
+ <!-- head and above array -->
+ <controller name="head_pan_controller" topic="head_pan_controller" type="JointPositionControllerNode">
+ <listen_topic name="head_pan_commands" />
+ <joint name="head_pan_joint" >
+ <pid p="100" d="0" i="0" iClamp="0" />
+ </joint>
+ </controller>
+ <controller name="head_tilt_controller" topic="head_tilt_controller" type="JointPositionControllerNode">
+ <listen_topic name="head_tilt_commands" />
+ <joint name="head_tilt_joint" >
+ <pid p="100" d="0" i="0" iClamp="0" />
+ </joint>
+ </controller>
+
+ <controller name="tilt_laser_controller" topic="tilt_laser_controller" type="LaserScannerControllerNode">
+ <joint name="tilt_laser_mount_joint" >
+ <pid p="0.4" d="0" i="0" iClamp="0.1" />
+ </joint>
+ </controller>
+
+</controllers>
Deleted: pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/gazebo/controllers_gazebo_prototype1.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/gazebo/controllers_gazebo_prototype1.xml 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/gazebo/controllers_gazebo_prototype1.xml 2008-11-08 00:55:51 UTC (rev 6422)
@@ -1,54 +0,0 @@
-<?xml version="1.0"?>
-
-<robot name="pr2"><!-- name of the robot-->
-
-
-
-<map name="transmissions_gazebo_mechanism_control" flag="gazebo"> <!-- we can set a name too, but the convertor only cares about the flag -->
- <verbatim key="transmissions_gazebo_mechanism_control" includes="true"> <!-- The key attribute is needed noly if multiple <xml> tags are in the same <map> tag -->
-
- <!-- PR2_ACTARRAY -->
- <controller:gazebo_mechanism_control name="gazebo_mechanism_control" plugin="libgazebo_mechanism_control.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
-
- <interface:audio name="gazebo_mechanism_control_dummy_iface" />
- </controller:gazebo_mechanism_control>
-
- </verbatim>
-</map>
-
-
-<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 -->
-
- <!-- battery controls -->
- <controller:gazebo_battery name="gazebo_battery_controller" plugin="libgazebo_battery.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>1.0</updateRate>
- <timeout>5</timeout>
- <diagnostic_rate>1.0</diagnostic_rate>
- <battery_state_rate>1.0</battery_state_rate>
- <full_charge_energy>120.0</full_charge_energy>
- <diagnosticTopicName>diagnostic</diagnosticTopicName>
- <stateTopicName>battery_state</stateTopicName>
- <selfTestServiceName>self_test</selfTestServiceName>
- <interface:audio name="battery_dummy_interface" />
- </controller:gazebo_battery>
-
- <controller:P3D name="p3d_base_controller" plugin="libP3D.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <bodyName>base</bodyName>
- <topicName>base_pose_ground_truth</topicName>
- <frameName>map</frameName>
- <xyzOffsets>25.65 25.65 0</xyzOffsets> <!-- initialize odometry for fake localization-->
- <rpyOffsets>0 0 0</rpyOffsets>
- <interface:position name="p3d_base_position"/>
- </controller:P3D>
-
- </verbatim>
-</map>
-
-</robot>
-
Deleted: pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/gazebo/controllers_head_tilt_laser_torso_gazebo.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/gazebo/controllers_head_tilt_laser_torso_gazebo.xml 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/gazebo/controllers_head_tilt_laser_torso_gazebo.xml 2008-11-08 00:55:51 UTC (rev 6422)
@@ -1,34 +0,0 @@
-<?xml version="1.0"?>
-
-<controllers>
-
-
- <!-- ========================================= -->
- <!-- torso array -->
- <controller name="torso_controller" topic="torso_controller" type="JointPositionControllerNode">
- <joint name="torso_joint">
- <pid p="1000" d="0" i="0" iClamp="0" />
- </joint>
- </controller>
- <!-- ========================================= -->
- <!-- head and above array -->
- <controller name="head_pan_controller" topic="head_pan_controller" type="JointPositionControllerNode">
- <listen_topic name="head_pan_commands" />
- <joint name="head_pan_joint" >
- <pid p="100" d="0" i="0" iClamp="0" />
- </joint>
- </controller>
- <controller name="head_tilt_controller" topic="head_tilt_controller" type="JointPositionControllerNode">
- <listen_topic name="head_tilt_commands" />
- <joint name="head_tilt_joint" >
- <pid p="100" d="0" i="0" iClamp="0" />
- </joint>
- </controller>
-
- <controller name="tilt_laser_controller" topic="tilt_laser_controller" type="LaserScannerControllerNode">
- <joint name="tilt_laser_mount_joint" >
- <pid p="0.4" d="0" i="0" iClamp="0.1" />
- </joint>
- </controller>
-
-</controllers>
Deleted: pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/gazebo/pr2_prototype1.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/gazebo/pr2_prototype1.xml 2008-11-08 00:51:26 UTC (rev 6421)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/gazebo/pr2_prototype1.xml 2008-11-08 00:55:51 UTC (rev 6422)
@@ -1,856 +0,0 @@
-<?xml version="1.0" ?>
-<robot name="pr2">
-
-
-
-
-
- <joint name="base_joint" type="planar"/><link name="base">
- <parent name="world"/>
- <origin rpy="0 0 0" xyz="0 0 0"/>
- <joint name="base_joint"/>
-
- <inertial>
- <mass value="70.750964"/>
- <com xyz="0 0 0"/>
- <inertia ixx="5.652232699207" ixy="-0.009719934438" ixz="1.293988226423" iyy="5.669473158652" iyz="-0.007379583694" izz="3.683196351726"/>
- </inertial>
-
- <visual>
- <origin rpy="0 0 0" xyz="0 0 0"/>
- <map flag="gazebo" name="gazebo_material">
- <elem key="material">Gazebo/Green</elem>
- </map>
- <geometry name="pr2_base_mesh_file">
- <mesh filename="base"/>
- </geometry>
- </visual>
-
- <collision>
- <origin rpy="0 0 0" xyz="0 0 0.13"/>
- <geometry name="base_collision_geom">
- <box size="0.65 0.65 0.26"/>
- </geometry>
- </collision>
- </link><joint name="base_laser_joint" type="fixed">
- <axis xyz="0 1 0"/>
- <anchor xyz="0 0 0"/>
- </joint><sensor name="base_laser" type="laser">
- <calibration filename="calib_filename"/>
- <parent name="base"/>
- <origin rpy="0 0 0" xyz="0.275 0 0.182"/>
- <joint name="base_laser_joint"/>
- <inertial>
- <mass value="1.0"/>
- <com xyz="0 0 0"/>
- <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
- </inertial>
-
- <visual>
- <origin rpy="0 0 0" xyz="0 0 0.12"/>
- <map flag="gazebo" name="gazebo_material">
- <elem key="material">Gazebo/PioneerBody</elem>
- </map>
- <geometry name="pr2_base_laser_geom">
- <mesh scale="0.001 0.001 0.001"/>
- </geometry>
- </visual>
-
- <collision>
- <origin rpy="0 0 0" xyz="0 0 0.12"/>
- <geometry name="base_laser_collision_geom">
- <box size=".001 .001 .001"/>
- </geometry>
- </collision>
-
- <map flag="gazebo" name="sensor">
- <verbatim key="sensor_ray">
- <sensor:ray name="base_laser">
- <rayCount>683</rayCount>
- <rangeCount>683</rangeCount>
- <laserCount>1</laserCount>
- <origin>0.0 0.0 0.17</origin> <!-- FIXME: for verbatim, adjust this number according to base_laser_center_box_center_offset_z -->
- <displayRays>false</displayRays>
-
- <minAngle>-90</minAngle>
- <maxAngle>90</maxAngle>
-
- <minRange>0.05</minRange>
- <maxRange>10.0</maxRange>
- <updateRate>10.0</updateRate>
- <controller:ros_laser name="ros_base_laser_controller" plugin="libRos_Laser.so">
- <gaussianNoise>0.005</gaussianNoise>
- <alwaysOn>true</alwaysOn>
- <updateRate>10</updateRate>
- <topicName>base_scan</topicName>
- <frameName>base_laser</frameName>
- <interface:laser name="ros_base_laser_iface"/>
- </controller:ros_laser>
- </sensor:ray>
- </verbatim>
- </map>
- </sensor><joint name="caster_front_left_joint" type="revolute">
- <axis xyz="0 0 1"/>
- <anchor xyz="0 0 0"/>
- <calibration values="1.5 -1"/>
- <limit effort="100" velocity="5"/>
- <joint_properties damping="1.0"/>
- </joint><link name="caster_front_left">
- <parent name="base"/>
- <origin rpy="0 0 0" xyz="0.2225 0.2225 0.0282"/>
- <joint name="caster_front_left_joint"/>
-
- <inertial>
- <mass value="3.473082"/>
- <com xyz="0 0 0"/>
- <inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
- </inertial>
-
- <visual>
- <origin rpy="0 0 0 " xyz="0 0 0"/>
- <map flag="gazebo" name="gazebo_material">
- <elem key="material">Gazebo/Green</elem>
- </map>
- <geometry name="pr2_caster_mesh_file">
- <mesh filename="caster" scale="1 1 1"/>
- </geometry>
- </visual>
-
- <collision>
- <origin rpy="0.0 0.0 0.0 " xyz="0 0 0"/>
- <geometry name="caster_collision_geom">
- <box size="0.192 0.164 0.013"/>
- </geometry>
- </collision>
- </link><transmission name="caster_front_left_trans" type="SimpleTransmission">
- <actuator name="caster_front_left_motor"/>
- <joint name="caster_front_left_joint"/>
- <mechanicalReduction>-75.05</mechanicalReduction>
- </transmission><joint name="wheel_front_left_l_joint" type="revolute">
- <axis xyz=" 0 1 0 "/>
- <anchor xyz="0 0 0"/>
- <limit effort="100" velocity="5"/>
- <calibration values="1.5 -1"/>
- <joint_properties damping="0.0"/>
- </joint><link name="wheel_front_left_l">
- <parent name="caster_front_left"/>
- <joint name="wheel_front_left_l_joint"/>
- <origin rpy="0 0 0" xyz="0 0.049 0"/>
- <inertial>
- <mass value="0.44036"/>
- <com xyz=" 0 0 0 "/>
- <inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
- </inertial>
- <visual>
- <origin rpy="0 0 0" xyz="0 0 0"/>
- <map flag="gazebo" name="gazebo_material">
- <!-- TODO should be different for left and right wheel-->
- <elem key="material">Gazebo/Red</elem>
- </map>
- <geometry name="pr2_wheel_mesh_file">
- <mesh filename="wheel_right"/>
- </geometry>
-
- </visual>
- <collision>
- <origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
- <geometry name="pr2_wheel_collision_geom">
- <cylinder length="0.03" radius="0.079"/>
- </geometry>
- <map flag="gazebo" name="friction_coefficients">
- <elem key="mu1" value="50.0"/>
- <elem key="mu2" value="50.0"/>
- </map>
- </collision>
- </link><transmission name="wheel_front_left_l_trans" type="SimpleTransmission">
- <actuator name="wheel_front_left_l_motor"/>
- <joint name="wheel_front_left_l_joint"/>
- <mechanicalReduction>75.05</mechanicalReduction>
- </transmission><joint name="wheel_front_left_r_joint" type="revolute">
- <axis xyz=" 0 1 0 "/>
- <anchor xyz="0 0 0"/>
- <limit effort="100" velocity="5"/>
- <calibration values="1.5 -1"/>
- <joint_properties damping="0.0"/>
- </joint><link name="wheel_front_left_r">
- <parent name="caster_front_left"/>
- <joint name="wheel_front_left_r_joint"/>
- <origin rpy="0 0 0" xyz="0 -0.049 0"/>
- <inertial>
- <mass value="0.44036"/>
- <com xyz=" 0 0 0 "/>
- <inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
- </inertial>
- <visual>
- <origin rpy="0 0 0" xyz="0 0 0"/>
- <map flag="gazebo" name="gazebo_material">
- <!-- TODO should be different for left and right wheel-->
- <elem key="material">Gazebo/Red</elem>
- </map>
- <geometry name="pr2_wheel_mesh_file">
- <mesh filename="wheel_right"/>
- </geometry>
-
- </visual>
- <collision>
- <origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
- <geometry name="pr2_wheel_collision_geom">
- <cylinder length="0.03" radius="0.079"/>
- </geometry>
- <map flag="gazebo" name="friction_coefficients">
- <elem key="mu1" value="50.0"/>
- <elem key="mu2" value="50.0"/>
- </map>
- </collision>
- </link><transmission name="wheel_front_left_r_trans" type="SimpleTransmission">
- <actuator name="wheel_front_left_r_motor"/>
- <joint name="wheel_front_left_r_joint"/>
- <mechanicalReduction>-75.05</mechanicalReduction>
- </transmission><joint name="caster_front_right_joint" type="revolute">
- <axis xyz="0 0 1"/>
- <anchor xyz="0 0 0"/>
- <calibration values="1.5 -1"/>
- <limit effort="100" velocity="5"/>
- <joint_properties damping="1.0"/>
- </joint><link name="caster_front_right">
- <parent name="base"/>
- <origin rpy="0 0 0" xyz="0.2225 -0.2225 0.0282"/>
- <joint name="caster_front_right_joint"/>
-
- <inertial>
- <mass value="3.473082"/>
- <com xyz="0 0 0"/>
- <inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
- </inertial>
-
- <visual>
- <origin rpy="0 0 0 " xyz="0 0 0"/>
- <map flag="gazebo" name="gazebo_material">
- <elem key="material">Gazebo/Green</elem>
- </map>
- <geometry name="pr2_caster_mesh_file">
- <mesh filename="caster" scale="1 1 1"/>
- </geometry>
- </visual>
-
- <collision>
- <origin rpy="0.0 0.0 0.0 " xyz="0 0 0"/>
- <geometry name="caster_collision_geom">
- <box size="0.192 0.164 0.013"/>
- </geometry>
- </collision>
- </link><transmission name="caster_front_right_trans" type="SimpleTransmission">
- <actuator name="caster_front_right_motor"/>
- <joint name="caster_front_right_joint"/>
- <mechanicalReduction>-75.05</mechanicalReduction>
- </transmission><joint name="wheel_front_right_l_joint" type="revolute">
- <axis xyz=" 0 1 0 "/>
- <anchor xyz="0 0 0"/>
- <limit effort="100" velocity="5"/>
- <calibration values="1.5 -1"/>
- <joint_properties damping="0.0"/>
- </joint><link name="wheel_front_right_l">
- <parent name="caster_front_right"/>
- <joint name="wheel_front_right_l_joint"/>
- <origin rpy="0 0 0" xyz="0 0.049 0"/>
- <inertial>
- <mass value="0.44036"/>
- <com xyz=" 0 0 0 "/>
- <inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
- </inertial>
- <visual>
- <origin rpy="0 0 0" xyz="0 0 0"/>
- <map flag="gazebo" name="gazebo_material">
- <!-- TODO should be different for left and right wheel-->
- <elem key="material">Gazebo/Red</elem>
- </map>
- <geometry name="pr2_wheel_mesh_file">
- <mesh filename="wheel_right"/>
- </geometry>
-
- </visual>
- <collision>
- <origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
- <geometry name="pr2_wheel_collision_geom">
- <cylinder length="0.03" radius="0.079"/>
- </geometry>
- <map flag="gazebo" name="friction_coefficients">
- <elem key="mu1" value="50.0"/>
- <elem key="mu2" value="50.0"/>
- </map>
- </collision>
- </link><transmission name="wheel_front_right_l_trans" type="SimpleTransmission">
- <actuator name="wheel_front_right_l_motor"/>
- <joint name="wheel_front_right_l_joint"/>
- <mechanicalReduction>75.05</mechanicalReduction>
- </transmission><joint name="wheel_front_right_r_joint" type="revolute">
- <axis xyz=" 0 1 0 "/>
- <anchor xyz="0 0 0"/>
- <limit effort="100" velocity="5"/>
- <calibration values="1.5 -1"/>
- <joint_properties damping="0.0"/>
- </joint><link name="wheel_front_right_r">
- <parent name="caster_front_right"/>
- <joint name="wheel_front_right_r_joint"/>
- <origin rpy="0 0 0" xyz="0 -0.049 0"/>
- <inertial>
- <mass value="0.44036"/>
- <com xyz=" 0 0 0 "/>
- <inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
- </inertial>
- <visual>
- <origin rpy="0 0 0" xyz="0 0 0"/>
- <map flag="gazebo" name="gazebo_material">
- <!-- TODO should be different for left and right wheel-->
- <elem key="material">Gazebo/Red</elem>
- </map>
- <geometry name="pr2_wheel_mesh_file">
- <mesh filename="wheel_right"/>
- </geometry>
-
- </visual>
- <collision>
- <origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
- <geometry name="pr2_wheel_collision_geom">
- <cylinder length="0.03" radius="0.079"/>
- </geometry>
- <map flag="gazebo" name="friction_coefficients">
- <elem key="mu1" value="50.0"/>
- <elem key="mu2" value="50.0"/>
- </map>
- </collision>
- </link><transmission name="wheel_front_right_r_trans" type="SimpleTransmission">
- <actuator name="wheel_front_right_r_motor"/>
- <joint name="wheel_front_right_r_joint"/>
- <mechanicalReduction>-75.05</mechanicalReduction>
- </transmission><joint name="caster_rear_left_joint" type="revolute">
- <axis xyz="0 0 1"/>
- <anchor xyz="0 0 0"/>
- <calibration values="1.5 -1"/>
- <limit effort="100" velocity="5"/>
- <joint_properties damping="1.0"/>
- </joint><link name="caster_rear_left">
- <parent name="base"/>
- <origin rpy="0 0 0" xyz="-0.2225 0.2225 0.0282"/>
- <joint name="caster_rear_left_joint"/>
-
- <inertial>
- <mass value="3.473082"/>
- <com xyz="0 0 0"/>
- <inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
- </inertial>
-
- <visual>
- <origin rpy="0 0 0 " xyz="0 0 0"/>
- <map flag="gazebo" name="gazebo_material">
- <elem key="material">Gazebo/Green</elem>
- </map>
- <geometry name="pr2_caster_mesh_file">
- <mesh filename="caster" scale="1 1 1"/>
- </geometry>
- </visual>
-
- <collision>
- <origin rpy="0.0 0.0 0.0 " xyz="0 0 0"/>
- <geometry name="caster_collision_geom">
- <box size="0.192 0.164 0.013"/>
- </geometry>
- </collision>
- </link><transmission name="caster_rear_left_trans" type="SimpleTransmission">
- <actuator name="caster_rear_left_motor"/>
- <joint name="caster_rear_left_joint"/>
- <mechanicalReduction>-75.05</mechanicalReduction>
- </transmission><joint name="wheel_rear_left_l_joint" type="revolute">
- <axis xyz=" 0 1 0 "/>
- <anchor xyz="0 0 0"/>
- <limit effort="100" velocity="5"/>
- <calibration values="1.5 -1"/>
- <joint_properties damping="0.0"/>
- </joint><link name="wheel_rear_left_l">
- <parent name="caster_rear_left"/>
- <joint name="wheel_rear_left_l_joint"/>
- <origin rpy="0 0 0" xyz="0 0.049 0"/>
- <inertial>
- <mass value="0.44036"/>
- <com xyz=" 0 0 0 "/>
- <inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
- </inertial>
- <visual>
- <origin rpy="0 0 0" xyz="0 0 0"/>
- <map flag="gazebo" name="gazebo_material">
- <!-- TODO should be different for left and right wheel-->
- <elem key="material">Gazebo/Red</elem>
- </map>
- <geometry name="pr2_wheel_mesh_file">
- <mesh filename="wheel_right"/>
- </geometry>
-
- </visual>
- <collision>
- <origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
- <geometry name="pr2_wheel_collision_geom">
- <cylinder length="0.03" radius="0.079"/>
- </geometry>
- <map flag="gazebo" name="friction_coefficients">
- <elem key="mu1" value="50.0"/>
- <elem key="mu2" value="50.0"/>
- </map>
- </collision>
- </link><transmission name="wheel_rear_left_l_trans" type="SimpleTransmission">
- <actuator name="wheel_rear_left_l_motor"/>
- <joint name="wheel_rear_left_l_joint"/>
- <mechanicalReduction>75.05</mechanicalReduction>
- </transmission><joint name="wheel_rear_left_r_joint" type="revolute">
- <axis xyz=" 0 1 0 "/>
- <anchor xyz="0 0 0"/>
- <limit effort="100" velocity="5"/>
- <calibration values="1.5 -1"/>
- <joint_properties damping="0.0"/>
- </joint><link name="wheel_rear_left_r">
- <parent name="caster_rear_left"/>
- <joint name="wheel_rear_left_r_joint"/>
- <origin rpy="0 0 0" ...
[truncated message content] |