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 import roslib; roslib.load_manifest('calibration_launch')
00035 import rospy
00036 import yaml
00037 import sys
00038 import actionlib
00039 import joint_states_settler.msg
00040 import time
00041 import threading
00042 import os
00043 import string
00044
00045 import capture_executive
00046 from capture_executive.config_manager import ConfigManager
00047 from capture_executive.sensor_managers import *
00048 from capture_executive.robot_measurement_cache import RobotMeasurementCache
00049
00050 from calibration_msgs.msg import RobotMeasurement
00051
00052
00053 roslib.load_manifest('calibration_estimation')
00054 from urdf_python.urdf import *
00055
00056
00057 class CaptureExecutive:
00058 def __init__(self, config_dir, system, robot_desc, output_debug=False):
00059
00060 self.cam_config = yaml.load(open(config_dir + "/cam_config.yaml"))
00061 self.chain_config = yaml.load(open(config_dir + "/chain_config.yaml"))
00062 self.laser_config = yaml.load(open(config_dir + "/laser_config.yaml"))
00063 self.controller_config = yaml.load(open(config_dir + "/controller_config.yaml"))
00064
00065 if self.laser_config == None:
00066 self.laser_config = dict()
00067
00068 self.output_debug = output_debug
00069
00070
00071 self.message = None
00072
00073
00074 self.interval_status = None
00075
00076
00077 links = URDF().parse(robot_desc).links.keys()
00078
00079
00080 system = yaml.load(open(system))
00081
00082
00083 for cam in self.cam_config.keys():
00084 try:
00085 link = system['sensors']['rectified_cams'][cam]['frame_id']
00086 if not link in links:
00087 print 'URDF does not contain link [%s]. Removing camera [%s]' % (link, cam)
00088 del self.cam_config[cam]
00089 except:
00090 print 'System description does not contain camera [%s]' % cam
00091 del self.cam_config[cam]
00092
00093
00094 for chain in self.chain_config.keys():
00095 try:
00096 link = system['sensors']['chains'][chain]['tip']
00097 if not link in links:
00098 print 'URDF does not contain link [%s]. Removing chain [%s]' % (link, chain)
00099 del self.chain_config[chain]
00100 except:
00101 print 'System description does not contain chain [%s]' % chain
00102 del self.chain_config[chain]
00103
00104 self.cache = RobotMeasurementCache()
00105 self.lock = threading.Lock()
00106
00107
00108 self.active = False
00109
00110
00111 self.config_manager = ConfigManager(self.cam_config,
00112 self.chain_config,
00113 self.laser_config,
00114 self.controller_config)
00115
00116
00117 self.cam_managers = [ (cam_id, CamManager( cam_id, self.add_cam_measurement) ) for cam_id in self.cam_config.keys() ]
00118 self.chain_managers = [ (chain_id, ChainManager(chain_id, self.add_chain_measurement) ) for chain_id in self.chain_config.keys() ]
00119 self.laser_managers = [ (laser_id, LaserManager(laser_id, self.add_laser_measurement) ) for laser_id in self.laser_config.keys() ]
00120
00121
00122 self.request_interval_sub = rospy.Subscriber("intersected_interval", calibration_msgs.msg.Interval, self.request_callback)
00123
00124
00125 self.interval_status_sub = rospy.Subscriber(
00126 "intersected_interval_status",
00127 calibration_msgs.msg.IntervalStatus, self.status_callback)
00128
00129
00130
00131
00132 def capture(self, next_configuration, timeout):
00133 done = False
00134 self.m_robot = None
00135 self.message = None
00136 self.interval_status = None
00137
00138 timeout_time = rospy.Time().now() + timeout
00139
00140 self.lock.acquire()
00141 if self.active:
00142 rospy.logerr("Can't capture since we're already active")
00143 done = True
00144 self.lock.release()
00145
00146 camera_measurements = next_configuration["camera_measurements"]
00147 next_configuration["camera_measurements"] = []
00148
00149 for (i, cam) in enumerate(camera_measurements):
00150 if self.cam_config.has_key(cam["cam_id"]):
00151 next_configuration["camera_measurements"].append(cam)
00152 else:
00153 rospy.logdebug("Not capturing measurement for camera: %s"%(cam["cam_id"]))
00154
00155
00156 self.config_manager.reconfigure(next_configuration)
00157
00158 time.sleep(2.0)
00159
00160
00161 cam_ids = [x["cam_id"] for x in next_configuration["camera_measurements"]]
00162 chain_ids = [x["chain_id"] for x in next_configuration["joint_measurements"]]
00163 try:
00164 laser_ids = [x["laser_id"] for x in next_configuration["laser_measurements"]]
00165 except:
00166 laser_ids = list()
00167 self.cache.reconfigure(cam_ids, chain_ids, laser_ids)
00168
00169 rospy.logdebug("Setting up sensor managers")
00170 enable_list = []
00171 disable_list = []
00172
00173 for cam_id, cam_manager in self.cam_managers:
00174 if cam_id in [x["cam_id"] for x in next_configuration["camera_measurements"]]:
00175 enable_list.append(cam_id)
00176 cam_manager.enable(self.output_debug)
00177 else:
00178 disable_list.append(cam_id)
00179 cam_manager.disable()
00180
00181 for chain_id, chain_manager in self.chain_managers:
00182 if chain_id in [x["chain_id"] for x in next_configuration["joint_measurements"]]:
00183 enable_list.append(chain_id)
00184 chain_manager.enable()
00185 else:
00186 disable_list.append(chain_id)
00187 chain_manager.disable()
00188
00189 for laser_id, laser_manager in self.laser_managers:
00190 enabled_lasers = [x["laser_id"] for x in next_configuration["laser_measurements"]]
00191 if laser_id in enabled_lasers:
00192 enable_list.append(laser_id)
00193 laser_manager.enable(self.output_debug)
00194 else:
00195 disable_list.append(laser_id)
00196 laser_manager.disable()
00197
00198 print "Enabling"
00199 for cur_enabled in enable_list:
00200 print " + %s" % cur_enabled
00201 print "Disabling"
00202 for cur_disabled in disable_list:
00203 print " - %s" % cur_disabled
00204
00205 self.lock.acquire()
00206 self.active = True
00207 self.lock.release()
00208
00209
00210 while (not rospy.is_shutdown()) and (not done) and (rospy.Time().now() < timeout_time):
00211 time.sleep(.1)
00212 self.lock.acquire()
00213 if self.m_robot is not None:
00214 done = True
00215 self.lock.release()
00216
00217
00218 for cam_id, cam_manager in self.cam_managers:
00219 cam_manager.disable()
00220 for chain_id, chain_manager in self.chain_managers:
00221 chain_manager.disable()
00222 for laser_id, laser_manager in self.laser_managers:
00223 laser_manager.disable()
00224
00225
00226 self.config_manager.stop()
00227
00228
00229 if self.m_robot is not None:
00230 self.m_robot.sample_id = next_configuration["sample_id"]
00231 self.m_robot.target_id = next_configuration["target"]["target_id"]
00232 self.m_robot.chain_id = next_configuration["target"]["chain_id"]
00233 elif self.interval_status is not None:
00234 total = 0
00235 bad_sensors = []
00236 l = len(self.interval_status.names)
00237 if l != len(self.interval_status.yeild_rates):
00238 rospy.logerr("Invalid interval status message; names and yeild rates have different lengths")
00239 l = min(l, len(self.interval_status.yeild_rates))
00240
00241 for i in range(l):
00242 if self.interval_status.yeild_rates[i] == 0.0:
00243 bad_sensors.append(self.interval_status.names[i])
00244 total += self.interval_status.yeild_rates[i]
00245
00246
00247 if len(bad_sensors) > 0:
00248 print "Didn't get good data from %s"%(', '.join(bad_sensors))
00249 else:
00250
00251
00252 avg = total / l
00253 for i in range(l):
00254 if self.interval_status.yeild_rates[i] <= avg:
00255 bad_sensors.append(self.interval_status.names[i])
00256 print "%s may be performing poorly"%(", ".join(bad_sensors))
00257 elif self.message is not None:
00258 print self.message
00259
00260 self.lock.acquire()
00261 self.active = False
00262 self.lock.release()
00263
00264 return self.m_robot
00265
00266 def request_callback(self, msg):
00267
00268 if (msg.end - msg.start) < rospy.Duration(1,0):
00269 return
00270
00271 self.lock.acquire()
00272 if self.active:
00273
00274 m = self.cache.request_robot_measurement(msg.start, msg.end)
00275 if isinstance(m, basestring):
00276 self.message = m
00277 else:
00278 self.m_robot = m
00279
00280 if self.m_robot is not None:
00281 self.active = False
00282 self.lock.release()
00283
00284 def status_callback(self, msg):
00285 self.lock.acquire()
00286 if self.active:
00287 self.interval_status = msg
00288 self.lock.release()
00289
00290 def add_cam_measurement(self, cam_id, msg):
00291 if len(msg.image_points) > 0:
00292 self.lock.acquire()
00293 self.cache.add_cam_measurement(cam_id, msg)
00294 self.lock.release()
00295
00296 def add_chain_measurement(self, chain_id, msg):
00297 self.lock.acquire()
00298 self.cache.add_chain_measurement(chain_id, msg)
00299 self.lock.release()
00300
00301 def add_laser_measurement(self, laser_id, msg, interval_start, interval_end):
00302 self.lock.acquire()
00303 self.cache.add_laser_measurement(laser_id, msg, interval_start, interval_end)
00304 self.lock.release()
00305
00306 if __name__=='__main__':
00307 rospy.init_node("capture_executive_node")
00308
00309 rospy.logdebug("Starting executive...")
00310 rospy.sleep(5.0)
00311
00312
00313 samples_dir = rospy.myargv()[1]
00314 config_dir = rospy.myargv()[2]
00315 system = rospy.myargv()[3]
00316
00317 try:
00318 robot_description = rospy.get_param('robot_description')
00319 except:
00320 rospy.logfatal('robot_description not set, exiting')
00321 sys.exit(-1)
00322
00323 executive = CaptureExecutive(config_dir, system, robot_description)
00324 time.sleep(1.0)
00325
00326
00327 sample_steps = list()
00328 sample_names = dict()
00329 sample_options = dict()
00330 sample_success = dict()
00331 sample_failure = dict()
00332 for directory in os.listdir(samples_dir):
00333 try:
00334 sample_options[directory] = yaml.load(open(samples_dir + '/' + directory + '/config.yaml'))
00335 sample_steps.append(directory)
00336 except IOError:
00337 continue
00338 sample_names[directory] = [x for x in os.listdir(samples_dir + '/' + directory + '/') if '.yaml' in x and x != 'config.yaml']
00339 sample_names[directory].sort()
00340 sample_success[directory] = 0
00341 sample_failure[directory] = 0
00342 sample_steps.sort()
00343
00344 for step in sample_steps:
00345 rospy.logdebug("%s Samples: \n - %s" % (sample_options[step]['group'], "\n - ".join(sample_names[step])))
00346
00347 pub = rospy.Publisher("robot_measurement", RobotMeasurement)
00348
00349 try:
00350 for step in sample_steps:
00351 keep_collecting = True
00352 full_paths = [samples_dir + '/' + step + '/' + x for x in sample_names[step] ]
00353 cur_config = yaml.load(open(full_paths[0]))
00354 m_robot = executive.capture(cur_config, rospy.Duration(0.01))
00355 while not rospy.is_shutdown() and keep_collecting:
00356 print
00357 print sample_options[step]["prompt"]
00358 print "Press <enter> to continue, type N to exit this step"
00359 resp = raw_input(">>>")
00360 if string.upper(resp) == "N":
00361 print sample_options[step]["finish"]
00362 keep_collecting = False
00363 else:
00364 for cur_sample_path in full_paths:
00365 print "On %s sample [%s]" % (sample_options[step]["group"], cur_sample_path)
00366 cur_config = yaml.load(open(cur_sample_path))
00367 m_robot = executive.capture(cur_config, rospy.Duration(40))
00368 if m_robot is None:
00369 print "--------------- Failed To Capture a %s Sample -----------------" % sample_options[step]["group"]
00370 if not sample_options[step]["repeat"]:
00371 sample_failure[step] += 1
00372 else:
00373 print "++++++++++++++ Successfully Captured a %s Sample ++++++++++++++" % sample_options[step]["group"]
00374 sample_success[step] += 1
00375 pub.publish(m_robot)
00376 print "Succeeded on %u %s samples" % (sample_success[step], sample_options[step]["group"])
00377 if rospy.is_shutdown():
00378 break
00379 keep_collecting = sample_options[step]["repeat"]
00380 except EOFError:
00381 print "Exiting"
00382
00383 time.sleep(1)
00384
00385 print "Calibration data collection has completed!"
00386 for step in sample_steps:
00387 if sample_options[step]["repeat"]:
00388 print "%s Samples: %u" % (sample_options[step]["group"], sample_success[step])
00389 else:
00390 print "%s Samples: %u/%u" % (sample_options[step]["group"], sample_success[step], sample_success[step] + sample_failure[step])
00391 print ""
00392 print "You can now kill this node, along with any other calibration nodes that are running."
00393
00394