$search
00001 #! /usr/bin/env python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2008, Willow Garage, Inc. 00005 # All rights reserved. 00006 # 00007 # Redistribution and use in source and binary forms, with or without 00008 # modification, are permitted provided that the following conditions 00009 # are met: 00010 # 00011 # * Redistributions of source code must retain the above copyright 00012 # notice, this list of conditions and the following disclaimer. 00013 # * Redistributions in binary form must reproduce the above 00014 # copyright notice, this list of conditions and the following 00015 # disclaimer in the documentation and/or other materials provided 00016 # with the distribution. 00017 # * Neither the name of Willow Garage, Inc. nor the names of its 00018 # contributors may be used to endorse or promote products derived 00019 # from this software without specific prior written permission. 00020 # 00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 # POSSIBILITY OF SUCH DAMAGE. 00033 00034 # author: Vijay Pradeep 00035 00036 import roslib; roslib.load_manifest('pr2_calibration_estimation') 00037 00038 import sys 00039 import rospy 00040 import time 00041 import numpy 00042 import rosbag 00043 import yaml 00044 import os.path 00045 import numpy 00046 00047 import stat 00048 import os 00049 00050 from numpy import matrix 00051 00052 from pr2_calibration_estimation.robot_params import RobotParams 00053 from pr2_calibration_estimation.sensors.multi_sensor import MultiSensor 00054 from pr2_calibration_estimation.opt_runner import opt_runner 00055 00056 def usage(): 00057 rospy.logerr("Not enough arguments") 00058 print "Usage:" 00059 print " ./proto1.py [bagfile] [output_dir]" 00060 sys.exit(0) 00061 00062 00063 def build_sensor_defs(sensors_dump): 00064 ''' 00065 Given a list of sensor definition dictionaries, merge them into a single dictionary 00066 ''' 00067 # There could be multiple defitions of sensors in the sensors namespace. We 00068 # need to merge all of these into a single consistent dictionary 00069 all_sensors_dict = dict() 00070 00071 for cur_sensors_file in sensors_dump: 00072 for cur_sensor_type, cur_sensor_list in cur_sensors_file.items(): 00073 for cur_sensor in cur_sensor_list: 00074 # We want sensor_ids to be unique. Thus, we should warn the user if there are duplicate block IDs being loaded 00075 if cur_sensor['sensor_id'] in all_sensors_dict.keys(): 00076 rospy.logwarn("Loading a duplicate [%s]. Overwriting previous" % cur_sensor['sensor_id']) 00077 all_sensors_dict[cur_sensor['sensor_id']] = cur_sensor 00078 all_sensors_dict[cur_sensor['sensor_id']]['sensor_type'] = cur_sensor_type 00079 00080 print "The following error sensors have been loaded:\n" 00081 # We want to sort by the types of blocks 00082 all_sensor_types = list(set([x['sensor_type'] for x in all_sensors_dict.values()])) 00083 00084 for cur_sensor_type in all_sensor_types: 00085 print " %s sensors" % cur_sensor_type 00086 cur_sensor_ids = [cur_sensor_id for cur_sensor_id,cur_sensor in all_sensors_dict.items() if cur_sensor['sensor_type'] == cur_sensor_type] 00087 cur_sensor_ids.sort() 00088 for cur_sensor_id in cur_sensor_ids: 00089 print " - %s" % cur_sensor_id 00090 print "" 00091 00092 return all_sensors_dict 00093 00094 def load_calibration_steps(steps_dict): 00095 # We want to execute the calibration in alphabetical order, based on the key names 00096 step_keys = steps_dict.keys() 00097 step_keys.sort() 00098 step_list = [] 00099 for step_name in step_keys: 00100 # Add the step name to the dict (since we'll lose this info once we listify) 00101 steps_dict[step_name]["name"] = step_name 00102 step_list.append(steps_dict[step_name]) 00103 print "Loaded the calibration steps to execute in the following order:" 00104 for cur_step in step_list: 00105 print " - %s" % cur_step['name'] 00106 return step_list 00107 00108 # Verifies that the given filename has the correct permissions. 00109 # Either it shouldn't exist, or it should be writable 00110 def check_file_permissions(filename): 00111 # If the file doesn't exist, then we're fine 00112 if not os.path.isfile(filename): 00113 return True 00114 00115 statinfo = os.stat(filename); 00116 00117 # See if the current user owns the file. If so, look at user's write priveleges 00118 if (os.geteuid() == statinfo.st_uid): 00119 return (os.stat(filename).st_mode & stat.S_IWUSR) > 0 00120 00121 # See if the current user's group owns the file. If so, look at groups's write priveleges 00122 if (os.getgid() == statinfo.st_gid): 00123 return (os.stat(filename).st_mode & stat.S_IWGRP) > 0 00124 00125 # Not the owner, nor part of the group, so check the 'other' permissions 00126 return (os.stat(filename).st_mode & stat.S_IWOTH) > 0 00127 00128 00129 def load_requested_sensors(all_sensors_dict, requested_sensors): 00130 ''' 00131 Build a sensor dictionary with the subset of sensors that we request 00132 ''' 00133 all_sensor_types = list(set([x['sensor_type'] for x in all_sensors_dict.values()])) 00134 cur_sensors = dict([(x,[]) for x in all_sensor_types]) 00135 for requested_sensor_id in requested_sensors: 00136 # We need to now find requested_sensor_id in our library of sensors 00137 if requested_sensor_id in all_sensors_dict.keys(): 00138 cur_sensor_type = all_sensors_dict[requested_sensor_id]['sensor_type'] 00139 cur_sensors[cur_sensor_type].append(all_sensors_dict[requested_sensor_id]) 00140 else: 00141 rospy.logerr("Could not find [%s] in block library. Skipping this block") 00142 return cur_sensors 00143 00144 if __name__ == '__main__': 00145 rospy.init_node("multi_step_cov_estimator", anonymous=True) 00146 00147 print "Starting The Multi Step [Covariance] Estimator Node\n" 00148 00149 if (len(rospy.myargv()) < 2): 00150 usage() 00151 elif (len(rospy.myargv()) < 3): 00152 bag_filename = rospy.myargv()[1] 00153 output_dir = "." 00154 else: 00155 bag_filename = rospy.myargv()[1] 00156 output_dir = rospy.myargv()[2] 00157 00158 print "Using Bagfile: %s\n" % bag_filename 00159 if not os.path.isfile(bag_filename): 00160 rospy.logerr("Bagfile does not exist. Exiting...") 00161 sys.exit(1) 00162 00163 config_param_name = "calibration_config" 00164 if not rospy.has_param(config_param_name): 00165 rospy.logerr("Could not find parameter [%s]. Please populate this namespace with the estimation configuration.", config_param_name) 00166 sys.exit(1) 00167 config = rospy.get_param(config_param_name) 00168 00169 # Process all the sensor definitions that are on the parameter server 00170 sensors_name = "sensors" 00171 if sensors_name not in config.keys(): 00172 rospy.logerr("Could not find namespace [%s/%s]. Please populate this namespace with sensors.", (config_param_name, sensors_name)) 00173 sys.exit(1) 00174 sensors_dump = [yaml.load(x) for x in config[sensors_name].values()] 00175 all_sensors_dict = build_sensor_defs(sensors_dump) 00176 all_sensor_types = list(set([x['sensor_type'] for x in all_sensors_dict.values()])) 00177 00178 # Load all the calibration steps. 00179 step_list = load_calibration_steps(config["cal_steps"]) 00180 00181 # Count how many checkerboard poses we need to track 00182 msg_count = 0 00183 # f = open(bag_filename) 00184 bag = rosbag.Bag(bag_filename) 00185 multisensors = [] 00186 for topic, msg, t in bag.read_messages(topics=['robot_measurement']): 00187 if topic == "robot_measurement": 00188 msg_count+=1 00189 bag.close() 00190 00191 if 'initial_poses' in config.keys(): 00192 previous_pose_guesses = numpy.array(yaml.load(config['initial_poses'])) 00193 else: 00194 previous_pose_guesses = numpy.zeros([msg_count,6]) 00195 00196 # Check if we can write to all of our output files 00197 output_filenames = [] 00198 for suffix in [".yaml", "_poses.yaml", "_cov.txt"]: 00199 output_filenames += [output_dir + "/" + cur_step["output_filename"] + suffix for cur_step in step_list] 00200 00201 valid_list = [check_file_permissions(curfile) for curfile in output_filenames]; 00202 00203 permissions_valid = all(valid_list) 00204 00205 if not permissions_valid: 00206 print "Invalid file permissions. You need to be able to write to the following files:" 00207 print "\n".join([" - " + cur_file for cur_file,cur_valid in zip(output_filenames, valid_list) if not cur_valid]) 00208 sys.exit(-1) 00209 00210 # Specify which system the first calibration step should use. 00211 # Normally this would be set at the end of the calibration loop, but for the first step, 00212 # this is grabbed from the param server 00213 previous_system = yaml.load(config["initial_system"]) 00214 00215 # Load all the sensors from the bagfile and config file 00216 for cur_step in step_list: 00217 print "" 00218 print "*"*30 00219 print "Beginning [%s]" % cur_step["name"] 00220 00221 # Need to load only the sensors that we're interested in 00222 cur_sensors = load_requested_sensors(all_sensors_dict, cur_step['sensors']) 00223 00224 # Load all the sensors from bag 00225 # f = open(bag_filename) 00226 bag = rosbag.Bag(bag_filename) 00227 multisensors = [] 00228 for topic, msg, t in bag.read_messages(topics=['robot_measurement']): 00229 if topic == "robot_measurement": 00230 # Hack to rename laser id 00231 for cur_laser in msg.M_laser: 00232 if cur_laser.laser_id in ["tilt_laser_6x8", "tilt_laser_8x6", "tilt_laser_7x6", "tilt_laser_6x7"]: 00233 cur_laser.laser_id = "tilt_laser" 00234 ms = MultiSensor(cur_sensors) 00235 ms.sensors_from_message(msg) 00236 multisensors.append(ms) 00237 bag.close() 00238 00239 # Display sensor count statistics 00240 print "Executing step with the following Sensors:" 00241 # Iterate over sensor definitions for this step 00242 for cur_sensor_type, cur_sensor_list in cur_sensors.items(): 00243 print " %s Sensors:" % cur_sensor_type 00244 cur_sensor_ids = [cur_sensor['sensor_id'] for cur_sensor in cur_sensor_list] 00245 cur_sensor_ids.sort() 00246 for cur_sensor_id in cur_sensor_ids: 00247 counts = [ len([s for s in ms.sensors if s.sensor_id == cur_sensor_id]) for ms in multisensors] 00248 count = sum(counts) 00249 print " - %s (%u)" % (cur_sensor_id, count) 00250 print "" 00251 00252 print "Sensor breakdown (By Sample):" 00253 for k,ms in zip(range(len(multisensors)), multisensors): 00254 print " % 2u) %s" % (k, ", ".join([s.sensor_id for s in ms.sensors])) 00255 00256 print "Pose Guesses:\n", previous_pose_guesses 00257 00258 if len(multisensors) == 0: 00259 rospy.logwarn("No error blocks were generated for this optimization step. Skipping this step. This will result in a miscalibrated sensor") 00260 output_dict = previous_system 00261 output_poses = previous_pose_guesses 00262 else: 00263 free_dict = yaml.load(cur_step["free_params"]) 00264 use_cov = cur_step['use_cov'] 00265 if use_cov: 00266 print "Executing step with covariance calculations" 00267 else: 00268 print "Executing step without covariance calculations" 00269 output_dict, output_poses, J = opt_runner(previous_system, previous_pose_guesses, free_dict, multisensors, use_cov) 00270 00271 # Dump results to file 00272 out_f = open(output_dir + "/" + cur_step["output_filename"] + ".yaml", 'w') 00273 yaml.dump(output_dict, out_f) 00274 out_f.close() 00275 00276 out_f = open(output_dir + "/" + cur_step["output_filename"] + "_poses.yaml", 'w') 00277 yaml.dump([list([float(x) for x in pose]) for pose in list(output_poses)], out_f) 00278 out_f.close() 00279 00280 cov_x = matrix(J).T * matrix(J) 00281 numpy.savetxt(output_dir + "/" + cur_step["output_filename"] + "_cov.txt", cov_x, fmt="% 9.3f") 00282 00283 previous_system = output_dict 00284 previous_pose_guesses = output_poses 00285