Struct VelodyneCalibration
Defined in File VelodyneCalibration.h
Nested Relationships
Nested Types
Struct Documentation
-
struct VelodyneCalibration
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().
See also
CObservationVelodyneScan, CVelodyneScanner
Note
New in MRPT 1.4.0
Public Functions
-
VelodyneCalibration()
Default ctor (leaves all empty)
-
bool empty() const
Returns true if no calibration has been loaded yet
-
void clear()
Clear all previous contents
-
bool loadFromXMLFile(const std::string &velodyne_calibration_xml_filename)
Loads calibration from file, in the format supplied by the manufacturer.
- Returns:
false on any error, true on success
-
bool loadFromXMLText(const std::string &xml_file_contents)
Loads calibration from a string containing an entire XML calibration file.
See also
- Returns:
false on any error, true on success
-
bool loadFromYAMLText(const std::string &yaml_file_contents)
Loads calibration from a string containing an entire YAML calibration file.
See also
- Returns:
false on any error, true on success
-
bool loadFromYAMLFile(const std::string &velodyne_calib_yaml_filename)
Loads calibration from a YAML calibration file.
See also
- Returns:
false on any error, true on success
Public Members
-
std::vector<PerLaserCalib> laser_corrections
Public Static Functions
-
static const VelodyneCalibration &LoadDefaultCalibration(const std::string &lidar_model)
Loads default calibration files for common LIDAR models.
Note
Default files can be inspected in
[MRPT_SRC or /usr]/share/mrpt/config_files/rawlog-grabber/velodyne_default_calib_{*}.xml- Parameters:
lidar_model – [in] Valid model names are:
VLP16,HDL32,HDL64- Returns:
It always return a calibration structure, but it may be empty if the model name is unknown. See empty()
-
struct PerLaserCalib
Public Functions
-
PerLaserCalib()
Public Members
-
double azimuthCorrection = {.0}
-
double verticalCorrection = {.0}
-
double distanceCorrection = {.0}
-
double verticalOffsetCorrection = {.0}
-
double horizontalOffsetCorrection = {.0}
-
double sinVertCorrection = {.0}
-
double cosVertCorrection = {1.0}
-
double sinVertOffsetCorrection = {.0}
-
double cosVertOffsetCorrection = {1.0}
-
PerLaserCalib()
-
VelodyneCalibration()