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



Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST