|
From: <stu...@us...> - 2008-10-09 00:21:56
|
Revision: 5185
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=5185&view=rev
Author: stuglaser
Date: 2008-10-09 00:21:46 +0000 (Thu, 09 Oct 2008)
Log Message:
-----------
Reprogrammed motor boards on the one-armed bandit, so the config and calibration code needed updating.
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
Modified: pkg/trunk/manip/teleop_robot/scripts/calibrate.py
===================================================================
--- pkg/trunk/manip/teleop_robot/scripts/calibrate.py 2008-10-09 00:03:12 UTC (rev 5184)
+++ pkg/trunk/manip/teleop_robot/scripts/calibrate.py 2008-10-09 00:21:46 UTC (rev 5185)
@@ -36,6 +36,7 @@
import rostools
import copy
+import threading
# Loads interface with the robot.
rostools.update_path('teleop_robot')
@@ -93,10 +94,19 @@
print "Calibrated"
+class FunThread(threading.Thread):
+ def __init__(self, fun, *args):
+ self.fun = fun
+ self.start()
+
+ def run():
+ self.fun(*args)
+
+
calibrate_optically('''
<controller name="cal_shoulder_pan" topic="cal_shoulder_pan" type="JointCalibrationControllerNode">
<calibrate joint="shoulder_pan_right_joint"
- actuator="shoulder_pan_right_act"
+ actuator="shoulder_pan_right_motor"
transmission="shoulder_pan_right_trans"
velocity="0.6" />
<pid p="7" i="0.5" d="0" iClamp="1.0" />
@@ -106,8 +116,8 @@
calibrate_optically('''
<controller name="cal_shoulder_pitch" topic="cal_shoulder_pitch" type="JointCalibrationControllerNode">
<calibrate joint="shoulder_pitch_right_joint"
- actuator="shoulder_lift_right_act"
- transmission="shoulder_lift_right_trans"
+ actuator="shoulder_pitch_right_motor"
+ transmission="shoulder_pitch_right_trans"
velocity="0.6" />
<pid p="7" i="0.5" d="0" iClamp="1.0" />
</controller>
@@ -116,7 +126,7 @@
calibrate_blindly('''
<controller name="upperarm_calibration" topic="upperarm_calibration" type="JointBlindCalibrationControllerNode">
<calibrate joint="upperarm_roll_right_joint"
- actuator="upperarm_roll_right_act"
+ actuator="upperarm_roll_right_motor"
transmission="upperarm_roll_right_trans"
velocity="0.9" />
<pid p="5" i="0.5" d="0" iClamp="1.0" />
@@ -126,9 +136,9 @@
calibrate_blindly('''
<controller name="cal_elbow" topic="cal_elbow" type="JointBlindCalibrationControllerNode">
- <calibrate joint="elbow_right_joint"
- actuator="elbow_right_act"
- transmission="elbow_right_trans"
+ <calibrate joint="elbow_flex_right_joint"
+ actuator="elbow_flex_right_motor"
+ transmission="elbow_flex_right_trans"
velocity="0.8" />
<pid p="5" i="0.5" 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:03:12 UTC (rev 5184)
+++ pkg/trunk/robot_descriptions/wg_robot_description/one_armed_bandit/one_armed_bandit.xml 2008-10-09 00:21:46 UTC (rev 5185)
@@ -17,12 +17,40 @@
<include filename="../pr2/head_defs.xml" />
<joint name="base_joint" type="planar" />
-
- <link name="torso">
+ <link name="base">
<parent name="world" />
- <origin xyz="0 0 0.05" rpy="0 0 0" />
<joint name="base_joint" />
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <inertial>
+ <mass value="1000" />
+ <com xyz=" 0 0 0 " />
+ <inertia ixx="10000" ixy="0" ixz="0" iyy="10000" iyz="0" izz="10000" />
+ </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="pr2_base_mesh_file">
+ <mesh scale="1 1 0.01" />
+ </geometry>
+ </visual>
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0.0 0.0 0.0 " />
+ <geometry name="base_collision_geom">
+ <box size="1 1 0.01" />
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="torso_joint" type="fixed" />
+ <link name="torso">
+ <parent name="base" />
+ <origin xyz="0 0 0.5" rpy="0 0 0" />
+ <joint name="torso_joint" />
+
<inertial>
<mass value="1000" />
<com xyz="0 0 0" />
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:03:12 UTC (rev 5184)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/arm_defs.xml 2008-10-09 00:21:46 UTC (rev 5185)
@@ -242,7 +242,7 @@
</link>
<transmission type="SimpleTransmission" name="shoulder_pitch_${suffix}_trans">
- <actuator name="shoulder_pitch_${suffix}_act" />
+ <actuator name="shoulder_pitch_${suffix}_motor" />
<joint name="shoulder_pitch_${suffix}_joint" />
<mechanicalReduction>57.36</mechanicalReduction>
</transmission>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|