|
From: <hsu...@us...> - 2008-12-01 21:43:24
|
Revision: 7426
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7426&view=rev
Author: hsujohnhsu
Date: 2008-12-01 21:43:20 +0000 (Mon, 01 Dec 2008)
Log Message:
-----------
updates to multilink.
Modified Paths:
--------------
pkg/trunk/demos/2dnav_gazebo/manifest.xml
pkg/trunk/demos/examples_gazebo/multi_link.xml
pkg/trunk/robot_descriptions/wg_robot_description/multi_link_test/controllers_multi_link.xml
pkg/trunk/robot_descriptions/wg_robot_description/multi_link_test/multi_link.xml
Modified: pkg/trunk/demos/2dnav_gazebo/manifest.xml
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/manifest.xml 2008-12-01 21:35:37 UTC (rev 7425)
+++ pkg/trunk/demos/2dnav_gazebo/manifest.xml 2008-12-01 21:43:20 UTC (rev 7426)
@@ -17,4 +17,5 @@
<depend package="pr2_gui"/>
<depend package="world_3d_map"/>
<depend package="highlevel_controllers"/>
+ <depend package="executive_trex_pr2"/>
</package>
Modified: pkg/trunk/demos/examples_gazebo/multi_link.xml
===================================================================
--- pkg/trunk/demos/examples_gazebo/multi_link.xml 2008-12-01 21:35:37 UTC (rev 7425)
+++ pkg/trunk/demos/examples_gazebo/multi_link.xml 2008-12-01 21:43:20 UTC (rev 7426)
@@ -14,7 +14,7 @@
<!-- push robotdesc/pr2 to factory and spawn robot in gazebo -->
<node pkg="gazebo_plugin" type="urdf2factory" args="robotdesc/pr2" respawn="false" output="screen" /> <!-- load default arm controller -->
- <!--node pkg="mechanism_control" type="mech.py" args="sp $(find wg_robot_description)/multi_link_test/controllers_multi_link.xml" respawn="false" output="screen" /--> <!-- load default arm controller -->
+ <node pkg="mechanism_control" type="mech.py" args="sp $(find wg_robot_description)/multi_link_test/controllers_multi_link.xml" respawn="false" output="screen" /> <!-- load default arm controller -->
<!--node pkg="robot_mechanism_controllers" type="control.py" args="set test_controller 0.5" respawn="false" output="screen" /--> <!-- open gripper .5 radians -->
</launch>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/multi_link_test/controllers_multi_link.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/multi_link_test/controllers_multi_link.xml 2008-12-01 21:35:37 UTC (rev 7425)
+++ pkg/trunk/robot_descriptions/wg_robot_description/multi_link_test/controllers_multi_link.xml 2008-12-01 21:43:20 UTC (rev 7426)
@@ -13,17 +13,17 @@
</map>
<controller name="link1_controller" topic="link1_controller" type="JointEffortController">
<joint name="link1_joint" >
- <pid p="100" d="2" i="0.1" iClamp="20" />
+ <pid p="500" d="2" i="0.1" iClamp="20" />
</joint>
</controller>
<controller name="link2_controller" topic="link2_controller" type="JointEffortController">
<joint name="link2_joint" >
- <pid p="100" d="2" i="0.1" iClamp="20" />
+ <pid p="300" d="2" i="0.1" iClamp="20" />
</joint>
</controller>
<controller name="link3_controller" topic="link3_controller" type="JointEffortController">
<joint name="link3_joint" >
- <pid p="100" d="2" i="0.1" iClamp="20" />
+ <pid p="200" d="2" i="0.1" iClamp="20" />
</joint>
</controller>
<controller name="link4_controller" topic="link4_controller" type="JointEffortController">
Modified: pkg/trunk/robot_descriptions/wg_robot_description/multi_link_test/multi_link.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/multi_link_test/multi_link.xml 2008-12-01 21:35:37 UTC (rev 7425)
+++ pkg/trunk/robot_descriptions/wg_robot_description/multi_link_test/multi_link.xml 2008-12-01 21:43:20 UTC (rev 7426)
@@ -23,7 +23,7 @@
<anchor xyz="0 0 0" />
<limit k_position="10.0" k_velocity="10.0" min="-3.14159" max="3.14159" effort="10000" velocity="5" />
<calibration values="1.5 -1 " />
- <joint_properties damping="100.0" />
+ <joint_properties damping="200.0" />
</joint>
<!-- joint blocks -->
@@ -32,7 +32,7 @@
<anchor xyz="0.0 0 0" />
<limit k_position="10.0" k_velocity="10.0" min="-3.14159" max="3.14159" effort="10000" velocity="5" />
<calibration values="1.5 -1 " />
- <joint_properties damping="10.0" />
+ <joint_properties damping="100.0" />
</joint>
<!-- joint blocks -->
@@ -41,7 +41,7 @@
<anchor xyz="0.0 0 0" />
<limit k_position="10.0" k_velocity="10.0" min="-3.14159" max="3.14159" effort="5000" velocity="5" />
<calibration values="1.5 -1 " />
- <joint_properties damping="10.0" />
+ <joint_properties damping="100.0" />
</joint>
<!-- joint blocks -->
@@ -59,7 +59,7 @@
<anchor xyz="0.0 0 0" />
<limit k_position="10.0" k_velocity="10.0" min="-3.14159" max="3.14159" effort="500" velocity="5" />
<calibration values="1.5 -1 " />
- <joint_properties damping="50.0" />
+ <joint_properties damping="10.0" />
</joint>
<!-- joint blocks -->
@@ -68,7 +68,7 @@
<anchor xyz="0.0 0 0" />
<limit k_position="10.0" k_velocity="10.0" min="-3.14159" max="3.14159" effort="100" velocity="5" />
<calibration values="1.5 -1 " />
- <joint_properties damping="100.0" />
+ <joint_properties damping="10.0" />
</joint>
<!-- joint blocks -->
@@ -77,7 +77,7 @@
<anchor xyz="0.0 0 0" />
<limit k_position="10.0" k_velocity="10.0" min="-3.14159" max="3.14159" effort="100" velocity="5" />
<calibration values="1.5 -1 " />
- <joint_properties damping="100.0" />
+ <joint_properties damping="10.0" />
</joint>
<!-- link blocks -->
@@ -112,9 +112,9 @@
<origin xyz="0 0 10" rpy="0 0 0" />
<joint name="link1_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" />
+ <mass value="1" />
+ <com xyz="0 0 0.5" />
+ <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
</inertial>
<visual >
<origin xyz="0 0 -0.5" rpy="0 0 0" />
@@ -143,9 +143,9 @@
<origin xyz="0.0 0 0" rpy="0 0 0" />
<joint name="link2_joint" />
<inertial >
- <mass value="10" />
- <com xyz="1.0 0 0" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="100.0" iyz="0.0" izz="1.0" />
+ <mass value="1" />
+ <com xyz="0.5 0 0" />
+ <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
</inertial>
<visual >
<origin xyz="0.5 0 0" rpy="0 0 0" />
@@ -172,10 +172,10 @@
<origin xyz="1.0 0 0" rpy="0 0 0" />
<joint name="link3_joint" />
<inertial >
- <mass value="10" />
- <com xyz="0.1 0 0" />
+ <mass value="1" />
+ <com xyz="0.5 0 0" />
<!-- notably, if ixx and iyy and izz are simultaneously too large (i.e. 10*) compared to com length, this breaks down and links are totally wrong, try it if you like -->
- <inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
+ <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
</inertial>
<visual >
<origin xyz="0.5 0 0" rpy="0 0 0" />
@@ -203,15 +203,15 @@
<origin xyz="1.0 0 0" rpy="0 0 0" />
<joint name="link4_joint" />
<inertial >
- <mass value="10" />
- <com xyz="0.1 0 0" />
+ <mass value="1" />
+ <com xyz="0.5 0 0" />
<!-- notably, if ixx and iyy and izz are simultaneously too large (i.e. 10*) compared to com length, this breaks down and links are totally wrong, try it if you like -->
- <inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
+ <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
</inertial>
<visual >
<origin xyz="0.5 0 0" rpy="0 0 0" />
<map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Green</elem>
+ <elem key="material">Gazebo/Red</elem>
</map>
<geometry name="sholder_roll_mesh_file">
<mesh scale="1.0 0.1 0.1" />
@@ -234,15 +234,15 @@
<origin xyz="1.0 0 0" rpy="0 0 0" />
<joint name="link5_joint" />
<inertial >
- <mass value="10" />
- <com xyz="0.1 0 0" />
+ <mass value="1" />
+ <com xyz="0.5 0 0" />
<!-- notably, if ixx and iyy and izz are simultaneously too large (i.e. 10*) compared to com length, this breaks down and links are totally wrong, try it if you like -->
- <inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
+ <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
</inertial>
<visual >
<origin xyz="0.5 0 0" rpy="0 0 0" />
<map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Green</elem>
+ <elem key="material">Gazebo/Blue</elem>
</map>
<geometry name="sholder_roll_mesh_file">
<mesh scale="1.0 0.1 0.1" />
@@ -265,10 +265,10 @@
<origin xyz="1.0 0 0" rpy="0 0 0" />
<joint name="link6_joint" />
<inertial >
- <mass value="10" />
- <com xyz="0.1 0 0" />
+ <mass value="1" />
+ <com xyz="0.5 0 0" />
<!-- notably, if ixx and iyy and izz are simultaneously too large (i.e. 10*) compared to com length, this breaks down and links are totally wrong, try it if you like -->
- <inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
+ <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
</inertial>
<visual >
<origin xyz="0.5 0 0" rpy="0 0 0" />
@@ -296,15 +296,15 @@
<origin xyz="1.0 0 0" rpy="0 0 0" />
<joint name="link7_joint" />
<inertial >
- <mass value="10" />
- <com xyz="0.1 0 0" />
+ <mass value="1" />
+ <com xyz="0.5 0 0" />
<!-- notably, if ixx and iyy and izz are simultaneously too large (i.e. 10*) compared to com length, this breaks down and links are totally wrong, try it if you like -->
- <inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
+ <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
</inertial>
<visual >
<origin xyz="0.5 0 0" rpy="0 0 0" />
<map name="gazebo_material" flag="gazebo">
- <elem key="material">Gazebo/Green</elem>
+ <elem key="material">Gazebo/Red</elem>
</map>
<geometry name="sholder_roll_mesh_file">
<mesh scale="1.0 0.1 0.1" />
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|