MRPT  2.0.4
VelodyneCalibration.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #pragma once
10 
11 #include <string>
12 #include <vector>
13 
14 namespace mrpt::obs
15 {
16 /** Velodyne calibration data, for usage in mrpt::obs::CObservationVelodyneScan
17  *
18  * It is mandatory to use some calibration data to convert Velodyne scans into
19  * 3D point clouds. Users should
20  * normally use the XML files provided by the manufacturer with each scanner,
21  * but default calibration files can be
22  * loaded with \a VelodyneCalibration::LoadDefaultCalibration().
23  *
24  * \note New in MRPT 1.4.0
25  * \sa CObservationVelodyneScan, CVelodyneScanner
26  * \ingroup mrpt_obs_grp
27  */
29 {
30  /** Default ctor (leaves all empty) */
32 
33  /** Returns true if no calibration has been loaded yet */
34  bool empty() const;
35  /** Clear all previous contents */
36  void clear();
37 
38  /** Loads default calibration files for common LIDAR models.
39  * \param[in] lidar_model Valid model names are: `VLP16`, `HDL32`, `HDL64`
40  * \return It always return a calibration structure, but it may be empty if
41  * the model name is unknown. See \a empty()
42  * \note Default files can be inspected in `[MRPT_SRC or
43  * /usr]/share/mrpt/config_files/rawlog-grabber/velodyne_default_calib_{*}.xml`
44  */
46  const std::string& lidar_model);
47 
48  /** Loads calibration from file, in the format supplied by the manufacturer.
49  * \return false on any error, true on success */
50  bool loadFromXMLFile(const std::string& velodyne_calibration_xml_filename);
51  /** Loads calibration from a string containing an entire XML calibration
52  * file. \sa loadFromXMLFile \return false on any error, true on success */
53  bool loadFromXMLText(const std::string& xml_file_contents);
54  /** Loads calibration from a string containing an entire YAML calibration
55  * file. \sa loadFromYAMLFile, loadFromXMLFile \return false on any error,
56  * true on success */
57  bool loadFromYAMLText(const std::string& yaml_file_contents);
58  /** Loads calibration from a YAML calibration file.
59  * \sa loadFromYAMLText, loadFromXMLFile
60  * \return false on any error, true on success */
61  bool loadFromYAMLFile(const std::string& velodyne_calib_yaml_filename);
62 
63 // Pragma to ensure we can safely serialize some of these structures
64 #pragma pack(push, 1)
66  {
72 
74  };
75 #pragma pack(pop)
76 
77  std::vector<PerLaserCalib> laser_corrections;
78 
79  private:
80  bool internal_loadFromXMLNode(void* node);
81 };
82 } // namespace mrpt::obs
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:205
mrpt::obs::VelodyneCalibration::internal_loadFromXMLNode
bool internal_loadFromXMLNode(void *node)
Definition: VelodyneCalibration.cpp:75
mrpt::obs::VelodyneCalibration::PerLaserCalib::azimuthCorrection
double azimuthCorrection
Definition: VelodyneCalibration.h:67
mrpt::obs::VelodyneCalibration::PerLaserCalib
Definition: VelodyneCalibration.h:66
mrpt::obs::VelodyneCalibration::empty
bool empty() const
Returns true if no calibration has been loaded yet.
Definition: VelodyneCalibration.cpp:323
mrpt::obs
This namespace contains representation of robot actions and observations.
Definition: CParticleFilter.h:18
mrpt::obs::VelodyneCalibration::PerLaserCalib::PerLaserCalib
PerLaserCalib()
mrpt::obs::VelodyneCalibration::loadFromYAMLFile
bool loadFromYAMLFile(const std::string &velodyne_calib_yaml_filename)
Loads calibration from a YAML calibration file.
Definition: VelodyneCalibration.cpp:296
mrpt::obs::VelodyneCalibration::VelodyneCalibration
VelodyneCalibration()
Default ctor (leaves all empty)
Definition: VelodyneCalibration.cpp:74
mrpt::obs::VelodyneCalibration::loadFromYAMLText
bool loadFromYAMLText(const std::string &yaml_file_contents)
Loads calibration from a string containing an entire YAML calibration file.
Definition: VelodyneCalibration.cpp:240
mrpt::obs::VelodyneCalibration::PerLaserCalib::verticalOffsetCorrection
double verticalOffsetCorrection
Definition: VelodyneCalibration.h:69
mrpt::obs::VelodyneCalibration::PerLaserCalib::sinVertOffsetCorrection
double sinVertOffsetCorrection
Definition: VelodyneCalibration.h:71
mrpt::obs::VelodyneCalibration::PerLaserCalib::sinVertCorrection
double sinVertCorrection
Definition: VelodyneCalibration.h:70
mrpt::obs::VelodyneCalibration::PerLaserCalib::distanceCorrection
double distanceCorrection
Definition: VelodyneCalibration.h:68
mrpt::obs::VelodyneCalibration
Velodyne calibration data, for usage in mrpt::obs::CObservationVelodyneScan.
Definition: VelodyneCalibration.h:29
mrpt::obs::VelodyneCalibration::PerLaserCalib::verticalCorrection
double verticalCorrection
Definition: VelodyneCalibration.h:67
mrpt::obs::VelodyneCalibration::laser_corrections
std::vector< PerLaserCalib > laser_corrections
Definition: VelodyneCalibration.h:77
mrpt::obs::VelodyneCalibration::PerLaserCalib::cosVertOffsetCorrection
double cosVertOffsetCorrection
Definition: VelodyneCalibration.h:71
mrpt::obs::VelodyneCalibration::PerLaserCalib::cosVertCorrection
double cosVertCorrection
Definition: VelodyneCalibration.h:70
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:166
mrpt::obs::VelodyneCalibration::LoadDefaultCalibration
static const VelodyneCalibration & LoadDefaultCalibration(const std::string &lidar_model)
Loads default calibration files for common LIDAR models.
Definition: VelodyneCalibration.cpp:329
mrpt::obs::VelodyneCalibration::clear
void clear()
Clear all previous contents.
Definition: VelodyneCalibration.cpp:324
mrpt::obs::VelodyneCalibration::PerLaserCalib::horizontalOffsetCorrection
double horizontalOffsetCorrection
Definition: VelodyneCalibration.h:69



Page generated by Doxygen 1.8.18 for MRPT 2.0.4 at Thu Sep 24 07:14:18 UTC 2020