pr2_calibration_estimation::post_process Namespace Reference

Functions

def usage

Variables

tuple all_sensor_types = list(set([x['sensor_type'] for x in all_sensors_dict.values()]))
tuple all_sensors_dict = est_helpers.build_sensor_defs(sensors_dump)
tuple bag = rosbag.Bag(bag_filename)
tuple bag_filename = rospy.myargv()
list bearing_list = []
list cam_covs = [matrix(array(s.compute_cov(fk)) * kron(eye(s.get_residual_length()/2),ones([2,2]))) for s,fk in zip(cam_sensors, fk_points)]
list cam_Js = [s.compute_expected_J(fk) for s,fk in zip(cam_sensors, fk_points)]
list cam_sensors = [[s for s in ms.sensors if s.sensor_id == cur_loop['cam']][0] for ms in multisensors_pruned]
list cb_points = [SingleTransform(pose).transform * system_def.checkerboards[ms.checkerboard].generate_points() for pose, ms in zip(cb_poses_pruned,multisensors_pruned)]
tuple cb_poses = yaml.load(open(output_dir + "/" + cur_step["output_filename"] + "_poses.yaml"))
list chain_sensors = [[s for s in ms.sensors if s.sensor_id == cur_loop['3d']][0] for ms in multisensors_pruned]
tuple circ_angles = numpy.linspace(0,2*numpy.pi, 360, endpoint=True)
tuple circ_pos
tuple config = rospy.get_param(config_param_name)
string config_param_name = "calibration_config"
tuple cur_scatter = plt.scatter(array(r)[:,0], array(r)[:,1], **cur_loop['plot_ops'])
list cur_step = step_list[-1]
tuple e = error_calc.calculate_error(opt_all_vec)
tuple ellip = numpy.sqrt(4.6052)
tuple ellip_shifted = array(ellip + r[k,:].T)
tuple error_calc = opt_runner.ErrorCalc(system_def, free_dict, multisensors_pruned, False)
tuple error_cat = numpy.concatenate(error_list)
tuple errors_dict = opt_runner.compute_errors_breakdown(error_calc, multisensors_pruned, numpy.array(cb_poses_pruned))
list fk_covs = [matrix(array(s.compute_cov(None)) * kron(eye(s.get_residual_length()/3),ones([3,3]))) for s in chain_sensors]
list fk_points = [s.get_measurement() for s in chain_sensors]
tuple free_dict = yaml.load(cur_step["free_params"])
list full_covs = [matrix(cam_J)*fk_cov*matrix(cam_J).T + cam_cov for cam_J, cam_cov, fk_cov in zip(cam_Js, cam_covs, fk_covs)]
tuple loop_list = yaml.load(open(loop_list_filename))
tuple loop_list_filename = rospy.myargv()
tuple m = Marker()
int marker_count = 0
tuple marker_fk_pub = rospy.Publisher("cal_markers", Marker)
tuple marker_guess_pub = rospy.Publisher("cb_guess", Marker)
list meas_points = [s.get_measurement() for s in cam_sensors]
tuple ms = MultiSensor(sensor_defs)
list multisensors = []
tuple opt_all_vec = opt_runner.build_opt_vector(system_def, free_dict, numpy.array(cb_poses_pruned))
tuple output_dir = rospy.myargv()
list points_list_fk = [ geometry_msgs.msg.Point(cur_pt[0, 0], cur_pt[0, 1], cur_pt[0, 2]) for cur_pt in list(numpy.concatenate(fk_points,1).T)]
list points_list_guess = [ geometry_msgs.msg.Point(cur_pt[0, 0], cur_pt[0, 1], cur_pt[0, 2]) for cur_pt in list(numpy.concatenate(cb_points,1).T)]
list proj_points = [s.compute_expected(pts) for (s,pts) in zip(cam_sensors,fk_points)]
tuple r = numpy.concatenate(proj_points)
tuple rms_error = numpy.sqrt( numpy.mean(error_cat**2) )
list sample_ind = [k for k,ms in zip(range(len(multisensors)), multisensors) if len(ms.sensors) == 2]
list scatter_list = []
tuple sensor_defs = est_helpers.load_requested_sensors(all_sensors_dict, [cur_loop['cam'], cur_loop['3d']])
list sensors_dump = [yaml.load(x) for x in config[sensors_name].values()]
string sensors_name = "sensors"
tuple step_list = est_helpers.load_calibration_steps(config["cal_steps"])
tuple system_def = RobotParams()
tuple system_def_dict = yaml.load(open(output_dir + "/" + cur_step["output_filename"] + ".yaml"))

Function Documentation

def pr2_calibration_estimation::post_process::usage (  ) 

Definition at line 55 of file post_process.py.


Variable Documentation

tuple pr2_calibration_estimation::post_process::all_sensor_types = list(set([x['sensor_type'] for x in all_sensors_dict.values()]))

Definition at line 96 of file post_process.py.

Definition at line 95 of file post_process.py.

Definition at line 155 of file post_process.py.

Definition at line 72 of file post_process.py.

Definition at line 258 of file post_process.py.

list pr2_calibration_estimation::post_process::cam_covs = [matrix(array(s.compute_cov(fk)) * kron(eye(s.get_residual_length()/2),ones([2,2]))) for s,fk in zip(cam_sensors, fk_points)]

Definition at line 242 of file post_process.py.

list pr2_calibration_estimation::post_process::cam_Js = [s.compute_expected_J(fk) for s,fk in zip(cam_sensors, fk_points)]

Definition at line 241 of file post_process.py.

list pr2_calibration_estimation::post_process::cam_sensors = [[s for s in ms.sensors if s.sensor_id == cur_loop['cam']][0] for ms in multisensors_pruned]

Definition at line 206 of file post_process.py.

list pr2_calibration_estimation::post_process::cb_points = [SingleTransform(pose).transform * system_def.checkerboards[ms.checkerboard].generate_points() for pose, ms in zip(cb_poses_pruned,multisensors_pruned)]

Definition at line 208 of file post_process.py.

tuple pr2_calibration_estimation::post_process::cb_poses = yaml.load(open(output_dir + "/" + cur_step["output_filename"] + "_poses.yaml"))

Definition at line 105 of file post_process.py.

list pr2_calibration_estimation::post_process::chain_sensors = [[s for s in ms.sensors if s.sensor_id == cur_loop['3d']][0] for ms in multisensors_pruned]

Definition at line 205 of file post_process.py.

tuple pr2_calibration_estimation::post_process::circ_angles = numpy.linspace(0,2*numpy.pi, 360, endpoint=True)

Definition at line 281 of file post_process.py.

Initial value:
numpy.concatenate( [ [numpy.sin(circ_angles)],
                                            [numpy.cos(circ_angles)] ] )

Definition at line 282 of file post_process.py.

Definition at line 87 of file post_process.py.

Definition at line 83 of file post_process.py.

tuple pr2_calibration_estimation::post_process::cur_scatter = plt.scatter(array(r)[:,0], array(r)[:,1], **cur_loop['plot_ops'])

Definition at line 271 of file post_process.py.

Definition at line 101 of file post_process.py.

tuple pr2_calibration_estimation::post_process::e = error_calc.calculate_error(opt_all_vec)

Definition at line 189 of file post_process.py.

Definition at line 286 of file post_process.py.

Definition at line 287 of file post_process.py.

Definition at line 187 of file post_process.py.

tuple pr2_calibration_estimation::post_process::error_cat = numpy.concatenate(error_list)

Definition at line 198 of file post_process.py.

tuple pr2_calibration_estimation::post_process::errors_dict = opt_runner.compute_errors_breakdown(error_calc, multisensors_pruned, numpy.array(cb_poses_pruned))

Definition at line 193 of file post_process.py.

list pr2_calibration_estimation::post_process::fk_covs = [matrix(array(s.compute_cov(None)) * kron(eye(s.get_residual_length()/3),ones([3,3]))) for s in chain_sensors]

Definition at line 243 of file post_process.py.

Definition at line 207 of file post_process.py.

Definition at line 106 of file post_process.py.

list pr2_calibration_estimation::post_process::full_covs = [matrix(cam_J)*fk_cov*matrix(cam_J).T + cam_cov for cam_J, cam_cov, fk_cov in zip(cam_Js, cam_covs, fk_covs)]

Definition at line 245 of file post_process.py.

Definition at line 81 of file post_process.py.

Definition at line 74 of file post_process.py.

Definition at line 213 of file post_process.py.

Definition at line 147 of file post_process.py.

tuple pr2_calibration_estimation::post_process::marker_fk_pub = rospy.Publisher("cal_markers", Marker)

Definition at line 65 of file post_process.py.

tuple pr2_calibration_estimation::post_process::marker_guess_pub = rospy.Publisher("cb_guess", Marker)

Definition at line 64 of file post_process.py.

Definition at line 250 of file post_process.py.

Definition at line 165 of file post_process.py.

Definition at line 154 of file post_process.py.

tuple pr2_calibration_estimation::post_process::opt_all_vec = opt_runner.build_opt_vector(system_def, free_dict, numpy.array(cb_poses_pruned))

Definition at line 188 of file post_process.py.

Definition at line 73 of file post_process.py.

list pr2_calibration_estimation::post_process::points_list_fk = [ geometry_msgs.msg.Point(cur_pt[0, 0], cur_pt[0, 1], cur_pt[0, 2]) for cur_pt in list(numpy.concatenate(fk_points,1).T)]

Definition at line 210 of file post_process.py.

list pr2_calibration_estimation::post_process::points_list_guess = [ geometry_msgs.msg.Point(cur_pt[0, 0], cur_pt[0, 1], cur_pt[0, 2]) for cur_pt in list(numpy.concatenate(cb_points,1).T)]

Definition at line 211 of file post_process.py.

list pr2_calibration_estimation::post_process::proj_points = [s.compute_expected(pts) for (s,pts) in zip(cam_sensors,fk_points)]

Definition at line 249 of file post_process.py.

Definition at line 255 of file post_process.py.

tuple pr2_calibration_estimation::post_process::rms_error = numpy.sqrt( numpy.mean(error_cat**2) )

Definition at line 199 of file post_process.py.

tuple pr2_calibration_estimation::post_process::sample_ind = [k for k,ms in zip(range(len(multisensors)), multisensors) if len(ms.sensors) == 2]

Definition at line 176 of file post_process.py.

Definition at line 145 of file post_process.py.

tuple pr2_calibration_estimation::post_process::sensor_defs = est_helpers.load_requested_sensors(all_sensors_dict, [cur_loop['cam'], cur_loop['3d']])

Definition at line 150 of file post_process.py.

Definition at line 94 of file post_process.py.

Definition at line 90 of file post_process.py.

tuple pr2_calibration_estimation::post_process::step_list = est_helpers.load_calibration_steps(config["cal_steps"])

Definition at line 99 of file post_process.py.

Definition at line 181 of file post_process.py.

tuple pr2_calibration_estimation::post_process::system_def_dict = yaml.load(open(output_dir + "/" + cur_step["output_filename"] + ".yaml"))

Definition at line 104 of file post_process.py.

 All Classes Namespaces Files Functions Variables Typedefs


pr2_calibration_estimation
Author(s): Vijay Pradeep
autogenerated on Fri Jan 11 09:09:35 2013