00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 import roslib
00040 roslib.load_manifest('pr2_bringup')
00041 import rospy
00042 import getopt
00043 import yaml
00044 from std_msgs.msg import *
00045 from pr2_mechanism_msgs.srv import LoadController, UnloadController, SwitchController, SwitchControllerRequest
00046 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
00047 from pr2_controllers_msgs.srv import QueryCalibrationState
00048 from std_msgs.msg import Bool
00049 from std_srvs.srv import Empty
00050 from sensor_msgs.msg import *
00051
00052
00053
00054 calibration_params_namespace = "calibration_controllers"
00055 load_controller = rospy.ServiceProxy('pr2_controller_manager/load_controller', LoadController)
00056 unload_controller = rospy.ServiceProxy('pr2_controller_manager/unload_controller', UnloadController)
00057 switch_controller = rospy.ServiceProxy('pr2_controller_manager/switch_controller', SwitchController)
00058
00059 hold_position = {'r_shoulder_pan': -0.7, 'l_shoulder_pan': 0.7, 'r_elbow_flex': -2.0,
00060 'l_elbow_flex': -2.0, 'r_upper_arm_roll': 0.0, 'l_upper_arm_roll': 0.0,
00061 'r_shoulder_lift': 1.0, 'l_shoulder_lift': 1.0}
00062
00063 def get_controller_name(joint_name):
00064 return calibration_params_namespace+"/calibrate/cal_%s" % joint_name
00065
00066 def get_holding_name(joint_name):
00067 return "%s/hold/%s_position_controller" % (calibration_params_namespace, joint_name)
00068
00069 def get_service_name(joint_name):
00070 return '%s/is_calibrated'%get_controller_name(joint_name)
00071
00072 global last_joint_states
00073 last_joint_states = None
00074 def joint_states_cb(msg):
00075 global last_joint_states
00076 last_joint_states = msg
00077 rospy.Subscriber('joint_states', JointState, joint_states_cb)
00078
00079 global motors_halted
00080 motors_halted = None
00081 def motor_state_cb(msg):
00082 global motors_halted
00083 motors_halted = msg.data
00084 rospy.logdebug("motors halted = %d"%motors_halted)
00085 rospy.Subscriber('pr2_etherCAT/motors_halted', Bool, motor_state_cb)
00086
00087 pub_diag = rospy.Publisher('/diagnostics', DiagnosticArray)
00088 def diagnostics(level, msg_short, msg_long):
00089 if level == 0:
00090 rospy.loginfo(msg_long)
00091 elif level == 1:
00092 rospy.logwarn(msg_long)
00093 elif level == 2:
00094 rospy.logerr(msg_long)
00095 d = DiagnosticArray()
00096 d.header.stamp = rospy.Time.now()
00097 ds = DiagnosticStatus()
00098 ds.level = level
00099 ds.message = msg_long
00100 ds.name = msg_short
00101 d.status = [ds]
00102 pub_diag.publish(d)
00103
00104
00105
00106 class HoldingController:
00107 def __init__(self, joint_name):
00108 self.joint_name = joint_name
00109 rospy.logdebug("Loading holding controller: %s" %get_holding_name(joint_name))
00110 resp = load_controller(get_holding_name(joint_name))
00111 if resp.ok:
00112 rospy.logdebug("Starting holding controller for joint %s."%joint_name)
00113 switch_controller([get_holding_name(joint_name)], [], SwitchControllerRequest.STRICT)
00114 self.pub_cmd = rospy.Publisher("%s/command" %get_holding_name(joint_name), Float64, latch=True)
00115 else:
00116 rospy.logerr("Failed to load holding controller for joint %s."%joint_name)
00117 raise Exception('Failure to load holding controller')
00118
00119 def __del__(self):
00120 switch_controller([], [get_holding_name(self.joint_name)], SwitchControllerRequest.STRICT)
00121 unload_controller(get_holding_name(self.joint_name))
00122 self.pub_cmd.unregister()
00123
00124 def hold(self, position):
00125 self.pub_cmd.publish(Float64(position))
00126
00127
00128
00129 class StatusPub:
00130 def __init__(self):
00131 self.pub_status = rospy.Publisher('calibration_status', String)
00132 self.status = {}
00133 self.status['active'] = []
00134 self.status['done'] = []
00135
00136 def publish(self, active=None):
00137 if active:
00138 self.status['active'] = active
00139 else:
00140 self.status['done'].extend(self.status['active'])
00141 self.status['active'] = []
00142
00143 str = "====\n"
00144 str += "Calibrating: %s\n"%", ".join(self.status["active"])
00145 str += "Calibrated: %s\n"%", ".join(self.status["done"])
00146 self.pub_status.publish(str)
00147
00148
00149
00150 class CalibrateParallel:
00151 def __init__(self, joints, status):
00152 self.joints = []
00153 self.hold_controllers = []
00154 self.services = {}
00155 self.status = status
00156
00157
00158 for j in joints:
00159 rospy.logdebug("Loading controller: %s" %get_controller_name(j))
00160 resp = load_controller(get_controller_name(j))
00161 if resp.ok:
00162
00163 rospy.logdebug("Waiting for service: %s" %get_service_name(j))
00164 rospy.wait_for_service(get_service_name(j))
00165 self.services[j] = rospy.ServiceProxy(get_service_name(j), QueryCalibrationState)
00166 self.joints.append(j)
00167 else:
00168 rospy.logerr("Failed to load calibration for joint %s. Skipping this joint"%j)
00169
00170
00171 def __del__(self):
00172
00173 switch_controller([], [get_controller_name(j) for j in self.joints], SwitchControllerRequest.BEST_EFFORT)
00174
00175
00176 for j in self.joints:
00177 unload_controller(get_controller_name(j))
00178
00179 def is_calibrated(self):
00180
00181 for j in self.joints:
00182 if self.services[j]().is_calibrated:
00183 rospy.logdebug("joint %s is already calibrated"%j)
00184 else:
00185 rospy.logdebug("joint %s needs to be calibrated"%j)
00186 return False
00187 return True
00188
00189
00190 def calibrate(self):
00191
00192 rospy.logdebug("Start calibrating joints %s"%self.joints)
00193 switch_controller([get_controller_name(j) for j in self.joints], [], SwitchControllerRequest.STRICT)
00194
00195
00196 self.status.publish(self.joints)
00197 start_time = rospy.Time.now()
00198 while not self.is_calibrated():
00199 if motors_halted and motors_halted == 1:
00200 diagnostics(2, 'Calibration on hold', 'Calibration is on hold because motors are halted. Enable the run-stop')
00201 start_time = rospy.Time.now()
00202 rospy.sleep(1.0)
00203 elif rospy.Time.now() > start_time + rospy.Duration(30.0):
00204 diagnostics(2, 'Calibration stuck', 'Joint %s is taking a long time to calibrate. It might be stuck and need some human help'%self.joints)
00205 rospy.sleep(1.0)
00206 rospy.sleep(0.1)
00207
00208 rospy.logdebug("Stop calibration controllers for joints %s"%self.joints)
00209 switch_controller([], [get_controller_name(j) for j in self.joints], SwitchControllerRequest.BEST_EFFORT)
00210
00211
00212 rospy.logdebug("Loading holding controllers for joints %s"%self.joints)
00213 self.hold_controllers = []
00214 for j in self.joints:
00215 if j in hold_position:
00216 holder = HoldingController(j)
00217 holder.hold(hold_position[j])
00218 self.hold_controllers.append(holder)
00219 self.status.publish()
00220
00221
00222
00223 class CalibrateSequence:
00224 def __init__(self, sequence, status):
00225 self.status = status
00226
00227
00228 self.groups = []
00229 for s in sequence:
00230 self.groups.append(CalibrateParallel(s, status))
00231
00232
00233 def is_calibrated(self):
00234
00235 for g in self.groups:
00236 if not g.is_calibrated():
00237 return False
00238 return True
00239
00240
00241 def calibrate(self):
00242
00243 if self.is_calibrated():
00244 return True
00245
00246
00247 for g in self.groups:
00248 g.calibrate()
00249
00250
00251
00252
00253
00254
00255 def main():
00256 try:
00257 rospy.init_node('calibration', anonymous=True, disable_signals=True)
00258 calibration_start_time = rospy.Time.now()
00259
00260 rospy.wait_for_service('pr2_controller_manager/load_controller')
00261 rospy.wait_for_service('pr2_controller_manager/switch_controller')
00262 rospy.wait_for_service('pr2_controller_manager/unload_controller')
00263
00264
00265
00266 allowed_flags = ['alpha-casters', 'alpha-head', 'alpha2b-head', 'arms=']
00267 opts, args = getopt.gnu_getopt(rospy.myargv(), 'h', allowed_flags)
00268 caster_list = ['caster_fl', 'caster_fr', 'caster_bl', 'caster_br']
00269 head_list = ['head_pan', 'head_tilt']
00270 arms = 'auto'
00271 for o, a in opts:
00272 if o == '-h':
00273 rospy.loginfo("Flags:", ' '.join(['--'+f for f in allowed_flags]))
00274 sys.exit(0)
00275 elif o == '--alpha-casters':
00276 caster_list = ['caster_fl_alpha2', 'caster_fr_alpha2', 'caster_bl_alpha2', 'caster_br_alpha2']
00277 elif o == '--alpha-head':
00278 head_list = ['head_pan_alpha2', 'head_tilt']
00279 elif o == '--alpha2b-head':
00280 head_list = ['head_pan_alpha2', 'head_tilt_alpha2b']
00281 elif o == '--arms':
00282 arms = a
00283
00284 if arms not in ['both', 'none', 'left', 'right', 'auto']:
00285 print 'Arms must be "both", "none", "left", "right", or "auto"'
00286 sys.exit(1)
00287
00288
00289 rospy.loginfo("Loading controller configuration on parameter server...")
00290 pr2_controller_configuration_dir = roslib.packages.get_pkg_dir('pr2_controller_configuration')
00291 calibration_yaml = '%s/pr2_calibration_controllers.yaml' % pr2_controller_configuration_dir
00292 hold_yaml = '%s/pr2_joint_position_controllers.yaml' % pr2_controller_configuration_dir
00293 if len(args) < 3:
00294 rospy.loginfo("No yaml files specified for calibration and holding controllers, using defaults")
00295 else:
00296 calibration_yaml = args[1]
00297 hold_yaml = args[2]
00298 rospy.set_param(calibration_params_namespace+"/calibrate", yaml.load(open(calibration_yaml)))
00299 rospy.set_param(calibration_params_namespace+"/hold", yaml.load(open(hold_yaml)))
00300
00301
00302 imustatus = True
00303 joints_status = False
00304 pub_calibrated = rospy.Publisher('calibrated', Bool, latch=True)
00305 pub_calibrated.publish(False)
00306 status = StatusPub()
00307
00308
00309 if arms == 'auto':
00310 started_waiting = rospy.get_rostime()
00311 global last_joint_states
00312 while rospy.get_rostime() <= started_waiting + rospy.Duration(50.0):
00313 if last_joint_states:
00314 break
00315 js = last_joint_states
00316 if not js:
00317 rospy.logwarn('Could not do auto arm selection because no joint state was received')
00318 arms = 'both'
00319 else:
00320 if 'r_shoulder_pan_joint' in js.name and 'l_shoulder_pan_joint' in js.name:
00321 arms = 'both'
00322 elif 'r_shoulder_pan_joint' in js.name:
00323 arms = 'right'
00324 elif 'l_shoulder_pan_joint' in js.name:
00325 arms = 'left'
00326 else:
00327 arms = 'none'
00328 rospy.loginfo("Arm selection was set to \"auto\". Chose to calibrate using \"%s\"" % arms)
00329
00330
00331 torso = CalibrateSequence([['torso_lift']], status)
00332 gripper_list = []
00333 arm_list = []
00334 if arms == 'both':
00335 arm_list = [['r_shoulder_pan', 'l_shoulder_pan'], ['r_elbow_flex', 'l_elbow_flex'],
00336 ['r_upper_arm_roll', 'l_upper_arm_roll'], ['r_shoulder_lift', 'l_shoulder_lift'],
00337 ['r_forearm_roll', 'r_wrist', 'l_forearm_roll', 'l_wrist']]
00338 gripper_list = ['r_gripper', 'l_gripper']
00339 if arms == 'left':
00340 arm_list = [['l_shoulder_pan'], ['l_elbow_flex'], ['l_upper_arm_roll'], ['l_shoulder_lift'], ['l_forearm_roll', 'l_wrist']]
00341 gripper_list = ['l_gripper']
00342 if arms == 'right':
00343 arm_list = [['r_shoulder_pan'], ['r_elbow_flex'], ['r_upper_arm_roll'], ['r_shoulder_lift'], ['r_forearm_roll', 'r_wrist']]
00344 gripper_list = ['r_gripper']
00345 arm = CalibrateSequence(arm_list, status)
00346 gripper = CalibrateSequence([gripper_list], status)
00347 head = CalibrateSequence([head_list, ['laser_tilt']], status)
00348 caster = CalibrateSequence([caster_list], status)
00349
00350
00351
00352 if not torso.is_calibrated():
00353 rospy.loginfo('Calibrating imu')
00354 status.publish(['imu'])
00355 imu_calibrate_srv_name = 'torso_lift_imu/calibrate'
00356 rospy.wait_for_service(imu_calibrate_srv_name)
00357 imu_calibrate_srv = rospy.ServiceProxy(imu_calibrate_srv_name, Empty)
00358 try:
00359 imu_calibrate_srv()
00360 status.publish()
00361
00362 except:
00363 imustatus = False
00364 rospy.loginfo('Calibrating imu finished')
00365 else:
00366 rospy.loginfo('Not calibrating imu')
00367
00368
00369 torso.calibrate()
00370
00371
00372 torso_holder = None
00373 if not arm.is_calibrated():
00374 torso_holder = HoldingController('torso_lift')
00375 torso_holder.hold(0.25)
00376 rospy.sleep(5.0)
00377 rospy.loginfo('Moving up spine to allow arms to calibrate')
00378 arm.calibrate()
00379 rospy.loginfo('Moving down spine after arm calibration')
00380 torso_holder.hold(0.01)
00381 rospy.sleep(20.0)
00382
00383
00384 gripper.calibrate()
00385 head.calibrate()
00386 caster.calibrate()
00387
00388 joints_status = True
00389 status.publish()
00390
00391
00392
00393 finally:
00394 rospy.loginfo("Bringing down calibration node")
00395
00396 rospy.set_param(calibration_params_namespace, "")
00397 del arm
00398 del gripper
00399 del torso
00400 del torso_holder
00401 del caster
00402 del head
00403
00404 if not imustatus and not joints_status:
00405 rospy.logerr("Both mechanism and IMU calibration failed")
00406 elif not joints_status:
00407 rospy.logerr("IMU calibration complete, but mechanism calibration failed")
00408 elif not imustatus:
00409 rospy.logerr("Mechanism calibration complete, but IMU calibration failed.")
00410 else:
00411 rospy.loginfo('Calibration completed in %f sec' %(rospy.Time.now() - calibration_start_time).to_sec())
00412
00413 if joints_status:
00414 pub_calibrated.publish(True)
00415 rospy.spin()
00416
00417
00418 if __name__ == '__main__': main()