class mola::Kitti360Dataset

Overview

RawDataSource from Kitti-360 datasets.

Each “sequence” directory contains these sensor streams:

  • image_0 & image_1 : Perspective cameras

  • image_2 & image_3 : Fish-eye cameras (TO-DO)

  • lidar : Velodyne 3D LIDAR. Published as mrpt::obs::CObservationPointCloud with X,Y,Z,I,T channels. The timestamp (T) channel is estimated from azimuth of points (if generate_lidar_timestamps param is true), with generated timestamps between [-0.05,+0.05] seconds.

  • Ground truth poses

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

sequence: 00|02|03|04|05|06|07|08|09|10|18|test_0|test_1|test_2|test_3

Expected contents under base_dir directory (the result of using the download scripts provided by the KITTI-360 web):

KITTI-360/
├── calibration
  ├── calib_cam_to_pose.txt
  ├── calib_cam_to_velo.txt
  ├── calib_sick_to_velo.txt
  ├── image_02.yaml
  ├── image_03.yaml
  └── perspective.txt

├── data_3d_raw
    2013_05_28_drive_00xx_sync
    ├── cam0_to_world.txt
    ├── poses.txt
    └── velodyne_points
        ├── timestamps.txt
        └── data
            ├── 0000000000.bin
            ├── 0000000001.bin
... ...           ...
├── data_2d_raw
   ├── 2013_05_28_drive_00xx_sync
      ├── image_00
         ├── data_rect
             0000000000.png
             0000000001.png
            ...
         └── timestamps.txt
      └── image_01
          ├── data_rect
              0000000000.png
              0000000001.png
             ...
          └── timestamps.txt
... ...
├── data_poses/
   ├── 2013_05_28_drive_00xx_sync
      ├── cam0_to_world.txt
      └── poses.txt
... ...
└──  data_3d_test_slam/
    ├── test_0
       └── 2013_05_28_drive_0008_sync
           └── velodyne_points
               ├── data
               └── timestamps.txt
    ├── test_1
       └── 2013_05_28_drive_0008_sync
           └── velodyne_points
               ├── data
               └── timestamps.txt
    ├── test_2
       └── 2013_05_28_drive_0004_sync
           └── velodyne_points
               ├── data
               └── timestamps.txt
    └── test_3
        └── 2013_05_28_drive_0002_sync
            └── velodyne_points
                ├── data
                └── timestamps.txt
  • Example base_dir : /mnt/storage/KITTI-360/ (normally read from environment variable KITTI360_DATASET in mola-cli launch files).

  • Sequences: 01, 02, etc.

#include <Kitti360Dataset.h>

class Kitti360Dataset:
    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