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::obs
16 {
17 /** Velodyne calibration data, for usage in mrpt::obs::CObservationVelodyneScan
18  *
19  * It is mandatory to use some calibration data to convert Velodyne scans into
20  * 3D point clouds. Users should
21  * normally use the XML files provided by the manufacturer with each scanner,
22  * but default calibration files can be
23  * loaded with \a VelodyneCalibration::LoadDefaultCalibration().
24  *
25  * \note New in MRPT 1.4.0
26  * \sa CObservationVelodyneScan, CVelodyneScanner
27  * \ingroup mrpt_obs_grp
28  */
30 {
31  /** Default ctor (leaves all empty) */
33 
34  /** Returns true if no calibration has been loaded yet */
35  bool empty() const;
36  /** Clear all previous contents */
37  void clear();
38 
39  /** Loads default calibration files for common LIDAR models.
40  * \param[in] lidar_model Valid model names are: `VLP16`, `HDL32`
41  * \return It always return a calibration structure, but it may be empty if
42  * the model name is unknown. See \a empty()
43  * \note Default files can be inspected in `[MRPT_SRC or
44  * /usr]/share/mrpt/config_files/rawlog-grabber/velodyne_default_calib_{*}.xml`
45  */
47  const std::string& lidar_model);
48 
49  /** Loads calibration from file, in the format supplied by the manufacturer.
50  * \return false on any error, true on success */
51  bool loadFromXMLFile(const std::string& velodyne_calibration_xml_filename);
52  /** Loads calibration from a string containing an entire XML calibration
53  * file. \sa loadFromXMLFile \return false on any error, true on success */
54  bool loadFromXMLText(const std::string& xml_file_contents);
55 
56 // Pragma to ensure we can safely serialize some of these structures
57 #pragma pack(push, 1)
59  {
64 
65  PerLaserCalib();
66  };
67 #pragma pack(pop)
68 
69  std::vector<PerLaserCalib> laser_corrections;
70 
71  private:
72  bool internal_loadFromXMLNode(void* node);
73 };
74 }
75 #endif
76 
77 
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
This namespace contains representation of robot actions and observations.
GLsizei const GLchar ** string
Definition: glext.h:4101
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: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020