|
From: <wa...@us...> - 2009-06-29 22:18:47
|
Revision: 17904
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17904&view=rev
Author: wattsk
Date: 2009-06-29 22:17:36 +0000 (Mon, 29 Jun 2009)
Log Message:
-----------
Changed name of calibrate_arms to calibrate_pr2 and changed sequence. Renamed calibration controllers in pr2_default_controllers for each robot
Modified Paths:
--------------
pkg/trunk/stacks/pr2/pr2_alpha/pre.launch
pkg/trunk/stacks/pr2/pr2_alpha/pre.machine
pkg/trunk/stacks/pr2/pr2_alpha/pre_ethercat_reset.launch
pkg/trunk/stacks/pr2/pr2_alpha/prf_ethercat_reset.launch
pkg/trunk/stacks/pr2/pr2_alpha/prg_ethercat_reset.launch
pkg/trunk/stacks/pr2/pr2_alpha/test/alpha_full_connection.xml
Added Paths:
-----------
pkg/trunk/stacks/mechanism/mechanism_bringup/scripts/calibrate_pr2.py
pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/pr2_calibration_controller.xml
pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/pre_calibration_controller.xml
pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/prf_calibration_controller.xml
pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/prg_calibration_controller.xml
Removed Paths:
-------------
pkg/trunk/stacks/mechanism/mechanism_bringup/scripts/calibrate_arms.py
pkg/trunk/stacks/pr2/pr2_alpha/calibrate.launch
pkg/trunk/stacks/pr2/pr2_alpha/calibrate_pre.launch
pkg/trunk/stacks/pr2/pr2_alpha/calibrate_prf.launch
pkg/trunk/stacks/pr2/pr2_alpha/calibrate_prg.launch
pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/full_calibration_controller.xml
pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/full_calibration_controller_pre.xml
pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/full_calibration_controller_prf.xml
pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/full_calibration_controller_prg.xml
Deleted: pkg/trunk/stacks/mechanism/mechanism_bringup/scripts/calibrate_arms.py
===================================================================
--- pkg/trunk/stacks/mechanism/mechanism_bringup/scripts/calibrate_arms.py 2009-06-29 22:07:15 UTC (rev 17903)
+++ pkg/trunk/stacks/mechanism/mechanism_bringup/scripts/calibrate_arms.py 2009-06-29 22:17:36 UTC (rev 17904)
@@ -1,277 +0,0 @@
-#!/usr/bin/python
-# Software License Agreement (BSD License)
-#
-# Copyright (c) 2008, Willow Garage, Inc.
-# All rights reserved.
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# * Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# * Redistributions in binary form must reproduce the above
-# copyright notice, this list of conditions and the following
-# disclaimer in the documentation and/or other materials provided
-# with the distribution.
-# * Neither the name of the Willow Garage nor the names of its
-# contributors may be used to endorse or promote products derived
-# from this software without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
-# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
-# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-
-# Author: Kevin Watts
-
-# Calibrate the arm sequentially
-# Wrist -> Elbow roll -> Elbow flex -> Upperarm Roll ->
-# Shoulder Lift -> Shoulder Pan
-
-import roslib
-import copy
-import threading
-import sys, os
-from time import sleep
-
-# Loads interface with the robot.
-roslib.load_manifest('mechanism_bringup')
-import rospy
-from std_msgs.msg import *
-import std_srvs.srv
-from robot_srvs.srv import *
-
-from robot_mechanism_controllers.srv import *
-from robot_mechanism_controllers import controllers
-
-
-class SendMessageOnSubscribe(rospy.SubscribeListener):
- def __init__(self, msg):
- self.msg = msg
- print "Waiting for subscriber..."
-
- def peer_subscribe(self, topic_name, topic_publish, peer_publish):
- peer_publish(self.msg)
- sleep(0.1)
- # TODO: change this line when flushing messages is implemented
- # rospy.signal_shutdown("Done")
- # sys.exit(0)
-
-
-spawn_controller = rospy.ServiceProxy('spawn_controller', SpawnController)
-kill_controller = rospy.ServiceProxy('kill_controller', KillController)
-
-def slurp(filename):
- f = open(filename)
- stuff = f.read()
- f.close()
- return stuff
-
-def calibrate(config):
- #spawn_controller = rospy.ServiceProxy('spawn_controller', SpawnController)
- #kill_controller = rospy.ServiceProxy('kill_controller', KillController)
-
- # Spawns the controllers
- resp = spawn_controller(SpawnControllerRequest(config,1))
-
- # Accumulates the list of spawned controllers
- launched = []
- print "OKs: " + ','.join([str(ok) for ok in resp.ok])
- try:
- for i in range(len(resp.ok)):
- if resp.ok[i] == 0:
- print "Failed: %s" % resp.name[i]
- else:
- launched.append(resp.name[i])
- print "Launched: %s" % ', '.join(launched)
-
- # Sets up callbacks for calibration completion
- waiting_for = launched[:]
- def calibrated(msg, name): # Somewhat not thread-safe
- if name in waiting_for:
- waiting_for.remove(name)
- for name in waiting_for:
- rospy.Subscriber("/%s/calibrated" % name, Empty, calibrated, name)
-
- # Waits until all the controllers have calibrated
- while waiting_for and not rospy.is_shutdown():
- print "Waiting for: %s" % ', '.join(waiting_for)
- sleep(0.5)
- finally:
- # Try to kill controllers several times
- # Make sure they're dead.
- for name in launched:
- for i in range(1,6):
- try:
- kill_controller(name)
- break # Go to next controller if no exception
- except:
- print "Failed to kill controller %s on try %d" % (name, i)
-
-#
-# Functions make xml code for controllers
-#
-def xml_for_cal(name, velocity, p, i, d, iClamp):
- return """
-<controller name="cal_%s" topic="cal_%s" type="JointUDCalibrationControllerNode">
-<calibrate joint="%s_joint" actuator="%s_motor"
-transmission="%s_trans" velocity="%d" />
-<pid p="%d" i="%d" d="%d" iClamp="%d" />
-</controller>""" % (name, name, name, name, name, velocity, p, i, d, iClamp)
-
-def xml_for_hold(name, p, i, d, iClamp):
- return """
-<controller name="%s_controller" type="JointPositionControllerNode">
-<joint name="%s_joint">
-<pid p="%d" i="%d" d="%d" iClamp="%d" />
-</controller>""" % (name, name, p, i, d, iClamp)
-
-def xml_for_wrist(side):
- return """
-<controller name="cal_%s_wrist" type="WristCalibrationControllerNode">
-<calibrate transmission="%s_wrist_trans"
-actuator_l="%s_wrist_l_motor" actuator_r="%s_wrist_r_motor"
-flex_joint="%s_wrist_flex_joint" roll_joint="%s_wrist_roll_joint"
-velocity="1.5" />
-<pid p="4.0" i="0.2" d="0" iClamp="2.0" />
-</controller>""" % (side, side, side, side, side, side)
-
-def hold_joint(name, p, i, d, iClamp, holding):
- # Try to launch 3x
- # If launched, add to list of holding controllers and return true
- for i in range(1,4):
- try:
- resp = spawn_controller(xml_for_hold(name, p, i, d, iClamp))
- if resp.ok[0] != 0:
- holding.append(resp.name[0])
- return True
- except:
- print "Failed to spawn holding controller %s on try %d" % (name, i)
-
- return False
-
-def set_controller(controller, command):
- # try:
- #rospy.init_node('control', anonymous = True)
- #finally:
- pub = rospy.Publisher('/' + controller + '/set_command', Float64,
- SendMessageOnSubscribe(Float64(command)))
-
-def calibrate_imu():
- print "Calibrating IMU"
- try:
- rospy.wait_for_service('/imu/calibrate', 5)
- calibrate = rospy.ServiceProxy('/imu/calibrate', std_srvs.srv.Empty)
- calibrate(timeout=20) # This should take 10 seconds
- return True
- except:
- print "IMU calibration failed: %s"%sys.exc_info()[0]
- return False
-
-if __name__ == '__main__':
- rospy.wait_for_service('spawn_controller')
- # if rospy.is_shutdown():
- # return
-
- rospy.init_node('calibration', anonymous=True)
-
- holding = [] # Tracks which controllers are holding joints by name
-
- # Calibrate all joints sequentially
- # Hold joints after they're calibrated.
- # Can set desired joint position by using name + /set_command service
- # for joint position controllers
-
- # Wrist and forearm calibrated with forearm_calibrator in arm_defs.xml
-
- imustatus = calibrate_imu()
- if not imustatus:
- print "IMU Calibration failed."
-
- print "Calibrating shoulder pan"
- calibrate(xml_for_cal("r_shoulder_pan", 1.0, 7, 0.5, 0, 1.0))
- hold_joint("r_shoulder_pan", 60, 10, 5, 4, holding)
- set_controller("r_shoulder_pan_controller", float(-0.7))
-
- calibrate(xml_for_cal("l_shoulder_pan", 1.0, 7, 0.5, 0, 1.0))
- hold_joint("l_shoulder_pan", 60, 10, 5, 4, holding)
- set_controller("l_shoulder_pan_controller", float(0.7))
-
- print "Calibrating elbow flex"
- calibrate(xml_for_cal("r_elbow_flex", -1.0, 6, 0.2, 0, 1) + "\n" + xml_for_cal("l_elbow_flex", -1.0, 6, 0.2, 0, 1))
- hold_joint("r_elbow_flex", 100, 20, 10, 2, holding)
- hold_joint("l_elbow_flex", 100, 20, 10, 2, holding)
-
- set_controller("r_elbow_flex_controller", float(3.0))
- set_controller("l_elbow_flex_controller", float(3.0))
-
- print "Calibrating right upperarm roll"
- upperarm_roll_name = "r_upper_arm_roll"
- calibrate(xml_for_cal(upperarm_roll_name, 1.0, 6, 0.2, 0, 2))
- hold_joint(upperarm_roll_name, 25, 2, 1.0, 1.0, holding)
- set_controller("r_upper_arm_roll_controller", float(0.0))
-
- print "Calibrating left upperarm roll"
- upperarm_roll_name = "l_upper_arm_roll"
- calibrate(xml_for_cal(upperarm_roll_name, 1.0, 6, 0.2, 0, 2))
- hold_joint(upperarm_roll_name, 25, 2, 1.0, 1.0, holding)
- set_controller("l_upper_arm_roll_controller", float(0.0))
-
- print "Calibrating shoulder lift"
- shoulder_lift_name = "r_shoulder_lift"
- calibrate(xml_for_cal("r_shoulder_lift", -1.0, 9, 1.0, 0, 6) + "\n" + xml_for_cal("l_shoulder_lift", -1.0, 9, 1.0, 0, 6))
-
- hold_joint("r_shoulder_lift", 60, 10, 5, 4, holding)
- hold_joint("l_shoulder_lift", 60, 10, 5, 4, holding)
-
- set_controller("r_shoulder_lift_controller", float(3.0))
- set_controller("l_shoulder_lift_controller", float(3.0))
-
-
-
- sleep(0.5)
- print "Calibrating rest of robot"
-
- # Calibrate other controllers given
- xml = ''
-
- if len(sys.argv) > 1:
- xacro_cmd = roslib.packages.get_pkg_dir('xacro', True) + '/xacro.py'
- xmls = [os.popen2(xacro_cmd + " %s" % f)[1].read() for f in rospy.myargv()[1:]]
-
- # Poor man's xml splicer
- for i in range(len(xmls) - 1):
- xmls[i] = xmls[i].replace('</controllers>', '')
- xmls[i+1] = xmls[i+1].replace('<controllers>', '')
- xml = "\n".join(xmls)
- else:
- print "Reading from stdin..."
- xml = sys.stdin.read()
-
- try:
- calibrate(xml)
- finally:
- # Kill all holding controllers
- for name in holding:
- for i in range(1,6):
- try:
- kill_controller(name)
- break # Go to next controller if no exception
- except:
- print "Failed to kill controller %s on try %d" % (name, i)
-
- if not imustatus:
- print "Mechanism calibration complete, but IMU calibration failed."
- sys.exit(2)
-
- print "Calibration complete"
Copied: pkg/trunk/stacks/mechanism/mechanism_bringup/scripts/calibrate_pr2.py (from rev 17893, pkg/trunk/stacks/mechanism/mechanism_bringup/scripts/calibrate_arms.py)
===================================================================
--- pkg/trunk/stacks/mechanism/mechanism_bringup/scripts/calibrate_pr2.py (rev 0)
+++ pkg/trunk/stacks/mechanism/mechanism_bringup/scripts/calibrate_pr2.py 2009-06-29 22:17:36 UTC (rev 17904)
@@ -0,0 +1,266 @@
+#!/usr/bin/python
+# Software License Agreement (BSD License)
+#
+# Copyright (c) 2008, Willow Garage, Inc.
+# All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# * Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# * Redistributions in binary form must reproduce the above
+# copyright notice, this list of conditions and the following
+# disclaimer in the documentation and/or other materials provided
+# with the distribution.
+# * Neither the name of the Willow Garage nor the names of its
+# contributors may be used to endorse or promote products derived
+# from this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+
+# Author: Kevin Watts
+
+# Calibrates the PR-2 in a safe sequence
+
+import roslib
+import copy
+import threading
+import sys, os
+from time import sleep
+
+# Loads interface with the robot.
+roslib.load_manifest('mechanism_bringup')
+import rospy
+from std_msgs.msg import *
+from robot_srvs.srv import *
+
+from robot_mechanism_controllers.srv import *
+from robot_mechanism_controllers import controllers
+
+
+class SendMessageOnSubscribe(rospy.SubscribeListener):
+ def __init__(self, msg):
+ self.msg = msg
+ print "Waiting for subscriber..."
+
+ def peer_subscribe(self, topic_name, topic_publish, peer_publish):
+ peer_publish(self.msg)
+ sleep(0.1)
+ # TODO: change this line when flushing messages is implemented
+ # rospy.signal_shutdown("Done")
+ # sys.exit(0)
+
+
+spawn_controller = rospy.ServiceProxy('spawn_controller', SpawnController)
+kill_controller = rospy.ServiceProxy('kill_controller', KillController)
+
+def slurp(filename):
+ f = open(filename)
+ stuff = f.read()
+ f.close()
+ return stuff
+
+def calibrate(config):
+ # Spawns the controllers
+ resp = spawn_controller(SpawnControllerRequest(config,1))
+
+ # Accumulates the list of spawned controllers
+ launched = []
+ print "OKs: " + ','.join([str(ok) for ok in resp.ok])
+ try:
+ for i in range(len(resp.ok)):
+ if resp.ok[i] == 0:
+ print "Failed: %s" % resp.name[i]
+ else:
+ launched.append(resp.name[i])
+ print "Launched: %s" % ', '.join(launched)
+
+ # Sets up callbacks for calibration completion
+ waiting_for = launched[:]
+ def calibrated(msg, name): # Somewhat not thread-safe
+ if name in waiting_for:
+ waiting_for.remove(name)
+ for name in waiting_for:
+ rospy.Subscriber("%s/calibrated" % name, Empty, calibrated, name)
+
+ # Waits until all the controllers have calibrated
+ while waiting_for and not rospy.is_shutdown():
+ print "Waiting for: %s" % ', '.join(waiting_for)
+ sleep(0.5)
+ finally:
+ # Try to kill controllers several times
+ # Make sure they're dead.
+ for name in launched:
+ for i in range(1,6):
+ try:
+ kill_controller(name)
+ break # Go to next controller if no exception
+ except:
+ print "Failed to kill controller %s on try %d" % (name, i)
+
+#
+# Functions make xml code for controllers
+#
+def xml_for_cal(name, velocity, p, i, d, iClamp):
+ return """
+<controller name="cal_%s" topic="cal_%s" type="JointUDCalibrationControllerNode">
+<calibrate joint="%s_joint" actuator="%s_motor"
+transmission="%s_trans" velocity="%d" />
+<pid p="%d" i="%d" d="%d" iClamp="%d" />
+</controller>""" % (name, name, name, name, name, velocity, p, i, d, iClamp)
+
+def xml_for_hold(name, p, i, d, iClamp):
+ return """
+<controller name="%s_controller" type="JointPositionControllerNode">
+<joint name="%s_joint">
+<pid p="%d" i="%d" d="%d" iClamp="%d" />
+</controller>""" % (name, name, p, i, d, iClamp)
+
+def xml_for_wrist(side):
+ return """
+<controller name="cal_%s_wrist" type="WristCalibrationControllerNode">
+<calibrate transmission="%s_wrist_trans"
+actuator_l="%s_wrist_l_motor" actuator_r="%s_wrist_r_motor"
+flex_joint="%s_wrist_flex_joint" roll_joint="%s_wrist_roll_joint"
+velocity="1.5" />
+<pid p="4.0" i="0.2" d="0" iClamp="2.0" />
+</controller>""" % (side, side, side, side, side, side)
+
+def hold_joint(name, p, i, d, iClamp, holding):
+ # Try to launch 3x
+ # If launched, add to list of holding controllers and return true
+ for i in range(1,4):
+ try:
+ resp = spawn_controller(xml_for_hold(name, p, i, d, iClamp), 1)
+ if resp.ok[0] != 0:
+ holding.append(resp.name[0])
+ return True
+ except:
+ rospy.logerr("Failed to spawn holding controller %s on try %d" % (name, i))
+
+ return False
+
+def set_controller(controller, command):
+ pub = rospy.Publisher(controller + '/set_command', Float64,
+ SendMessageOnSubscribe(Float64(command)))
+
+def calibrate_imu():
+ rospy.logout("Calibrating IMU")
+ try:
+ rospy.wait_for_service('imu/calibrate', 5)
+ calibrate = rospy.ServiceProxy('imu/calibrate', std_srvs.srv.Empty)
+ calibrate(timeout=20) # This should take 10 seconds
+ return True
+ except:
+ rospy.logout("IMU calibration failed: %s"%sys.exc_info()[0])
+ return False
+
+if __name__ == '__main__':
+ rospy.wait_for_service('spawn_controller')
+
+ rospy.init_node('calibration', anonymous=True)
+
+ holding = [] # Tracks which controllers are holding joints by name
+
+ # Calibrate all joints sequentially
+ # Hold joints after they're calibrated.
+ # Can set desired joint position by using name + /set_command service
+ # for joint position controllers
+
+ imustatus = calibrate_imu()
+ if not imustatus:
+ rospy.logerr("IMU Calibration failed.")
+
+ # Check sign on torso lift controller
+ calibrate(xml_for_cal("torso_lift", -10, 2000000, 0, 10000, 12000))
+ hold_joint("torso_lift", 1000000, 0.0, 10000, 1000000, holding)
+ set_controller("torso_lift_controller", float(0.08))
+ sleep(0.5)
+
+ calibrate(xml_for_cal("r_shoulder_pan", 1.0, 7, 0.5, 0, 1.0))
+ hold_joint("r_shoulder_pan", 60, 10, 5, 4, holding)
+ set_controller("r_shoulder_pan_controller", float(-0.7))
+
+ calibrate(xml_for_cal("l_shoulder_pan", 1.0, 7, 0.5, 0, 1.0))
+ hold_joint("l_shoulder_pan", 60, 10, 5, 4, holding)
+ set_controller("l_shoulder_pan_controller", float(0.7))
+
+ calibrate(xml_for_cal("r_elbow_flex", -1.0, 6, 0.2, 0, 1) + "\n" + xml_for_cal("l_elbow_flex", -1.0, 6, 0.2, 0, 1))
+ hold_joint("r_elbow_flex", 100, 20, 10, 2, holding)
+ hold_joint("l_elbow_flex", 100, 20, 10, 2, holding)
+
+ set_controller("r_elbow_flex_controller", float(-2.0))
+ set_controller("l_elbow_flex_controller", float(-2.0))
+
+ upperarm_roll_name = "r_upper_arm_roll"
+ calibrate(xml_for_cal(upperarm_roll_name, 1.0, 6, 0.2, 0, 2))
+ hold_joint(upperarm_roll_name, 25, 2, 1.0, 1.0, holding)
+ set_controller("r_upper_arm_roll_controller", float(0.0))
+
+ upperarm_roll_name = "l_upper_arm_roll"
+ calibrate(xml_for_cal(upperarm_roll_name, 1.0, 6, 0.2, 0, 2))
+ hold_joint(upperarm_roll_name, 25, 2, 1.0, 1.0, holding)
+ set_controller("l_upper_arm_roll_controller", float(0.0))
+
+ shoulder_lift_name = "r_shoulder_lift"
+ calibrate(xml_for_cal("r_shoulder_lift", -1.0, 9, 1.0, 0, 6) + "\n" + xml_for_cal("l_shoulder_lift", -1.0, 9, 1.0, 0, 6))
+
+ hold_joint("r_shoulder_lift", 60, 10, 5, 4, holding)
+ hold_joint("l_shoulder_lift", 60, 10, 5, 4, holding)
+
+ set_controller("r_shoulder_lift_controller", float(1.0))
+ set_controller("l_shoulder_lift_controller", float(1.0))
+
+ rospy.logerr('Setting torso lift controller')
+ torso_pub = rospy.Publisher('torso_lift_controller/set_command', Float64)
+ torso_pub.publish(Float64(float(0.0)))
+ sleep(1.5)
+
+ # Calibrate other controllers given
+ xml = ''
+
+ if len(sys.argv) > 1:
+ xacro_cmd = roslib.packages.get_pkg_dir('xacro', True) + '/xacro.py'
+
+ xmls = [os.popen2(xacro_cmd + " %s" % f)[1].read() for f in rospy.myargv()[1:]]
+
+ # Poor man's xml splicer
+ for i in range(len(xmls) - 1):
+ xmls[i] = xmls[i].replace('</controllers>', '')
+ xmls[i+1] = xmls[i+1].replace('<controllers>', '')
+ xml = "\n".join(xmls)
+ else:
+ print "Reading from stdin..."
+ xml = sys.stdin.read()
+
+ try:
+ calibrate(xml)
+ finally:
+ # Kill all holding controllers
+ for name in holding:
+ for i in range(1,6):
+ try:
+ kill_controller(name)
+ break # Go to next controller if no exception
+ except:
+ rospy.logerr("Failed to kill controller %s on try %d" % (name, i))
+
+ if not imustatus:
+ print "Mechanism calibration complete, but IMU calibration failed."
+ sys.exit(2)
+
+ rospy.logout("Calibration complete")
Deleted: pkg/trunk/stacks/pr2/pr2_alpha/calibrate.launch
===================================================================
--- pkg/trunk/stacks/pr2/pr2_alpha/calibrate.launch 2009-06-29 22:07:15 UTC (rev 17903)
+++ pkg/trunk/stacks/pr2/pr2_alpha/calibrate.launch 2009-06-29 22:17:36 UTC (rev 17904)
@@ -1,5 +0,0 @@
-<launch>
- <node pkg="mechanism_bringup" type="calibrate.py"
- args="$(find pr2_default_controllers)/calibration_controllers/full_calibration_controller.xml"
- output="screen" />
-</launch>
Deleted: pkg/trunk/stacks/pr2/pr2_alpha/calibrate_pre.launch
===================================================================
--- pkg/trunk/stacks/pr2/pr2_alpha/calibrate_pre.launch 2009-06-29 22:07:15 UTC (rev 17903)
+++ pkg/trunk/stacks/pr2/pr2_alpha/calibrate_pre.launch 2009-06-29 22:17:36 UTC (rev 17904)
@@ -1,6 +0,0 @@
-<launch>
-<!-- Calibrates both arms -->
- <node pkg="mechanism_bringup" type="calibrate_arms.py"
- args="$(find pr2_default_controllers)/calibration_controllers/full_calibration_controller_pre.xml"
- output="screen" />
-</launch>
Deleted: pkg/trunk/stacks/pr2/pr2_alpha/calibrate_prf.launch
===================================================================
--- pkg/trunk/stacks/pr2/pr2_alpha/calibrate_prf.launch 2009-06-29 22:07:15 UTC (rev 17903)
+++ pkg/trunk/stacks/pr2/pr2_alpha/calibrate_prf.launch 2009-06-29 22:17:36 UTC (rev 17904)
@@ -1,6 +0,0 @@
-<launch>
-<!-- Calibrates both arms -->
- <node pkg="mechanism_bringup" type="calibrate_arms.py"
- args="$(find pr2_default_controllers)/calibration_controllers/full_calibration_controller_prf.xml"
- output="screen" />
-</launch>
\ No newline at end of file
Deleted: pkg/trunk/stacks/pr2/pr2_alpha/calibrate_prg.launch
===================================================================
--- pkg/trunk/stacks/pr2/pr2_alpha/calibrate_prg.launch 2009-06-29 22:07:15 UTC (rev 17903)
+++ pkg/trunk/stacks/pr2/pr2_alpha/calibrate_prg.launch 2009-06-29 22:17:36 UTC (rev 17904)
@@ -1,6 +0,0 @@
-<launch>
-<!-- Calibrates both arms -->
- <node pkg="mechanism_bringup" type="calibrate_arms.py"
- args="$(find pr2_default_controllers)/calibration_controllers/full_calibration_controller_prg.xml"
- output="screen" />
-</launch>
\ No newline at end of file
Modified: pkg/trunk/stacks/pr2/pr2_alpha/pre.launch
===================================================================
--- pkg/trunk/stacks/pr2/pr2_alpha/pre.launch 2009-06-29 22:07:15 UTC (rev 17903)
+++ pkg/trunk/stacks/pr2/pr2_alpha/pre.launch 2009-06-29 22:17:36 UTC (rev 17904)
@@ -5,10 +5,10 @@
<!-- Joystick -->
<param name="joy/deadzone" value="5000"/>
- <node machine="four" pkg="joy" type="joy" respawn="true"/>
+ <node machine="two" pkg="joy" type="joy" respawn="true"/>
<!-- Power Board Control Node -->
- <node pkg="pr2_power_board" type="power_node" respawn="true"/>
+ <node machine="two" pkg="pr2_power_board" type="power_node" respawn="true"/>
<!-- Robot state publisher -->
<node machine="two" pkg="robot_state_publisher" type="state_publisher" name="robot_state_publisher">
@@ -18,6 +18,7 @@
<!-- Battery Monitor -->
<node machine="two" pkg="ocean_battery_driver" type="monitor" respawn="true"/>
+
<!-- Battery Assertions -->
<include file="$(find ocean_battery_driver)/expected_batteries.launch"/>
@@ -30,7 +31,7 @@
</node>
<!-- Tilt Laser -->
- <node machine="three" pkg="hokuyo_node" type="hokuyo_node" name="tilt_hokuyo_node" args="scan:=tilt_scan">
+ <node machine="realtime" pkg="hokuyo_node" type="hokuyo_node" name="tilt_hokuyo_node" args="scan:=tilt_scan">
<param name="port" type="string" value="/dev/ttyACM0" />
<param name="frameid" type="string" value="laser_tilt_link" />
<param name="min_ang_degrees" type="double" value="-80.0" />
@@ -45,28 +46,30 @@
<param name="imu/autostart" type="bool" value="true" />
<param name="imu/frameid" type="string" value="imu" />
<param name="imu/autocalibrate" type="bool" value="false" />
- <node machine="four" pkg="imu_node" type="imu_node" output="screen"/>
+ <node machine="realtime" pkg="imu_node" type="imu_node" output="screen"/>
-<!-- Videre Stereo cam -->
+<!-- Videre Stereo cam
<include file="$(find pr2_alpha)/stereo.launch" />
-
-<!-- Sound -->
+-->
+<!-- Sound
<node pkg="sound_play" type="soundplay_node.py" machine="three" />
+-->
<!-- Runtime Diagnostics Logging -->
<node pkg="rosrecord" type="rosrecord" args="-f /hwlog/pre_runtime_automatic /diagnostics" />
-<!-- NTP monitoring script Warns to console if sync error -->
+<!-- NTP monitoring script Warns to console if sync error
<node pkg="runtime_monitor" type="ntp_monitor.py" args="pre2" machine="realtime"/>
<node pkg="runtime_monitor" type="ntp_monitor.py" args="fw1 7000" machine="two"/>
- <node pkg="runtime_monitor" type="ntp_monitor.py" args="pre2" machine="three"/>
- <node pkg="runtime_monitor" type="ntp_monitor.py" args="pre2" machine="four"/>
+-->
-<!-- Disk usage monitoring script Warns to console if disk full -->
- <node pkg="pr2_computer_monitor" type="disk_usage.py" args="$(optenv HOME /home)" machine="realtime"/>
- <node pkg="pr2_computer_monitor" type="disk_usage.py" args="$(optenv HOME /home)" machine="two"/>
- <node pkg="pr2_computer_monitor" type="disk_usage.py" args="$(optenv HOME /home)" machine="three"/>
- <node pkg="pr2_computer_monitor" type="disk_usage.py" args="$(optenv HOME /home)" machine="four"/>
+ <!-- Disk usage monitoring script Warns to console if disk full -->
+ <node pkg="pr2_computer_monitor" type="hd_monitor.py" args="$(optenv HOME /home) /dev/sda" machine="realtime_root"/>
+ <node pkg="pr2_computer_monitor" type="hd_monitor.py" args="$(optenv HOME /home) /dev/sda /dev/sdb" machine="two_root"/>
+ <!-- Monitor CPU temp, usage -->
+ <node pkg="pr2_computer_monitor" type="cpu_monitor.py" machine="realtime_root" />
+ <node pkg="pr2_computer_monitor" type="cpu_monitor.py" machine="two_root" />
+
</launch>
Modified: pkg/trunk/stacks/pr2/pr2_alpha/pre.machine
===================================================================
--- pkg/trunk/stacks/pr2/pr2_alpha/pre.machine 2009-06-29 22:07:15 UTC (rev 17903)
+++ pkg/trunk/stacks/pr2/pr2_alpha/pre.machine 2009-06-29 22:17:36 UTC (rev 17904)
@@ -1,9 +1,8 @@
<launch>
- <machine name="realtime_root" user="root" address="pre1" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" default="never"/>
+ <machine name="realtime_root" user="root" address="c1" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" default="never"/>
- <machine name="realtime" address="pre1" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
- <machine name="two" address="pre2" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" default="true"/>
- <machine name="three" address="pre3" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
- <machine name="four" address="pre4" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
- <machine name="stereo" address="pre4" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
+ <machine name="realtime" address="c1" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" default="true"/>
+ <machine name="two" address="c2" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
+ <machine name="two_root" user="root" address="c2" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
+ <machine name="stereo" address="c2" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
</launch>
Modified: pkg/trunk/stacks/pr2/pr2_alpha/pre_ethercat_reset.launch
===================================================================
--- pkg/trunk/stacks/pr2/pr2_alpha/pre_ethercat_reset.launch 2009-06-29 22:07:15 UTC (rev 17903)
+++ pkg/trunk/stacks/pr2/pr2_alpha/pre_ethercat_reset.launch 2009-06-29 22:17:36 UTC (rev 17904)
@@ -5,9 +5,9 @@
<include file="$(find pr2_alpha)/pre.machine" />
<!-- pr2_etherCAT -->
- <node machine="realtime_root" pkg="pr2_etherCAT" type="pr2_etherCAT" args="-i eth0 -x /robotdesc/pr2"/>
+ <node machine="realtime_root" pkg="pr2_etherCAT" type="pr2_etherCAT" args="-i ecat0 -x /robotdesc/pr2"/>
-<!-- PR2 Calibration -->
- <include file="$(find pr2_alpha)/calibrate_pre.launch" />
-
+ <node pkg="mechanism_bringup" type="calibrate_pr2.py"
+ args="$(find pr2_default_controllers)/calibration_controllers/pre_calibration_controller.xml"
+ output="screen" />
</launch>
Modified: pkg/trunk/stacks/pr2/pr2_alpha/prf_ethercat_reset.launch
===================================================================
--- pkg/trunk/stacks/pr2/pr2_alpha/prf_ethercat_reset.launch 2009-06-29 22:07:15 UTC (rev 17903)
+++ pkg/trunk/stacks/pr2/pr2_alpha/prf_ethercat_reset.launch 2009-06-29 22:17:36 UTC (rev 17904)
@@ -9,9 +9,10 @@
<include file="$(find pr2_alpha)/prf.machine" />
<!-- pr2_etherCAT -->
- <node machine="realtime_root" pkg="pr2_etherCAT" type="pr2_etherCAT" args="-i eth0 -x /robotdesc/pr2"/>
+ <node machine="realtime_root" pkg="pr2_etherCAT" type="pr2_etherCAT" args="-i eth0 -x robotdesc/pr2"/>
<!-- PR2 Calibration -->
- <include file="$(find pr2_alpha)/calibrate_prf.launch" />
-
+ <node pkg="mechanism_bringup" type="calibrate_pr2.py"
+ args="$(find pr2_default_controllers)/calibration_controllers/prf_calibration_controller.xml"
+ output="screen" />
</launch>
Modified: pkg/trunk/stacks/pr2/pr2_alpha/prg_ethercat_reset.launch
===================================================================
--- pkg/trunk/stacks/pr2/pr2_alpha/prg_ethercat_reset.launch 2009-06-29 22:07:15 UTC (rev 17903)
+++ pkg/trunk/stacks/pr2/pr2_alpha/prg_ethercat_reset.launch 2009-06-29 22:17:36 UTC (rev 17904)
@@ -8,10 +8,11 @@
<include file="$(find pr2_alpha)/prg.machine" />
-<!-- pr2_etherCAT -->
- <node machine="realtime_root" pkg="pr2_etherCAT" type="pr2_etherCAT" args="-i eth0 -x /robotdesc/pr2"/>
+ <!-- pr2_etherCAT -->
+ <node machine="realtime_root" pkg="pr2_etherCAT" type="pr2_etherCAT" args="-i eth0 -x robotdesc/pr2"/>
-<!-- PR2 Calibration -->
- <include file="$(find pr2_alpha)/calibrate_prg.launch" />
-
+ <!-- PR2 Calibration -->
+ <node pkg="mechanism_bringup" type="calibrate_pr2.py"
+ args="$(find pr2_default_controllers)/calibration_controllers/prg_calibration_controller.xml"
+ output="screen" />
</launch>
Modified: pkg/trunk/stacks/pr2/pr2_alpha/test/alpha_full_connection.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_alpha/test/alpha_full_connection.xml 2009-06-29 22:07:15 UTC (rev 17903)
+++ pkg/trunk/stacks/pr2/pr2_alpha/test/alpha_full_connection.xml 2009-06-29 22:17:36 UTC (rev 17904)
@@ -3,7 +3,7 @@
set to the robot's base name (e.g., pre, prf, prg). -->
<launch>
- <include file="$(find pr2_alpha)/test/pre.machine" />
+ <include file="$(find pr2_alpha)/test/alpha.machine" />
<node machine="realtime" pkg="pr2_alpha" type="subpub.py"
args="realtime realtime_root two three four"/>
Deleted: pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/full_calibration_controller.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/full_calibration_controller.xml 2009-06-29 22:07:15 UTC (rev 17903)
+++ pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/full_calibration_controller.xml 2009-06-29 22:17:36 UTC (rev 17904)
@@ -1,24 +0,0 @@
-<controllers>
- <include filename="$(find pr2_defs)/defs/arm_defs.xml" />
- <include filename="$(find pr2_defs)/defs/gripper_defs.xml" />
- <include filename="$(find pr2_defs)/defs/base_defs.xml" />
- <include filename="$(find pr2_defs)/defs/head_defs.xml" />
- <include filename="$(find pr2_defs)/defs/body_defs.xml" />
-
- <upper_arm_calibrator side="r" />
- <forearm_calibrator side="r" />
- <gripper_calibrator side="r" />
-
- <upper_arm_calibrator side="l" />
- <forearm_calibrator side="l" />
- <gripper_calibrator side="l" />
-
- <base_calibrator />
-
- <head_calibrator />
-
- <torso_calibrator />
-
- <tilting_laser_calibrator name="laser_tilt" />
-
-</controllers>
Deleted: pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/full_calibration_controller_pre.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/full_calibration_controller_pre.xml 2009-06-29 22:07:15 UTC (rev 17903)
+++ pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/full_calibration_controller_pre.xml 2009-06-29 22:17:36 UTC (rev 17904)
@@ -1,23 +0,0 @@
-<controllers>
- <include filename="$(find pr2_defs)/defs/arm_defs.xml" />
- <include filename="$(find pr2_defs)/defs/gripper_defs.xml" />
- <include filename="$(find pr2_defs)/defs/base_defs.xml" />
- <include filename="$(find pr2_defs)/defs/head_defs.xml" />
- <include filename="$(find pr2_defs)/defs/body_defs.xml" />
-
- <!-- Arm calibration is done by calibrate_arms.py -->
- <forearm_calibrator side="r" />
- <gripper_calibrator side="r" />
-
- <forearm_calibrator side="l" />
- <gripper_calibrator side="l" />
-
- <!-- New calibrators for Alpha2, IDE hardware -->
- <base_calibrator_alpha2 />
- <!--base_calibrator /--> <!-- New casters are in the shop, have A1's -->
-
- <head_calibrator_alpha2b />
- <tilting_laser_calibrator name="laser_tilt" />
-
- <torso_limit_calibrator />
-</controllers>
Deleted: pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/full_calibration_controller_prf.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/full_calibration_controller_prf.xml 2009-06-29 22:07:15 UTC (rev 17903)
+++ pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/full_calibration_controller_prf.xml 2009-06-29 22:17:36 UTC (rev 17904)
@@ -1,22 +0,0 @@
-<controllers>
- <include filename="$(find pr2_defs)/defs/arm_defs.xml" />
- <include filename="$(find pr2_defs)/defs/gripper_defs.xml" />
- <include filename="$(find pr2_defs)/defs/base_defs.xml" />
- <include filename="$(find pr2_defs)/defs/head_defs.xml" />
- <include filename="$(find pr2_defs)/defs/body_defs.xml" />
-
- <!-- Arm calibration is done by calibrate_arms.py -->
- <forearm_calibrator side="r" />
- <gripper_calibrator side="r" />
-
- <forearm_calibrator side="l" />
- <gripper_calibrator side="l" />
-
- <tilting_laser_calibrator name="laser_tilt" />
-
- <base_calibrator />
-
- <head_calibrator />
-
- <torso_calibrator />
-</controllers>
Deleted: pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/full_calibration_controller_prg.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/full_calibration_controller_prg.xml 2009-06-29 22:07:15 UTC (rev 17903)
+++ pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/full_calibration_controller_prg.xml 2009-06-29 22:17:36 UTC (rev 17904)
@@ -1,22 +0,0 @@
-<controllers>
- <include filename="$(find pr2_defs)/defs/arm_defs.xml" />
- <include filename="$(find pr2_defs)/defs/gripper_defs.xml" />
- <include filename="$(find pr2_defs)/defs/base_defs.xml" />
- <include filename="$(find pr2_defs)/defs/head_defs.xml" />
- <include filename="$(find pr2_defs)/defs/body_defs.xml" />
-
- <!-- Arm calibration is done by calibrate_arms.py -->
- <forearm_calibrator side="r" />
- <gripper_calibrator side="r" />
-
- <forearm_calibrator side="l" />
- <gripper_calibrator side="l" />
-
- <tilting_laser_calibrator name="laser_tilt" />
-
- <base_calibrator />
-
- <head_calibrator />
-
- <torso_calibrator />
-</controllers>
Copied: pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/pr2_calibration_controller.xml (from rev 17804, pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/full_calibration_controller.xml)
===================================================================
--- pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/pr2_calibration_controller.xml (rev 0)
+++ pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/pr2_calibration_controller.xml 2009-06-29 22:17:36 UTC (rev 17904)
@@ -0,0 +1,24 @@
+<controllers>
+ <include filename="$(find pr2_defs)/defs/arm_defs.xml" />
+ <include filename="$(find pr2_defs)/defs/gripper_defs.xml" />
+ <include filename="$(find pr2_defs)/defs/base_defs.xml" />
+ <include filename="$(find pr2_defs)/defs/head_defs.xml" />
+ <include filename="$(find pr2_defs)/defs/body_defs.xml" />
+
+ <upper_arm_calibrator side="r" />
+ <forearm_calibrator side="r" />
+ <gripper_calibrator side="r" />
+
+ <upper_arm_calibrator side="l" />
+ <forearm_calibrator side="l" />
+ <gripper_calibrator side="l" />
+
+ <base_calibrator />
+
+ <head_calibrator />
+
+ <torso_calibrator />
+
+ <tilting_laser_calibrator name="laser_tilt" />
+
+</controllers>
Copied: pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/pre_calibration_controller.xml (from rev 17804, pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/full_calibration_controller_pre.xml)
===================================================================
--- pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/pre_calibration_controller.xml (rev 0)
+++ pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/pre_calibration_controller.xml 2009-06-29 22:17:36 UTC (rev 17904)
@@ -0,0 +1,23 @@
+<controllers>
+ <include filename="$(find pr2_defs)/defs/arm_defs.xml" />
+ <include filename="$(find pr2_defs)/defs/gripper_defs.xml" />
+ <include filename="$(find pr2_defs)/defs/base_defs.xml" />
+ <include filename="$(find pr2_defs)/defs/head_defs.xml" />
+ <include filename="$(find pr2_defs)/defs/body_defs.xml" />
+
+ <!-- Arm calibration is done by calibrate_arms.py -->
+ <forearm_calibrator side="r" />
+ <gripper_calibrator side="r" />
+
+ <forearm_calibrator side="l" />
+ <gripper_calibrator side="l" />
+
+ <!-- New calibrators for Alpha2, IDE hardware -->
+ <base_calibrator_alpha2 />
+ <!--base_calibrator /--> <!-- New casters are in the shop, have A1's -->
+
+ <head_calibrator_alpha2b />
+ <tilting_laser_calibrator name="laser_tilt" />
+
+ <!--torso_limit_calibrator /-->
+</controllers>
Copied: pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/prf_calibration_controller.xml (from rev 17804, pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/full_calibration_controller_prf.xml)
===================================================================
--- pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/prf_calibration_controller.xml (rev 0)
+++ pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/prf_calibration_controller.xml 2009-06-29 22:17:36 UTC (rev 17904)
@@ -0,0 +1,21 @@
+<controllers>
+ <include filename="$(find pr2_defs)/defs/arm_defs.xml" />
+ <include filename="$(find pr2_defs)/defs/gripper_defs.xml" />
+ <include filename="$(find pr2_defs)/defs/base_defs.xml" />
+ <include filename="$(find pr2_defs)/defs/head_defs.xml" />
+ <include filename="$(find pr2_defs)/defs/body_defs.xml" />
+
+ <!-- Arm calibration is done by calibrate_arms.py -->
+ <forearm_calibrator side="r" />
+ <gripper_calibrator side="r" />
+
+ <forearm_calibrator side="l" />
+ <gripper_calibrator side="l" />
+
+ <tilting_laser_calibrator name="laser_tilt" />
+
+ <base_calibrator />
+
+ <head_calibrator />
+
+</controllers>
Copied: pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/prg_calibration_controller.xml (from rev 17804, pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/full_calibration_controller_prg.xml)
===================================================================
--- pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/prg_calibration_controller.xml (rev 0)
+++ pkg/trunk/stacks/pr2/pr2_default_controllers/calibration_controllers/prg_calibration_controller.xml 2009-06-29 22:17:36 UTC (rev 17904)
@@ -0,0 +1,21 @@
+<controllers>
+ <include filename="$(find pr2_defs)/defs/arm_defs.xml" />
+ <include filename="$(find pr2_defs)/defs/gripper_defs.xml" />
+ <include filename="$(find pr2_defs)/defs/base_defs.xml" />
+ <include filename="$(find pr2_defs)/defs/head_defs.xml" />
+ <include filename="$(find pr2_defs)/defs/body_defs.xml" />
+
+ <!-- Arm calibration is done by calibrate_arms.py -->
+ <forearm_calibrator side="r" />
+ <gripper_calibrator side="r" />
+
+ <forearm_calibrator side="l" />
+ <gripper_calibrator side="l" />
+
+ <tilting_laser_calibrator name="laser_tilt" />
+
+ <base_calibrator />
+
+ <head_calibrator />
+
+</controllers>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|