calibration.h
Go to the documentation of this file.
00001 // Copyright (C) 2012, 2019 Austin Robot Technology, Piyush Khandelwal, Joshua Whitley
00002 // All rights reserved.
00003 //
00004 // Software License Agreement (BSD License 2.0)
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions
00008 // are met:
00009 //
00010 //  * Redistributions of source code must retain the above copyright
00011 //    notice, this list of conditions and the following disclaimer.
00012 //  * Redistributions in binary form must reproduce the above
00013 //    copyright notice, this list of conditions and the following
00014 //    disclaimer in the documentation and/or other materials provided
00015 //    with the distribution.
00016 //  * Neither the name of {copyright_holder} nor the names of its
00017 //    contributors may be used to endorse or promote products derived
00018 //    from this software without specific prior written permission.
00019 //
00020 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 // POSSIBILITY OF SUCH DAMAGE.
00032 
00033 #ifndef VELODYNE_POINTCLOUD_CALIBRATION_H
00034 #define VELODYNE_POINTCLOUD_CALIBRATION_H
00035 
00036 #include <map>
00037 #include <vector>
00038 #include <string>
00039 
00040 namespace velodyne_pointcloud
00041 {
00042 
00052 struct LaserCorrection
00053 {
00055   float rot_correction;
00056   float vert_correction;
00057   float dist_correction;
00058   bool two_pt_correction_available;
00059   float dist_correction_x;
00060   float dist_correction_y;
00061   float vert_offset_correction;
00062   float horiz_offset_correction;
00063   int max_intensity;
00064   int min_intensity;
00065   float focal_distance;
00066   float focal_slope;
00067 
00069   float cos_rot_correction;              
00070   float sin_rot_correction;              
00071   float cos_vert_correction;             
00072   float sin_vert_correction;             
00073 
00074   int laser_ring;                        
00075 };
00076 
00078 class Calibration
00079 {
00080 public:
00081   float distance_resolution_m;
00082   std::map<int, LaserCorrection> laser_corrections_map;
00083   std::vector<LaserCorrection> laser_corrections;
00084   int num_lasers;
00085   bool initialized;
00086   bool ros_info;
00087 
00088 public:
00089   explicit Calibration(bool info = true)
00090   : distance_resolution_m(0.002f),
00091     num_lasers(0),
00092     initialized(false),
00093     ros_info(info) {}
00094   explicit Calibration(
00095     const std::string& calibration_file,
00096     bool info = true)
00097   : distance_resolution_m(0.002f),
00098     ros_info(info)
00099   {
00100     read(calibration_file);
00101   }
00102 
00103   void read(const std::string& calibration_file);
00104   void write(const std::string& calibration_file);
00105 };
00106 
00107 }  // namespace velodyne_pointcloud
00108 
00109 #endif  // VELODYNE_POINTCLOUD_CALIBRATION_H


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Wed Jul 3 2019 19:32:23