|
From: <stu...@us...> - 2008-10-09 00:53:16
|
Revision: 5186
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=5186&view=rev
Author: stuglaser
Date: 2008-10-09 00:53:12 +0000 (Thu, 09 Oct 2008)
Log Message:
-----------
Placed the torso and laser in the proper locations for the one-armed bandit.
Modified Paths:
--------------
pkg/trunk/manip/teleop_robot/scripts/calibrate.py
pkg/trunk/robot_descriptions/wg_robot_description/one_armed_bandit/one_armed_bandit.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/arm_defs.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/head_defs.xml
Modified: pkg/trunk/manip/teleop_robot/scripts/calibrate.py
===================================================================
--- pkg/trunk/manip/teleop_robot/scripts/calibrate.py 2008-10-09 00:21:46 UTC (rev 5185)
+++ pkg/trunk/manip/teleop_robot/scripts/calibrate.py 2008-10-09 00:53:12 UTC (rev 5186)
@@ -144,3 +144,13 @@
</controller>
''')
+
+calibrate_optically('''
+<controller name="cal_laser_tilt" topic="cal_laser_tilt" type="JointCalibrationControllerNode">
+ <calibrate joint="tilt_laser_mount_joint"
+ actuator="tilt_laser_motor"
+ transmission="tilt_laser_mount_trans"
+ velocity="-0.6" />
+ <pid p=".25" i="0.1" d="0" iClamp="1.0" />
+</controller>
+''')
Modified: pkg/trunk/robot_descriptions/wg_robot_description/one_armed_bandit/one_armed_bandit.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/one_armed_bandit/one_armed_bandit.xml 2008-10-09 00:21:46 UTC (rev 5185)
+++ pkg/trunk/robot_descriptions/wg_robot_description/one_armed_bandit/one_armed_bandit.xml 2008-10-09 00:53:12 UTC (rev 5186)
@@ -48,7 +48,7 @@
<joint name="torso_joint" type="fixed" />
<link name="torso">
<parent name="base" />
- <origin xyz="0 0 0.5" rpy="0 0 0" />
+ <origin xyz="0 0 1.0414" rpy="0 0 0" />
<joint name="torso_joint" />
<inertial>
@@ -63,7 +63,7 @@
<elem key="material">Gazebo/Red</elem>
</map>
<geometry name="pr2_base_mesh_file">
- <mesh scale="1 1 0.01" />
+ <mesh filename="torso" />
</geometry>
</visual>
@@ -75,9 +75,11 @@
</collision>
</link>
- <pr2_upperarm suffix="right" reflect="-1" parent="torso" />
+ <pr2_upperarm suffix="right" reflect="-1" parent="torso">
+ <origin xyz="0 -0.188 0" rpy="0 0 0" />
+ </pr2_upperarm>
<tilting_hokuyo name="tilt_laser" parent="torso">
- <origin xyz="0.1 0.1 1.15" rpy="0 0 0" />
+ <origin xyz="0.0635 0.01905 0.2413" rpy="0 0 0" />
</tilting_hokuyo>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/arm_defs.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/arm_defs.xml 2008-10-09 00:21:46 UTC (rev 5185)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/arm_defs.xml 2008-10-09 00:53:12 UTC (rev 5186)
@@ -154,7 +154,7 @@
- <macro name="pr2_upperarm" params="suffix parent reflect">
+ <macro name="pr2_upperarm" params="suffix parent reflect *origin">
<!-- Shoulder pan -->
@@ -169,7 +169,7 @@
<link name="shoulder_pan_${suffix}">
<parent name="${parent}" />
- <origin xyz="0 ${reflect*0.188} 0" rpy="0 0 0" />
+ <insert_block name="origin" />
<joint name="shoulder_pan_${suffix}_joint" />
<inertial>
<mass value="16.29553" />
@@ -352,8 +352,10 @@
</macro>
- <macro name="pr2_arm" params="suffix parent reflect">
- <pr2_upperarm suffix="${suffix}" reflect="${reflect}" parent="${parent}" />
+ <macro name="pr2_arm" params="suffix parent reflect *origin">
+ <pr2_upperarm suffix="${suffix}" reflect="${reflect}" parent="${parent}">
+ <insert_block name="origin" />
+ </pr2_upperarm>
<pr2_forearm suffix="${suffix}" reflect="${reflect}" parent="elbow_flex_${suffix}" />
</macro>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/head_defs.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/head_defs.xml 2008-10-09 00:21:46 UTC (rev 5185)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/head_defs.xml 2008-10-09 00:53:12 UTC (rev 5186)
@@ -9,7 +9,7 @@
<axis xyz="0 1 0" />
<anchor xyz="0 0 0" />
<limit min="-0.785" max="1.48" effort="0.5292" velocity="1256.0" />
- <calibration reference_position="-0.35" values="0 0" />
+ <calibration reference_position="-0.28" values="0 0" />
</joint>
<link name="${name}_mount">
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|