Main MRPT website > C++ reference for MRPT 1.5.7
VelodyneCalibration.h
Go to the documentation of this file.
1 /* +---------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +---------------------------------------------------------------------------+ */
9 #ifndef VelodyneCalibration_H
10 #define VelodyneCalibration_H
11 
12 #include <mrpt/utils/core_defs.h>
13 #include <mrpt/obs/link_pragmas.h>
14 #include <string>
15 #include <vector>
16 
17 namespace mrpt {
18 namespace obs
19 {
20  /** Velodyne calibration data, for usage in mrpt::obs::CObservationVelodyneScan
21  *
22  * It is mandatory to use some calibration data to convert Velodyne scans into 3D point clouds. Users should
23  * normally use the XML files provided by the manufacturer with each scanner, but default calibration files can be
24  * loaded with \a VelodyneCalibration::LoadDefaultCalibration().
25  *
26  * \note New in MRPT 1.4.0
27  * \sa CObservationVelodyneScan, CVelodyneScanner
28  * \ingroup mrpt_obs_grp
29  */
31  {
32  VelodyneCalibration(); //!< Default ctor (leaves all empty)
33 
34  bool empty() const; //!< Returns true if no calibration has been loaded yet
35  void clear(); //!< Clear all previous contents
36 
37  /** Loads default calibration files for common LIDAR models.
38  * \param[in] lidar_model Valid model names are: `VLP16`, `HDL32`
39  * \return It always return a calibration structure, but it may be empty if the model name is unknown. See \a empty()
40  * \note Default files can be inspected in `[MRPT_SRC or /usr]/share/mrpt/config_files/rawlog-grabber/velodyne_default_calib_{*}.xml`
41  */
42  static const VelodyneCalibration & LoadDefaultCalibration(const std::string & lidar_model);
43 
44  /** Loads calibration from file, in the format supplied by the manufacturer. \return false on any error, true on success */
45  bool loadFromXMLFile(const std::string & velodyne_calibration_xml_filename);
46  /** Loads calibration from a string containing an entire XML calibration file. \sa loadFromXMLFile \return false on any error, true on success */
47  bool loadFromXMLText(const std::string & xml_file_contents);
48 
49 // Pragma to ensure we can safely serialize some of these structures
50 #pragma pack(push,1)
52  {
53  double azimuthCorrection, verticalCorrection, distanceCorrection;
54  double verticalOffsetCorrection, horizontalOffsetCorrection;
55  double sinVertCorrection, cosVertCorrection;
56  double sinVertOffsetCorrection, cosVertOffsetCorrection;
57 
58  PerLaserCalib();
59  };
60 #pragma pack(pop)
61 
62  std::vector<PerLaserCalib> laser_corrections;
63  private:
64  bool internal_loadFromXMLNode(void *node);
65 
66  };
67 } // End of namespace
68 } // End of namespace
69 
70 #endif
Velodyne calibration data, for usage in mrpt::obs::CObservationVelodyneScan.
EIGEN_STRONG_INLINE bool empty() const
void clear()
Clear the contents of this container.
Definition: ts_hash_map.h:113
std::vector< PerLaserCalib > laser_corrections
GLsizei const GLchar ** string
Definition: glext.h:3919
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.



Page generated by Doxygen 1.8.14 for MRPT 1.5.7 Git: 5902e14cc Wed Apr 24 15:04:01 2019 +0200 at lun oct 28 01:39:17 CET 2019