Class Kitti360Dataset
Defined in File Kitti360Dataset.h
Inheritance Relationships
Base Types
public RawDataSourceBase
public OfflineDatasetSource
public Dataset_UI
Class Documentation
-
class Kitti360Dataset : public RawDataSourceBase, public OfflineDatasetSource, public Dataset_UI
RawDataSource from Kitti-360 datasets.
Each “sequence” directory contains these sensor streams:
image_0
&image_1
: Perspective camerasimage_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 (ifgenerate_lidar_timestamps
param istrue
), 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.
Public Functions
-
Kitti360Dataset()
-
~Kitti360Dataset() override = default
-
void spinOnce() override
-
inline bool hasGroundTruthTrajectory() const override
-
inline trajectory_t getGroundTruthTrajectory() const override
-
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)
-
std::shared_ptr<mrpt::obs::CObservationImage> getImage(const unsigned int cam_idx, timestep_t step) const
-
size_t datasetSize() const override
-
mrpt::obs::CSensoryFrame::Ptr datasetGetObservations(size_t timestep) const override
-
inline size_t datasetUI_size() const override
-
inline size_t datasetUI_lastQueriedTimestep() const override
-
inline double datasetUI_playback_speed() const override
-
inline void datasetUI_playback_speed(double speed) override
-
inline bool datasetUI_paused() const override
-
inline void datasetUI_paused(bool paused) override
-
inline void datasetUI_teleport(size_t timestep) override
Public Members
-
double VERTICAL_ANGLE_OFFSET = mrpt::DEG2RAD(0.205)
See: “IMLS-SLAM: scan-to-model matching based on 3D data”, JE Deschaud, 2018.
Protected Functions
-
void initialize_rds(const Yaml &cfg) override