38 import joint_states_settler.msg
44 import capture_executive
54 def __init__(self, config_dir, system, robot_desc, output_debug=False):
56 self.
cam_config = yaml.load(open(config_dir +
"/cam_config.yaml"))
57 self.
chain_config = yaml.load(open(config_dir +
"/chain_config.yaml"))
58 self.
laser_config = yaml.load(open(config_dir +
"/laser_config.yaml"))
73 links = URDF().parse(robot_desc).link_map.keys()
76 system = yaml.load(open(system))
79 for cam
in self.cam_config.keys():
81 link = system[
'sensors'][
'rectified_cams'][cam][
'frame_id']
83 print 'URDF does not contain link [%s]. Removing camera [%s]' % (link, cam)
86 print 'System description does not contain camera [%s]' % cam
90 for chain
in self.chain_config.keys():
92 link = system[
'sensors'][
'chains'][chain][
'tip']
94 print 'URDF does not contain link [%s]. Removing chain [%s]' % (link, chain)
97 print 'System description does not contain chain [%s]' % chain
122 "intersected_interval_status",
128 def capture(self, next_configuration, timeout):
134 timeout_time = rospy.Time().now() + timeout
138 rospy.logerr(
"Can't capture since we're already active")
142 camera_measurements = next_configuration[
"camera_measurements"]
143 next_configuration[
"camera_measurements"] = []
145 for (i, cam)
in enumerate(camera_measurements):
146 if self.cam_config.has_key(cam[
"cam_id"]):
147 next_configuration[
"camera_measurements"].append(cam)
149 rospy.logdebug(
"Not capturing measurement for camera: %s"%(cam[
"cam_id"]))
152 self.config_manager.reconfigure(next_configuration)
157 cam_ids = [x[
"cam_id"]
for x
in next_configuration[
"camera_measurements"]]
158 chain_ids = [x[
"chain_id"]
for x
in next_configuration[
"joint_measurements"]]
160 laser_ids = [x[
"laser_id"]
for x
in next_configuration[
"laser_measurements"]]
163 self.cache.reconfigure(cam_ids, chain_ids, laser_ids)
165 rospy.logdebug(
"Setting up sensor managers")
170 if cam_id
in [x[
"cam_id"]
for x
in next_configuration[
"camera_measurements"]]:
171 enable_list.append(cam_id)
174 disable_list.append(cam_id)
175 cam_manager.disable()
178 if chain_id
in [x[
"chain_id"]
for x
in next_configuration[
"joint_measurements"]]:
179 enable_list.append(chain_id)
180 chain_manager.enable()
182 disable_list.append(chain_id)
183 chain_manager.disable()
186 enabled_lasers = [x[
"laser_id"]
for x
in next_configuration[
"laser_measurements"]]
187 if laser_id
in enabled_lasers:
188 enable_list.append(laser_id)
191 disable_list.append(laser_id)
192 laser_manager.disable()
195 for cur_enabled
in enable_list:
196 print " + %s" % cur_enabled
198 for cur_disabled
in disable_list:
199 print " - %s" % cur_disabled
205 print "\nCollecting sensor data.." 207 while (
not rospy.is_shutdown())
and (
not done)
and (rospy.Time().now() < timeout_time):
214 print "Stopping sensor streams..\n" 217 cam_manager.disable()
219 chain_manager.disable()
221 laser_manager.disable()
224 self.config_manager.stop()
228 self.m_robot.sample_id = next_configuration[
"sample_id"]
229 self.m_robot.target_id = next_configuration[
"target"][
"target_id"]
230 self.m_robot.chain_id = next_configuration[
"target"][
"chain_id"]
234 l = len(self.interval_status.names)
235 if l != len(self.interval_status.yeild_rates):
236 rospy.logerr(
"Invalid interval status message; names and yeild rates have different lengths")
237 l = min(l, len(self.interval_status.yeild_rates))
240 if self.interval_status.yeild_rates[i] == 0.0:
241 bad_sensors.append(self.interval_status.names[i])
242 total += self.interval_status.yeild_rates[i]
245 if len(bad_sensors) > 0:
246 print "Didn't get good data from %s"%(
', '.join(bad_sensors))
252 if self.interval_status.yeild_rates[i] <= avg:
253 bad_sensors.append(self.interval_status.names[i])
254 print "%s may be performing poorly"%(
", ".join(bad_sensors))
266 if (msg.end - msg.start) < rospy.Duration(1,0):
272 m = self.cache.request_robot_measurement(msg.start, msg.end)
273 if isinstance(m, basestring):
289 if len(msg.image_points) > 0:
291 self.cache.add_cam_measurement(cam_id, msg)
296 self.cache.add_chain_measurement(chain_id, msg)
301 self.cache.add_laser_measurement(laser_id, msg, interval_start, interval_end)
304 if __name__==
'__main__':
305 rospy.init_node(
"capture_executive_node")
307 rospy.logdebug(
"Starting executive...")
311 samples_dir = rospy.myargv()[1]
312 config_dir = rospy.myargv()[2]
313 system = rospy.myargv()[3]
316 robot_description = rospy.get_param(
'robot_description')
318 rospy.logfatal(
'robot_description not set, exiting')
325 sample_steps = list()
326 sample_names = dict()
327 sample_options = dict()
328 sample_success = dict()
329 sample_failure = dict()
330 for directory
in os.listdir(samples_dir):
332 sample_options[directory] = yaml.load(open(samples_dir +
'/' + directory +
'/config.yaml'))
333 sample_steps.append(directory)
336 sample_names[directory] = [x
for x
in os.listdir(samples_dir +
'/' + directory +
'/')
if '.yaml' in x
and x !=
'config.yaml']
337 sample_names[directory].sort()
338 sample_success[directory] = 0
339 sample_failure[directory] = 0
342 for step
in sample_steps:
343 rospy.logdebug(
"%s Samples: \n - %s" % (sample_options[step][
'group'],
"\n - ".join(sample_names[step])))
345 pub = rospy.Publisher(
"robot_measurement", RobotMeasurement)
348 for step
in sample_steps:
349 keep_collecting =
True 350 full_paths = [samples_dir +
'/' + step +
'/' + x
for x
in sample_names[step] ]
351 if len(full_paths) == 0:
352 rospy.logfatal(samples_dir +
'/' + step +
'/' +
' is not found' )
353 rospy.logfatal(
'please run make_samples.py' )
355 cur_config = yaml.load(open(full_paths[0]))
356 m_robot = executive.capture(cur_config, rospy.Duration(0.01))
357 while not rospy.is_shutdown()
and keep_collecting:
359 print sample_options[step][
"prompt"]
360 print "Press <enter> to continue, type N to exit this step" 361 resp = raw_input(
">>>")
362 if string.upper(resp) ==
"N":
363 print sample_options[step][
"finish"]
364 keep_collecting =
False 366 for cur_sample_path
in full_paths:
367 print "On %s sample [%s]" % (sample_options[step][
"group"], cur_sample_path)
368 cur_config = yaml.load(open(cur_sample_path))
369 m_robot = executive.capture(cur_config, rospy.Duration(40))
371 print "--------------- Failed To Capture a %s Sample -----------------" % sample_options[step][
"group"]
372 if not sample_options[step][
"repeat"]:
373 sample_failure[step] += 1
375 print "++++++++++++++ Successfully Captured a %s Sample ++++++++++++++" % sample_options[step][
"group"]
376 sample_success[step] += 1
378 print "Succeeded on %u %s samples" % (sample_success[step], sample_options[step][
"group"])
379 if rospy.is_shutdown():
381 keep_collecting = sample_options[step][
"repeat"]
387 print "Calibration data collection has completed!" 388 for step
in sample_steps:
389 if sample_options[step][
"repeat"]:
390 print "%s Samples: %u" % (sample_options[step][
"group"], sample_success[step])
392 print "%s Samples: %u/%u" % (sample_options[step][
"group"], sample_success[step], sample_success[step] + sample_failure[step])
394 print "You can now kill this node, along with any other calibration nodes that are running."
def status_callback(self, msg)
def request_callback(self, msg)
def capture(self, next_configuration, timeout)
def add_laser_measurement(self, laser_id, msg, interval_start, interval_end)
def add_chain_measurement(self, chain_id, msg)
def add_cam_measurement(self, cam_id, msg)
def __init__(self, config_dir, system, robot_desc, output_debug=False)