calibration.h
Go to the documentation of this file.
1 // Copyright (C) 2012, 2019 Austin Robot Technology, Piyush Khandelwal, Joshua Whitley
2 // All rights reserved.
3 //
4 // Software License Agreement (BSD License 2.0)
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions
8 // are met:
9 //
10 // * Redistributions of source code must retain the above copyright
11 // notice, this list of conditions and the following disclaimer.
12 // * Redistributions in binary form must reproduce the above
13 // copyright notice, this list of conditions and the following
14 // disclaimer in the documentation and/or other materials provided
15 // with the distribution.
16 // * Neither the name of {copyright_holder} nor the names of its
17 // contributors may be used to endorse or promote products derived
18 // from this software without specific prior written permission.
19 //
20 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 // POSSIBILITY OF SUCH DAMAGE.
32 
33 #ifndef VELODYNE_POINTCLOUD_CALIBRATION_H
34 #define VELODYNE_POINTCLOUD_CALIBRATION_H
35 
36 #include <map>
37 #include <vector>
38 #include <string>
39 
41 {
42 
53 {
66  float focal_slope;
67 
73 
74  int laser_ring;
75 };
76 
79 {
80 public:
82  std::map<int, LaserCorrection> laser_corrections_map;
83  std::vector<LaserCorrection> laser_corrections;
86  bool ros_info;
87 
88 public:
89  explicit Calibration(bool info = true)
90  : distance_resolution_m(0.002f),
91  num_lasers(0),
92  initialized(false),
93  ros_info(info) {}
94  explicit Calibration(
95  const std::string& calibration_file,
96  bool info = true)
97  : distance_resolution_m(0.002f),
98  ros_info(info)
99  {
100  read(calibration_file);
101  }
102 
103  void read(const std::string& calibration_file);
104  void write(const std::string& calibration_file);
105 };
106 
107 } // namespace velodyne_pointcloud
108 
109 #endif // VELODYNE_POINTCLOUD_CALIBRATION_H
velodyne_pointcloud
Definition: calibration.h:40
velodyne_pointcloud::Calibration::write
void write(const std::string &calibration_file)
Definition: calibration.cc:275
velodyne_pointcloud::Calibration::initialized
bool initialized
Definition: calibration.h:85
velodyne_pointcloud::LaserCorrection::vert_offset_correction
float vert_offset_correction
Definition: calibration.h:61
velodyne_pointcloud::Calibration
Calibration information for the entire device.
Definition: calibration.h:78
velodyne_pointcloud::LaserCorrection::rot_correction
float rot_correction
Definition: calibration.h:55
velodyne_pointcloud::Calibration::Calibration
Calibration(bool info=true)
Definition: calibration.h:89
velodyne_pointcloud::Calibration::num_lasers
int num_lasers
Definition: calibration.h:84
velodyne_pointcloud::LaserCorrection::sin_vert_correction
float sin_vert_correction
sine of vert_correction
Definition: calibration.h:72
velodyne_pointcloud::Calibration::laser_corrections
std::vector< LaserCorrection > laser_corrections
Definition: calibration.h:83
velodyne_pointcloud::Calibration::ros_info
bool ros_info
Definition: calibration.h:86
velodyne_pointcloud::LaserCorrection
correction values for a single laser
Definition: calibration.h:52
velodyne_pointcloud::LaserCorrection::focal_slope
float focal_slope
Definition: calibration.h:66
velodyne_pointcloud::LaserCorrection::dist_correction_y
float dist_correction_y
Definition: calibration.h:60
velodyne_pointcloud::LaserCorrection::min_intensity
int min_intensity
Definition: calibration.h:64
velodyne_pointcloud::Calibration::laser_corrections_map
std::map< int, LaserCorrection > laser_corrections_map
Definition: calibration.h:82
velodyne_pointcloud::LaserCorrection::sin_rot_correction
float sin_rot_correction
sine of rot_correction
Definition: calibration.h:70
velodyne_pointcloud::LaserCorrection::cos_vert_correction
float cos_vert_correction
cosine of vert_correction
Definition: calibration.h:71
velodyne_pointcloud::Calibration::distance_resolution_m
float distance_resolution_m
Definition: calibration.h:81
velodyne_pointcloud::LaserCorrection::vert_correction
float vert_correction
Definition: calibration.h:56
velodyne_pointcloud::LaserCorrection::two_pt_correction_available
bool two_pt_correction_available
Definition: calibration.h:58
velodyne_pointcloud::LaserCorrection::laser_ring
int laser_ring
ring number for this laser
Definition: calibration.h:74
velodyne_pointcloud::LaserCorrection::dist_correction
float dist_correction
Definition: calibration.h:57
velodyne_pointcloud::LaserCorrection::horiz_offset_correction
float horiz_offset_correction
Definition: calibration.h:62
velodyne_pointcloud::Calibration::read
void read(const std::string &calibration_file)
Definition: calibration.cc:251
velodyne_pointcloud::LaserCorrection::focal_distance
float focal_distance
Definition: calibration.h:65
velodyne_pointcloud::Calibration::Calibration
Calibration(const std::string &calibration_file, bool info=true)
Definition: calibration.h:94
velodyne_pointcloud::LaserCorrection::cos_rot_correction
float cos_rot_correction
cosine of rot_correction
Definition: calibration.h:69
velodyne_pointcloud::LaserCorrection::max_intensity
int max_intensity
Definition: calibration.h:63
gen_calibration.f
f
Definition: gen_calibration.py:213
velodyne_pointcloud::LaserCorrection::dist_correction_x
float dist_correction_x
Definition: calibration.h:59


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Tue May 2 2023 02:28:04