46         const std::string& lidar_model);
    50     bool loadFromXMLFile(
const std::string& velodyne_calibration_xml_filename);
 Velodyne calibration data, for usage in mrpt::obs::CObservationVelodyneScan. 
 
bool loadFromXMLFile(const std::string &velodyne_calibration_xml_filename)
Loads calibration from file, in the format supplied by the manufacturer. 
 
double verticalOffsetCorrection
 
bool loadFromXMLText(const std::string &xml_file_contents)
Loads calibration from a string containing an entire XML calibration file. 
 
VelodyneCalibration()
Default ctor (leaves all empty) 
 
void clear()
Clear all previous contents. 
 
bool internal_loadFromXMLNode(void *node)
 
std::vector< PerLaserCalib > laser_corrections
 
bool loadFromYAMLText(const std::string &yaml_file_contents)
Loads calibration from a string containing an entire YAML calibration file. 
 
This namespace contains representation of robot actions and observations. 
 
double sinVertOffsetCorrection
 
bool empty() const
Returns true if no calibration has been loaded yet. 
 
double distanceCorrection
 
double verticalCorrection
 
double horizontalOffsetCorrection
 
double cosVertOffsetCorrection
 
bool loadFromYAMLFile(const std::string &velodyne_calib_yaml_filename)
Loads calibration from a YAML calibration file. 
 
static const VelodyneCalibration & LoadDefaultCalibration(const std::string &lidar_model)
Loads default calibration files for common LIDAR models.