Go to the documentation of this file.
9 #ifndef VelodyneCalibration_H
10 #define VelodyneCalibration_H
bool loadFromXMLFile(const std::string &velodyne_calibration_xml_filename)
Loads calibration from file, in the format supplied by the manufacturer.
bool internal_loadFromXMLNode(void *node)
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
bool empty() const
Returns true if no calibration has been loaded yet.
VelodyneCalibration()
Default ctor (leaves all empty)
double verticalOffsetCorrection
double sinVertOffsetCorrection
double distanceCorrection
Velodyne calibration data, for usage in mrpt::obs::CObservationVelodyneScan.
double verticalCorrection
std::vector< PerLaserCalib > laser_corrections
double cosVertOffsetCorrection
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.
GLsizei const GLchar ** string
void clear()
Clear all previous contents.
double horizontalOffsetCorrection
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 | |