|
From: <hsu...@us...> - 2008-11-19 18:02:24
|
Revision: 6990
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=6990&view=rev
Author: hsujohnhsu
Date: 2008-11-19 18:02:19 +0000 (Wed, 19 Nov 2008)
Log Message:
-----------
* update arm launch file to stop generating .model on launch.
* move Ros_Time plugin block from world files to gazebo_defs.xml.
* update testcameras.xml valid image.
* update Makefile for pr2_prototype1. (remove these later).
* fix indents in pr2d2.xml.
* sped up robot_floorobj.world to 200Hz.
Modified Paths:
--------------
pkg/trunk/demos/arm_gazebo/arm.launch
pkg/trunk/drivers/simulator/gazebo_plugin/test/testcamera.valid.ppm
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_arm_test.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_floorobj.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obstacle.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_pr2d2.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_prototype1.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_simple.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_tablegrasp.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_wg.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/testcameras.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/testscan.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/testslide.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/teststereo.world
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm/pr2d2.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/Makefile
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/pr2_arm.xacro.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/Makefile
pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/gazebo_defs.xml
Modified: pkg/trunk/demos/arm_gazebo/arm.launch
===================================================================
--- pkg/trunk/demos/arm_gazebo/arm.launch 2008-11-19 17:11:50 UTC (rev 6989)
+++ pkg/trunk/demos/arm_gazebo/arm.launch 2008-11-19 18:02:19 UTC (rev 6990)
@@ -1,7 +1,5 @@
<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.expanded $(find gazebo_robot_description)/world/pr2_arm.model" />
<!-- send pr2_arm.xml to param server -->
<include file="$(find wg_robot_description)/pr2_arm_test/send_description.launch" />
<!-- -g flag runs gazebo in gui-less mode -->
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/test/testcamera.valid.ppm
===================================================================
(Binary files differ)
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-19 17:11:50 UTC (rev 6989)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_arm_test.world 2008-11-19 18:02:19 UTC (rev 6990)
@@ -157,13 +157,6 @@
<!-- Robot Arm -->
<model:physical name="robot_model1">
- <!-- Broadcat time over ROS -->
- <controller:ros_time name="ros_time" plugin="libRos_Time.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
- </controller:ros_time>
-
<!-- location of robot in the world -->
<xyz>0.0 0.0 0.0408</xyz>
<rpy>0.0 0.0 0.0</rpy>
@@ -173,16 +166,6 @@
<xi:include href="pr2_arm.model" />
</include>
- <!-- P3D for position groundtruth -->
- <controller:P3D name="p3d_left_wrist_controller" plugin="libP3D.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <bodyName>left_gripper_palm</bodyName>
- <topicName>left_gripper_palm_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_floorobj.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_floorobj.world 2008-11-19 17:11:50 UTC (rev 6989)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_floorobj.world 2008-11-19 18:02:19 UTC (rev 6990)
@@ -24,7 +24,7 @@
<!-- erp is typically .1-.8 -->
<!-- here's the global contact cfm/erp -->
<physics:ode>
- <stepTime>0.001</stepTime>
+ <stepTime>0.005</stepTime>
<gravity>0 0 -9.8</gravity>
<cfm>0.000000000001</cfm>
<erp>0.2</erp>
@@ -305,12 +305,6 @@
<model:physical name="robot_model1">
- <controller:ros_time name="ros_time" plugin="libRos_Time.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
- </controller:ros_time>
-
<xyz>0.0 0.0 0.0408</xyz> <!-- bottom of base off the ground by this much, basically wheel height below skirt -->
<rpy>0.0 0.0 0.0 </rpy>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obstacle.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obstacle.world 2008-11-19 17:11:50 UTC (rev 6989)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obstacle.world 2008-11-19 18:02:19 UTC (rev 6990)
@@ -340,12 +340,6 @@
<model:physical name="robot_model1">
- <controller:ros_time name="ros_time" plugin="libRos_Time.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
- </controller:ros_time>
-
<xyz>0.0 0.0 0.0408</xyz> <!-- bottom of base off the ground by this much, basically wheel height below skirt -->
<rpy>0.0 0.0 0.0 </rpy>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_pr2d2.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_pr2d2.world 2008-11-19 17:11:50 UTC (rev 6989)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_pr2d2.world 2008-11-19 18:02:19 UTC (rev 6990)
@@ -309,12 +309,6 @@
<model:physical name="robot_model1">
- <controller:ros_time name="ros_time" plugin="libRos_Time.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
- </controller:ros_time>
-
<xyz>0.0 0.0 0.02</xyz> <!-- bottom of base off the ground by this much, basically wheel height below skirt -->
<rpy>0.0 0.0 0.0 </rpy>
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-19 17:11:50 UTC (rev 6989)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_prototype1.world 2008-11-19 18:02:19 UTC (rev 6990)
@@ -24,7 +24,7 @@
<!-- erp is typically .1-.8 -->
<!-- here's the global contact cfm/erp -->
<physics:ode>
- <stepTime>0.001</stepTime>
+ <stepTime>0.005</stepTime>
<gravity>0 0 -9.8</gravity>
<cfm>0.0000000001</cfm>
<erp>0.2</erp>
@@ -131,12 +131,6 @@
<model:physical name="robot_model1">
- <controller:ros_time name="ros_time" plugin="libRos_Time.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
- </controller:ros_time>
-
<xyz>0.0 0.0 0.0408</xyz> <!-- bottom of base off the ground by this much, basically wheel height below skirt -->
<rpy>0.0 0.0 0.0 </rpy>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_simple.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_simple.world 2008-11-19 17:11:50 UTC (rev 6989)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_simple.world 2008-11-19 18:02:19 UTC (rev 6990)
@@ -273,12 +273,6 @@
<model:physical name="robot_model1">
- <controller:ros_time name="ros_time" plugin="libRos_Time.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
- </controller:ros_time>
-
<xyz>0.0 0.0 0.0408</xyz> <!-- bottom of base off the ground by this much, basically wheel height below skirt -->
<rpy>0.0 0.0 0.0 </rpy>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_tablegrasp.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_tablegrasp.world 2008-11-19 17:11:50 UTC (rev 6989)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_tablegrasp.world 2008-11-19 18:02:19 UTC (rev 6990)
@@ -300,12 +300,6 @@
<model:physical name="robot_model1">
- <controller:ros_time name="ros_time" plugin="libRos_Time.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
- </controller:ros_time>
-
<xyz>0.0 0.0 0.0408</xyz> <!-- bottom of base off the ground by this much, basically wheel height below skirt -->
<rpy>0.0 0.0 0.0 </rpy>
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-19 17:11:50 UTC (rev 6989)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_wg.world 2008-11-19 18:02:19 UTC (rev 6990)
@@ -131,12 +131,6 @@
<model:physical name="robot_model1">
- <controller:ros_time name="ros_time" plugin="libRos_Time.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
- </controller:ros_time>
-
<xyz>0.0 0.0 0.0408</xyz> <!-- bottom of base off the ground by this much, basically wheel height below skirt -->
<rpy>0.0 0.0 0.0 </rpy>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/testcameras.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/testcameras.world 2008-11-19 17:11:50 UTC (rev 6989)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/testcameras.world 2008-11-19 18:02:19 UTC (rev 6990)
@@ -191,12 +191,6 @@
<model:physical name="robot_model1">
- <controller:ros_time name="ros_time" plugin="libRos_Time.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
- </controller:ros_time>
-
<xyz> -3.0 0.0 0.0408 </xyz>
<rpy> 0.0 0.0 0.0 </rpy>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/testscan.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/testscan.world 2008-11-19 17:11:50 UTC (rev 6989)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/testscan.world 2008-11-19 18:02:19 UTC (rev 6990)
@@ -189,12 +189,6 @@
<model:physical name="robot_model1">
- <controller:ros_time name="ros_time" plugin="libRos_Time.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
- </controller:ros_time>
-
<xyz>0.0 0.0 0.0408 </xyz>
<rpy>0.0 0.0 0.0 </rpy>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/testslide.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/testslide.world 2008-11-19 17:11:50 UTC (rev 6989)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/testslide.world 2008-11-19 18:02:19 UTC (rev 6990)
@@ -336,12 +336,6 @@
<model:physical name="robot_model1">
- <controller:ros_time name="ros_time" plugin="libRos_Time.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
- </controller:ros_time>
-
<xyz>0.0 8.0 110.0 </xyz>
<rpy>0.0 0.0 90.0 </rpy>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/teststereo.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/teststereo.world 2008-11-19 17:11:50 UTC (rev 6989)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/teststereo.world 2008-11-19 18:02:19 UTC (rev 6990)
@@ -189,12 +189,6 @@
<model:physical name="robot_model1">
- <controller:ros_time name="ros_time" plugin="libRos_Time.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
- </controller:ros_time>
-
<xyz>0.0 0.0 0.0408 </xyz>
<rpy>0.0 0.0 0.0 </rpy>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm/pr2d2.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm/pr2d2.xml 2008-11-19 17:11:50 UTC (rev 6989)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm/pr2d2.xml 2008-11-19 18:02:19 UTC (rev 6990)
@@ -506,16 +506,22 @@
<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>
+ <!-- PR2_ACTARRAY -->
+ <controller:gazebo_mechanism_control name="gazebo_mechanism_control" plugin="libgazebo_mechanism_control.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
- <robot filename="pr2d2.xml" />
+ <robot filename="pr2d2.xml" />
- <interface:audio name="gazebo_mechanism_control_dummy_iface" />
- </controller:gazebo_mechanism_control>
+ <interface:audio name="gazebo_mechanism_control_dummy_iface" />
+ </controller:gazebo_mechanism_control>
+ <controller:ros_time name="ros_time" plugin="libRos_Time.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
+ </controller:ros_time>
+
</verbatim>
</map>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/Makefile
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/Makefile 2008-11-19 17:11:50 UTC (rev 6989)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/Makefile 2008-11-19 18:02:19 UTC (rev 6990)
@@ -4,11 +4,11 @@
ROBOT = pr2_arm
-$(ROBOT).model: $(ROBOT).xml
- $(XACRO) $^ > $^.expanded
- $(URDF2GAZEBO) $^.expanded $(MODEL_FILE)/$@
+$(ROBOT).model: $(ROBOT).xacro.xml
+ $(XACRO) $^ > $(ROBOT).xml
+ $(URDF2GAZEBO) $(ROBOT).xml $(MODEL_FILE)/$@
clean:
- $(RM) $(ROBOT).xml.expanded $(MODEL_FILE)/$(ROBOT).model
+ $(RM) $(ROBOT).xml $(MODEL_FILE)/$(ROBOT).model
$(RM) core.* Ogre.log
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/pr2_arm.xacro.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/pr2_arm.xacro.xml 2008-11-19 17:11:50 UTC (rev 6989)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/pr2_arm.xacro.xml 2008-11-19 18:02:19 UTC (rev 6990)
@@ -58,4 +58,19 @@
</collision>
</link>
+ <map name="gazebo_material" flag="gazebo">
+ <verbatim>
+ <!-- P3D for position groundtruth -->
+ <controller:P3D name="p3d_left_wrist_controller" plugin="libP3D.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <bodyName>left_gripper_palm</bodyName>
+ <topicName>left_gripper_palm_pose_ground_truth</topicName>
+ <frameName>map</frameName>
+ <interface:position name="p3d_left_wrist_position"/>
+ </controller:P3D>
+ </verbatim>
+ </map>
+
+
</robot>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/Makefile
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/Makefile 2008-11-19 17:11:50 UTC (rev 6989)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/Makefile 2008-11-19 18:02:19 UTC (rev 6990)
@@ -9,5 +9,5 @@
$(URDF2GAZEBO) $^.xml $(MODEL_FILE)/$@
clean:
- $(RM) $(ROBOT).xml.expanded $(MODEL_FILE)/$(ROBOT).model
+ $(RM) $(ROBOT).xml $(MODEL_FILE)/$(ROBOT).model
$(RM) core.* Ogre.log
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/gazebo_defs.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/gazebo_defs.xml 2008-11-19 17:11:50 UTC (rev 6989)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/gazebo_defs.xml 2008-11-19 18:02:19 UTC (rev 6990)
@@ -25,6 +25,12 @@
<interface:audio name="battery_dummy_interface" />
</controller:gazebo_battery>
+ <controller:ros_time name="ros_time" plugin="libRos_Time.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
+ </controller:ros_time>
+
</verbatim>
</map>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|