struct mrpt::obs::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().

New in MRPT 1.4.0

See also:

CObservationVelodyneScan, CVelodyneScanner

#include <mrpt/obs/VelodyneCalibration.h>

struct VelodyneCalibration
{
    // structs

    struct PerLaserCalib;

    //
fields

    std::vector<PerLaserCalib> laser_corrections;

    // construction

    VelodyneCalibration();

    //
methods

    bool empty() const;
    void clear();
    bool loadFromXMLFile(const std::string& velodyne_calibration_xml_filename);
    bool loadFromXMLText(const std::string& xml_file_contents);
    bool loadFromYAMLText(const std::string& yaml_file_contents);
    bool loadFromYAMLFile(const std::string& velodyne_calib_yaml_filename);
    static const VelodyneCalibration& LoadDefaultCalibration(const std::string& lidar_model);
};

Construction

VelodyneCalibration()

Default ctor (leaves all empty)

Methods

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.

Loads calibration from file.

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.

Returns:

false on any error, true on success

See also:

loadFromXMLFile

bool loadFromYAMLText(const std::string& yaml_file_contents)

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

Returns:

false on any error, true on success

See also:

loadFromYAMLFile, loadFromXMLFile

bool loadFromYAMLFile(const std::string& velodyne_calib_yaml_filename)

Loads calibration from a YAML calibration file.

Returns:

false on any error, true on success

See also:

loadFromYAMLText, loadFromXMLFile

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

Loads default calibration files for common LIDAR models.

Default files can be inspected in [MRPT_SRC or /usr]/share/mrpt/config_files/rawlog-grabber/velodyne_default_calib_{*}.xml

Parameters:

lidar_model

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