Go to the documentation of this file.
9 #ifndef VelodyneCalibration_H
10 #define VelodyneCalibration_H
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
bool internal_loadFromXMLNode(void *node)
double verticalOffsetCorrection
double sinVertOffsetCorrection
bool loadFromXMLText(const std::string &xml_file_contents)
Loads calibration from a string containing an entire XML calibration file.
static const VelodyneCalibration & LoadDefaultCalibration(const std::string &lidar_model)
Loads default calibration files for common LIDAR models.
Velodyne calibration data, for usage in mrpt::obs::CObservationVelodyneScan.
void clear()
Clear all previous contents.
double verticalCorrection
std::vector< PerLaserCalib > laser_corrections
bool empty() const
Returns true if no calibration has been loaded yet.
bool loadFromXMLFile(const std::string &velodyne_calibration_xml_filename)
Loads calibration from file, in the format supplied by the manufacturer.
VelodyneCalibration()
Default ctor (leaves all empty)
Page generated by Doxygen 1.8.20 for MRPT 1.4.0 SVN: at Thu Aug 27 02:40:23 UTC 2020 | | |