Main MRPT website > C++ reference for MRPT 1.5.9
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 30 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...
 

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 42 of file VelodyneCalibration.cpp.

Member Function Documentation

◆ clear()

void VelodyneCalibration::clear ( )

Clear all previous contents.

Definition at line 187 of file VelodyneCalibration.cpp.

References laser_corrections.

Referenced by internal_loadFromXMLNode().

◆ empty()

bool VelodyneCalibration::empty ( ) const

Returns true if no calibration has been loaded yet.

Definition at line 183 of file VelodyneCalibration.cpp.

References laser_corrections.

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

◆ 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
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 195 of file VelodyneCalibration.cpp.

References cache_default_calibs, velodyne_default_calib_HDL32, and velodyne_default_calib_VLP16.

◆ loadFromXMLFile()

bool VelodyneCalibration::loadFromXMLFile ( const std::string velodyne_calibration_xml_filename)

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 162 of file VelodyneCalibration.cpp.

References XMLResults::error, eXMLErrorNone, XMLNode::getError(), internal_loadFromXMLNode(), XMLResults::nColumn, XMLResults::nLine, and XMLNode::parseFile().

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

◆ 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 138 of file VelodyneCalibration.cpp.

References XMLResults::error, eXMLErrorNone, XMLNode::getError(), internal_loadFromXMLNode(), XMLResults::nColumn, XMLResults::nLine, and XMLNode::parseString().

Member Data Documentation

◆ laser_corrections

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



Page generated by Doxygen 1.8.14 for MRPT 1.5.9 Git: 690a4699f Wed Apr 15 19:29:53 2020 +0200 at miƩ abr 15 19:30:12 CEST 2020