class mola::KittiOdometryDataset

Overview

RawDataSource from Kitti odometry/SLAM datasets. Each “sequence” directory contains these sensor streams:

  • image_0 & image_1 : A grayscale stereo camera pair

  • image_2 & image_3 : An RGB stereo camera pair

  • lidar : Velodyne 3D LIDAR

  • Ground truth poses

If the option clouds_as_organized_points is true, point cloud are published as mrpt::obs::CObservationRotatingScan. Otherwise (default), they are published as mrpt::obs::CObservationPointCloud with X,Y,Z,I channels.

The sequence to load is determined by the sequence parameter (e.g. via config yaml file), from these possible values:

sequence: 00|01|02|...|20|21

Expected contents under base_dir directory:

KITTI/
├── poses        # ground truth poses
  ├── 00.txt
  ├── 01.txt
   ...
  ├── 09.txt
  └── 10.txt

├── sequences
    00
    ├── calib.txt
    ├── times.txt
    ├── image_0
    |   ├── 000000.png
    |   ├── 000001.png
    |   ...
    ├── image_1
    |   ├── 000000.png
    |   ├── 000001.png
    |   ...
    └── velodyne
        ├── 000000.bin
        ├── 000001.bin
... ...    ...
    01
    ├── calib.txt
... ...    ...
  • Example base_dir : /mnt/storage/KITTI/ (normally read from environment variable KITTI_BASE_DIR in mola-cli launch files).

#include <KittiOdometryDataset.h>

class KittiOdometryDataset:
    public mola::RawDataSourceBase,
    public mola::OfflineDatasetSource,
    public mola::Dataset_UI
{
public:
    // fields

    double VERTICAL_ANGLE_OFFSET = mrpt::DEG2RAD(0.205);

    // methods

    virtual void spinOnce();
    virtual bool hasGroundTruthTrajectory() const;
    virtual trajectory_t getGroundTruthTrajectory() const;
    std::shared_ptr<mrpt::obs::CObservation> getPointCloud(timestep_t step) const;

    std::shared_ptr<mrpt::obs::CObservationImage> getImage(
        const unsigned int cam_idx,
        timestep_t step
        ) const;

    virtual size_t datasetSize() const;
    virtual mrpt::obs::CSensoryFrame::Ptr datasetGetObservations(size_t timestep) const;
    virtual size_t datasetUI_size() const;
    virtual size_t datasetUI_lastQueriedTimestep() const;
    virtual double datasetUI_playback_speed() const;
    virtual void datasetUI_playback_speed(double speed);
    virtual bool datasetUI_paused() const;
    virtual void datasetUI_paused(bool paused);
    virtual void datasetUI_teleport(size_t timestep);
};

Inherited Members

public:
    // structs

    struct SensorViewerImpl;

    // methods

    virtual void initialize(const Yaml& cfg) = 0;
    virtual size_t datasetSize() const = 0;
    virtual mrpt::obs::CSensoryFrame::Ptr datasetGetObservations(size_t timestep) const = 0;
    virtual bool hasGroundTruthTrajectory() const;
    virtual trajectory_t getGroundTruthTrajectory() const;
    virtual size_t datasetUI_size() const = 0;
    virtual size_t datasetUI_lastQueriedTimestep() const = 0;
    virtual double datasetUI_playback_speed() const = 0;
    virtual void datasetUI_playback_speed(double speed) = 0;
    virtual bool datasetUI_paused() const = 0;
    virtual void datasetUI_paused(bool paused) = 0;
    virtual void datasetUI_teleport(size_t timestep) = 0;

Fields

double VERTICAL_ANGLE_OFFSET = mrpt::DEG2RAD(0.205)

See: “IMLS-SLAM: scan-to-model matching based on 3D data”, JE Deschaud, 2018.

Methods

virtual void spinOnce()

Runs any required action on a timely manner

virtual bool hasGroundTruthTrajectory() const

Returns true if a groundtruth is available for the vehicle trajectory.

See also:

getGroundTruthTrajectory()

virtual trajectory_t getGroundTruthTrajectory() const

If hasGroundTruthTrajectory() returns true, this returns the dataset groundtruth for the vehicle trajectory.

Note that timestamps for datasets are not wall-clock time (“now”), but old timestamps of when original observations were grabbed.

See also:

hasGroundTruthTrajectory()

std::shared_ptr<mrpt::obs::CObservation> getPointCloud(timestep_t step) const

Direct programmatic access to dataset observations. The type of the lidar observation can be either:

  • mrpt::obs::CObservationPointCloud (clouds_as_organized_points_ =false)

  • mrpt::obs::CObservationRotatingScan (clouds_as_organized_points_ =true)

virtual size_t datasetSize() const

Number of different time steps available to call getObservations()

virtual mrpt::obs::CSensoryFrame::Ptr datasetGetObservations(size_t timestep) const

Returns the set of observations available for the given time step.

virtual size_t datasetUI_size() const

Number of different time steps available to call getObservations()

virtual size_t datasetUI_lastQueriedTimestep() const

Returns the latest requested observation, range [0, datasetSize()]

virtual void datasetUI_teleport(size_t timestep)

Forces continue replaying in this moment in time