Go to the documentation of this file.
46 const std::string& lidar_model);
50 bool loadFromXMLFile(
const std::string& velodyne_calibration_xml_filename);
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)
bool empty() const
Returns true if no calibration has been loaded yet.
This namespace contains representation of robot actions and observations.
bool loadFromYAMLFile(const std::string &velodyne_calib_yaml_filename)
Loads calibration from a YAML calibration file.
VelodyneCalibration()
Default ctor (leaves all empty)
bool loadFromYAMLText(const std::string &yaml_file_contents)
Loads calibration from a string containing an entire YAML calibration file.
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.
void clear()
Clear all previous contents.
double horizontalOffsetCorrection
Page generated by Doxygen 1.8.17 for MRPT 2.0.3 at Thu May 21 21:53:32 UTC 2020 | |