MRPT  2.0.1
List of all members | Classes | Public Member Functions | Static Public Member Functions | Public Attributes | Private Member Functions
mrpt::obs::VelodyneCalibration Struct Reference

Detailed Description

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().

Note
New in MRPT 1.4.0
See also
CObservationVelodyneScan, CVelodyneScanner

Definition at line 28 of file VelodyneCalibration.h.

#include <mrpt/obs/VelodyneCalibration.h>

Classes

struct  PerLaserCalib
 

Public Member Functions

 VelodyneCalibration ()
 Default ctor (leaves all empty) More...
 
bool empty () const
 Returns true if no calibration has been loaded yet. More...
 
void clear ()
 Clear all previous contents. More...
 
bool loadFromXMLFile (const std::string &velodyne_calibration_xml_filename)
 Loads calibration from file, in the format supplied by the manufacturer. More...
 
bool loadFromXMLText (const std::string &xml_file_contents)
 Loads calibration from a string containing an entire XML calibration file. More...
 
bool loadFromYAMLText (const std::string &yaml_file_contents)
 Loads calibration from a string containing an entire YAML calibration file. More...
 
bool loadFromYAMLFile (const std::string &velodyne_calib_yaml_filename)
 Loads calibration from a YAML calibration file. More...
 

Static Public Member Functions

static const VelodyneCalibrationLoadDefaultCalibration (const std::string &lidar_model)
 Loads default calibration files for common LIDAR models. More...
 

Public Attributes

std::vector< PerLaserCaliblaser_corrections
 

Private Member Functions

bool internal_loadFromXMLNode (void *node)
 

Constructor & Destructor Documentation

◆ VelodyneCalibration()

VelodyneCalibration::VelodyneCalibration ( )

Default ctor (leaves all empty)

Definition at line 74 of file VelodyneCalibration.cpp.

Member Function Documentation

◆ clear()

void VelodyneCalibration::clear ( )

Clear all previous contents.

Definition at line 324 of file VelodyneCalibration.cpp.

References laser_corrections.

Referenced by internal_loadFromXMLNode(), and loadFromYAMLText().

Here is the caller graph for this function:

◆ empty()

bool VelodyneCalibration::empty ( ) const

Returns true if no calibration has been loaded yet.

Definition at line 323 of file VelodyneCalibration.cpp.

References laser_corrections.

Referenced by mrpt::hwdrivers::CVelodyneScanner::initialize().

Here is the caller graph for this function:

◆ internal_loadFromXMLNode()

bool VelodyneCalibration::internal_loadFromXMLNode ( void *  node)
private

◆ LoadDefaultCalibration()

const VelodyneCalibration & VelodyneCalibration::LoadDefaultCalibration ( const std::string &  lidar_model)
static

Loads default calibration files for common LIDAR models.

Parameters
[in]lidar_modelValid 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()
Note
Default files can be inspected in [MRPT_SRC or /usr]/share/mrpt/config_files/rawlog-grabber/velodyne_default_calib_{*}.xml

Definition at line 329 of file VelodyneCalibration.cpp.

References cache_default_calibs, velodyne_default_calib_HDL32, velodyne_default_calib_HDL64E_S3, and velodyne_default_calib_VLP16.

◆ loadFromXMLFile()

bool VelodyneCalibration::loadFromXMLFile ( const std::string &  velodyne_calibration_xml_fil)

Loads calibration from file, in the format supplied by the manufacturer.

Loads calibration from file.

Returns
false on any error, true on success

Definition at line 205 of file VelodyneCalibration.cpp.

References internal_loadFromXMLNode(), and THROW_EXCEPTION.

Referenced by mrpt::hwdrivers::CVelodyneScanner::loadCalibrationFile().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ loadFromXMLText()

bool VelodyneCalibration::loadFromXMLText ( const std::string &  xml_file_contents)

Loads calibration from a string containing an entire XML calibration file.

See also
loadFromXMLFile
Returns
false on any error, true on success

Definition at line 166 of file VelodyneCalibration.cpp.

References internal_loadFromXMLNode(), and THROW_EXCEPTION.

Here is the call graph for this function:

◆ loadFromYAMLFile()

bool VelodyneCalibration::loadFromYAMLFile ( const std::string &  velodyne_calib_yaml_filename)

Loads calibration from a YAML calibration file.

See also
loadFromYAMLText, loadFromXMLFile
Returns
false on any error, true on success

Definition at line 296 of file VelodyneCalibration.cpp.

References loadFromYAMLText(), THROW_EXCEPTION, and THROW_EXCEPTION_FMT.

Here is the call graph for this function:

◆ loadFromYAMLText()

bool VelodyneCalibration::loadFromYAMLText ( const std::string &  yaml_file_contents)

Loads calibration from a string containing an entire YAML calibration file.

See also
loadFromYAMLFile, loadFromXMLFile
Returns
false on any error, true on success

Definition at line 240 of file VelodyneCalibration.cpp.

References ASSERT_, ASSERT_EQUAL_, mrpt::obs::VelodyneCalibration::PerLaserCalib::azimuthCorrection, clear(), mrpt::obs::VelodyneCalibration::PerLaserCalib::cosVertCorrection, mrpt::obs::VelodyneCalibration::PerLaserCalib::cosVertOffsetCorrection, mrpt::obs::VelodyneCalibration::PerLaserCalib::distanceCorrection, mrpt::obs::VelodyneCalibration::PerLaserCalib::horizontalOffsetCorrection, laser_corrections, mrpt::obs::VelodyneCalibration::PerLaserCalib::sinVertCorrection, mrpt::obs::VelodyneCalibration::PerLaserCalib::sinVertOffsetCorrection, THROW_EXCEPTION, mrpt::obs::VelodyneCalibration::PerLaserCalib::verticalCorrection, and mrpt::obs::VelodyneCalibration::PerLaserCalib::verticalOffsetCorrection.

Referenced by loadFromYAMLFile().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ laser_corrections

std::vector<PerLaserCalib> mrpt::obs::VelodyneCalibration::laser_corrections



Page generated by Doxygen 1.8.14 for MRPT 2.0.1 Git: 0fef1a6d7 Fri Apr 3 23:00:21 2020 +0200 at vie abr 3 23:20:28 CEST 2020