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 import roslib; roslib.load_manifest('pr2_calibration_estimation')
00037
00038 import sys
00039 import rospy
00040 import time
00041 import numpy
00042 import rosrecord
00043 import yaml
00044
00045 import numpy
00046
00047 from pr2_calibration_estimation.robot_params import RobotParams
00048 from pr2_calibration_estimation.blocks import robot_measurement_bundler
00049
00050 SCALE_ERROR = True
00051
00052 def usage():
00053 print "Usage:"
00054 print " ./error_viewer.py [config.yaml] [blocks.yaml] [bagfile]"
00055 sys.exit(-1)
00056
00057 if (len(sys.argv) < 4):
00058 usage()
00059
00060 config_filename = sys.argv[1]
00061 blocks_filename= sys.argv[2]
00062 bag_filename = sys.argv[3]
00063
00064
00065 config_f = open(config_filename)
00066 config = yaml.load(config_f)
00067 config_f.close()
00068 robot_params = RobotParams()
00069 robot_params.configure(config)
00070
00071
00072 blocks_f = open(blocks_filename)
00073 measurement_blocks = yaml.load(blocks_f)
00074 blocks_f.close()
00075 bundler = robot_measurement_bundler.RobotMeasurementBundler(measurement_blocks)
00076
00077 blocks = bundler.load_from_bag(bag_filename)
00078
00079 for block in blocks:
00080 block.update_config(robot_params)
00081
00082
00083 error_dict = dict()
00084 for block in blocks:
00085 if block.block_type not in error_dict:
00086 error_dict[block.block_type] = dict()
00087 error_dict[block.block_type][block.block_id] = []
00088
00089
00090
00091 for block in blocks:
00092 if SCALE_ERROR:
00093 cur_scalar = block.error_scalar
00094 else:
00095 cur_scalar = 1.0
00096 error_dict[block.block_type][block.block_id].append(block.compute_error()*cur_scalar)
00097
00098 for block_id_dict in error_dict.values():
00099 for key, error_list in block_id_dict.items():
00100 block_id_dict[key] = numpy.concatenate(error_list, 1)
00101
00102 from pr2_calibration_estimation import plot_helper
00103 plot_helper.start()
00104
00105 from matplotlib import pyplot as plt
00106 import matplotlib.patches
00107
00108
00109
00110
00111
00112 markers = ['c', 's']
00113
00114
00115
00116 for block_type, block_id_dict in error_dict.items():
00117 for cur_block_id, error_mat in block_id_dict.items():
00118 if 'NarrowLeft-TiltLaser' in cur_block_id:
00119 marker = 'o'
00120 color = 'b'
00121 elif 'NarrowRight-TiltLaser' in cur_block_id:
00122 marker = 's'
00123 color = 'b'
00124 elif 'WideLeft-TiltLaser' in cur_block_id:
00125 marker = 'o'
00126 color = 'r'
00127 elif 'WideRight-TiltLaser' in cur_block_id:
00128 marker = 's'
00129 color = 'r'
00130 elif 'NarrowLeft-RightArm' in cur_block_id:
00131 marker = 'o'
00132 color = 'g'
00133 elif 'NarrowRight-RightArm' in cur_block_id:
00134 marker = 's'
00135 color = 'g'
00136 elif 'WideLeft-RightArm' in cur_block_id:
00137 marker = 'o'
00138 color = 'y'
00139 elif 'WideRight-RightArm' in cur_block_id:
00140 marker = 's'
00141 color = 'y'
00142 else:
00143 print "Unknown Block ID: [%s]" % cur_block_id
00144
00145 cur_rms = numpy.sqrt(numpy.sum(numpy.multiply(error_mat, error_mat))/error_mat.shape[1])
00146
00147
00148 print "%s:" % cur_block_id
00149 print " color: %s" % color
00150 if SCALE_ERROR:
00151 scale_prefix = "Scaled "
00152 else:
00153 scale_prefix = ""
00154 print " %srms: %.2f" % (scale_prefix, cur_rms)
00155
00156 plt.scatter( error_mat[0,:].T, error_mat[1,:].T, s=40, c=color, marker=marker, edgecolors='None', linewidths=1, alpha=.75)
00157
00158 plt.axis('equal')
00159 plt.grid(True)
00160 plt.draw()
00161
00162
00163
00164
00165
00166
00167
00168
00169
00170
00171
00172
00173
00174
00175
00176
00177
00178
00179
00180
00181
00182