77 read(calibration_file);
80 void read(
const std::string& calibration_file);
81 void write(
const std::string& calibration_file);
int max_intensity
Definition: calibration.h:52
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Calibration()
Definition: calibration.h:75
float vert_offset_correction
Definition: calibration.h:50
float cos_vert_correction
cached cosine of vert_correction
Definition: calibration.h:61
bool initialized_
Definition: calibration.h:72
correction values for a single laser
Definition: calibration.h:43
int min_intensity
Definition: calibration.h:53
float focal_slope
Definition: calibration.h:55
std::map< int, LaserCorrection > laser_corrections_
Definition: calibration.h:70
float dist_correction_x
Definition: calibration.h:48
float dist_correction
Definition: calibration.h:47
float rot_correction
Definition: calibration.h:45
float sin_vert_correction
cached sine of vert_correction
Definition: calibration.h:62
float cos_rot_correction
cached cosine of rot_correction
Definition: calibration.h:59
float focal_offset
Definition: calibration.h:56
int laser_ring
ring number for this laser
Definition: calibration.h:64
float horiz_offset_correction
Definition: calibration.h:51
float vert_correction
Definition: calibration.h:46
Calibration class storing entire configuration for the Velodyne.
Definition: calibration.h:68
float focal_distance
Definition: calibration.h:54
Calibration(const std::string &calibration_file)
Definition: calibration.h:76
int num_lasers_
Definition: calibration.h:71
float sin_rot_correction
cached sine of rot_correction
Definition: calibration.h:60
float dist_correction_y
Definition: calibration.h:49