MRPT
1.9.9
|
Velodyne calibration data, for usage in mrpt::obs::CObservationVelodyneScan.
It is mandatory to use some calibration data to convert Velodyne scans into 3D point clouds. Users should normally use the XML files provided by the manufacturer with each scanner, but default calibration files can be loaded with VelodyneCalibration::LoadDefaultCalibration().
Definition at line 28 of file VelodyneCalibration.h.
#include <mrpt/obs/VelodyneCalibration.h>
Classes | |
struct | PerLaserCalib |
Public Member Functions | |
VelodyneCalibration () | |
Default ctor (leaves all empty) More... | |
bool | empty () const |
Returns true if no calibration has been loaded yet. More... | |
void | clear () |
Clear all previous contents. More... | |
bool | loadFromXMLFile (const std::string &velodyne_calibration_xml_filename) |
Loads calibration from file, in the format supplied by the manufacturer. More... | |
bool | loadFromXMLText (const std::string &xml_file_contents) |
Loads calibration from a string containing an entire XML calibration file. More... | |
bool | loadFromYAMLText (const std::string &yaml_file_contents) |
Loads calibration from a string containing an entire YAML calibration file. More... | |
bool | loadFromYAMLFile (const std::string &velodyne_calib_yaml_filename) |
Loads calibration from a YAML calibration file. More... | |
Static Public Member Functions | |
static const VelodyneCalibration & | LoadDefaultCalibration (const std::string &lidar_model) |
Loads default calibration files for common LIDAR models. More... | |
Public Attributes | |
std::vector< PerLaserCalib > | laser_corrections |
Private Member Functions | |
bool | internal_loadFromXMLNode (void *node) |
VelodyneCalibration::VelodyneCalibration | ( | ) |
Default ctor (leaves all empty)
Definition at line 41 of file VelodyneCalibration.cpp.
void VelodyneCalibration::clear | ( | ) |
Clear all previous contents.
Definition at line 304 of file VelodyneCalibration.cpp.
References laser_corrections.
Referenced by internal_loadFromXMLNode(), and loadFromYAMLText().
bool VelodyneCalibration::empty | ( | ) | const |
Returns true if no calibration has been loaded yet.
Definition at line 303 of file VelodyneCalibration.cpp.
References laser_corrections.
Referenced by mrpt::hwdrivers::CVelodyneScanner::initialize().
|
private |
Definition at line 42 of file VelodyneCalibration.cpp.
References ASSERT_ABOVEEQ_, mrpt::obs::VelodyneCalibration::PerLaserCalib::azimuthCorrection, clear(), mrpt::obs::VelodyneCalibration::PerLaserCalib::cosVertCorrection, mrpt::obs::VelodyneCalibration::PerLaserCalib::cosVertOffsetCorrection, mrpt::DEG2RAD(), mrpt::obs::VelodyneCalibration::PerLaserCalib::distanceCorrection, XMLNode::getChildNode(), XMLNode::getText(), mrpt::obs::VelodyneCalibration::PerLaserCalib::horizontalOffsetCorrection, XMLNode::isEmpty(), laser_corrections, mrpt::obs::VelodyneCalibration::PerLaserCalib::sinVertCorrection, mrpt::obs::VelodyneCalibration::PerLaserCalib::sinVertOffsetCorrection, mrpt::obs::VelodyneCalibration::PerLaserCalib::verticalCorrection, and mrpt::obs::VelodyneCalibration::PerLaserCalib::verticalOffsetCorrection.
Referenced by loadFromXMLFile(), and loadFromXMLText().
|
static |
Loads default calibration files for common LIDAR models.
[in] | lidar_model | Valid model names are: VLP16 , HDL32 , HDL64 |
[MRPT_SRC or /usr]/share/mrpt/config_files/rawlog-grabber/velodyne_default_calib_{*}.xml
Definition at line 309 of file VelodyneCalibration.cpp.
References cache_default_calibs, velodyne_default_calib_HDL32, velodyne_default_calib_HDL64E_S3, and velodyne_default_calib_VLP16.
bool VelodyneCalibration::loadFromXMLFile | ( | const std::string & | velodyne_calibration_xml_filename | ) |
Loads calibration from file, in the format supplied by the manufacturer.
Loads calibration from file.
Definition at line 193 of file VelodyneCalibration.cpp.
References eXMLErrorNone, XMLNode::getError(), internal_loadFromXMLNode(), XMLNode::parseFile(), and results.
Referenced by mrpt::hwdrivers::CVelodyneScanner::loadCalibrationFile().
bool VelodyneCalibration::loadFromXMLText | ( | const std::string & | xml_file_contents | ) |
Loads calibration from a string containing an entire XML calibration file.
Definition at line 163 of file VelodyneCalibration.cpp.
References eXMLErrorNone, XMLNode::getError(), internal_loadFromXMLNode(), XMLNode::parseString(), and results.
bool VelodyneCalibration::loadFromYAMLFile | ( | const std::string & | velodyne_calib_yaml_filename | ) |
Loads calibration from a YAML calibration file.
Definition at line 276 of file VelodyneCalibration.cpp.
References loadFromYAMLText(), THROW_EXCEPTION, and THROW_EXCEPTION_FMT.
bool VelodyneCalibration::loadFromYAMLText | ( | const std::string & | yaml_file_contents | ) |
Loads calibration from a string containing an entire YAML calibration file.
Definition at line 220 of file VelodyneCalibration.cpp.
References ASSERT_, ASSERT_EQUAL_, mrpt::obs::VelodyneCalibration::PerLaserCalib::azimuthCorrection, clear(), mrpt::obs::VelodyneCalibration::PerLaserCalib::cosVertCorrection, mrpt::obs::VelodyneCalibration::PerLaserCalib::cosVertOffsetCorrection, mrpt::obs::VelodyneCalibration::PerLaserCalib::distanceCorrection, mrpt::obs::VelodyneCalibration::PerLaserCalib::horizontalOffsetCorrection, laser_corrections, mrpt::obs::VelodyneCalibration::PerLaserCalib::sinVertCorrection, mrpt::obs::VelodyneCalibration::PerLaserCalib::sinVertOffsetCorrection, THROW_EXCEPTION, mrpt::obs::VelodyneCalibration::PerLaserCalib::verticalCorrection, and mrpt::obs::VelodyneCalibration::PerLaserCalib::verticalOffsetCorrection.
Referenced by loadFromYAMLFile().
std::vector<PerLaserCalib> mrpt::obs::VelodyneCalibration::laser_corrections |
Definition at line 77 of file VelodyneCalibration.h.
Referenced by clear(), empty(), internal_loadFromXMLNode(), loadFromYAMLText(), and velodyne_scan_to_pointcloud().
Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 8fe78517f Sun Jul 14 19:43:28 2019 +0200 at lun oct 28 02:10:00 CET 2019 |