Main MRPT website > C++ reference for MRPT 1.9.9
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 <string>
14 #include <vector>
15 
16 namespace mrpt
17 {
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
23  * 3D point clouds. Users should
24  * normally use the XML files provided by the manufacturer with each scanner,
25  * but default calibration files can be
26  * loaded with \a VelodyneCalibration::LoadDefaultCalibration().
27  *
28  * \note New in MRPT 1.4.0
29  * \sa CObservationVelodyneScan, CVelodyneScanner
30  * \ingroup mrpt_obs_grp
31  */
33 {
34  /** Default ctor (leaves all empty) */
36 
37  /** Returns true if no calibration has been loaded yet */
38  bool empty() const;
39  /** Clear all previous contents */
40  void clear();
41 
42  /** Loads default calibration files for common LIDAR models.
43  * \param[in] lidar_model Valid model names are: `VLP16`, `HDL32`
44  * \return It always return a calibration structure, but it may be empty if
45  * the model name is unknown. See \a empty()
46  * \note Default files can be inspected in `[MRPT_SRC or
47  * /usr]/share/mrpt/config_files/rawlog-grabber/velodyne_default_calib_{*}.xml`
48  */
50  const std::string& lidar_model);
51 
52  /** Loads calibration from file, in the format supplied by the manufacturer.
53  * \return false on any error, true on success */
54  bool loadFromXMLFile(const std::string& velodyne_calibration_xml_filename);
55  /** Loads calibration from a string containing an entire XML calibration
56  * file. \sa loadFromXMLFile \return false on any error, true on success */
57  bool loadFromXMLText(const std::string& xml_file_contents);
58 
59 // Pragma to ensure we can safely serialize some of these structures
60 #pragma pack(push, 1)
62  {
67 
68  PerLaserCalib();
69  };
70 #pragma pack(pop)
71 
72  std::vector<PerLaserCalib> laser_corrections;
73 
74  private:
75  bool internal_loadFromXMLNode(void* node);
76 };
77 } // End of namespace
78 } // End of namespace
79 
80 #endif
Velodyne calibration data, for usage in mrpt::obs::CObservationVelodyneScan.
bool loadFromXMLFile(const std::string &velodyne_calibration_xml_filename)
Loads calibration from file, in the format supplied by the manufacturer.
bool loadFromXMLText(const std::string &xml_file_contents)
Loads calibration from a string containing an entire XML calibration file.
VelodyneCalibration()
Default ctor (leaves all empty)
void clear()
Clear all previous contents.
std::vector< PerLaserCalib > laser_corrections
GLsizei const GLchar ** string
Definition: glext.h:4101
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
bool empty() const
Returns true if no calibration has been loaded yet.
static const VelodyneCalibration & LoadDefaultCalibration(const std::string &lidar_model)
Loads default calibration files for common LIDAR models.



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019