Class KittiOdometryDataset
- Defined in File KittiOdometryDataset.h 
Inheritance Relationships
Base Types
- public mola::RawDataSourceBase
- public mola::OfflineDatasetSource
- public mola::Dataset_UI
Class Documentation
- 
class KittiOdometryDataset : public mola::RawDataSourceBase, public mola::OfflineDatasetSource, public mola::Dataset_UI
- 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_pointsis 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 - sequenceparameter (e.g. via config yaml file), from these possible values:- sequence: 00|01|02|...|20|21 - Expected contents under - base_dirdirectory:- 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_DIRin mola-cli launch files).
 - Public Functions - 
KittiOdometryDataset()
 - 
~KittiOdometryDataset() override = default
 - 
KittiOdometryDataset(const KittiOdometryDataset&) = delete
 - 
KittiOdometryDataset &operator=(const KittiOdometryDataset&) = delete
 - 
KittiOdometryDataset(KittiOdometryDataset&&) = delete
 - 
KittiOdometryDataset &operator=(KittiOdometryDataset&&) = delete
 - 
virtual void spinOnce() override
 - 
inline virtual bool hasGroundTruthTrajectory() const override
 - 
inline virtual 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
 - 
virtual size_t datasetSize() const override
 - 
virtual mrpt::obs::CSensoryFrame::Ptr datasetGetObservations(size_t timestep) const override
 - 
inline virtual size_t datasetUI_size() const override
 - 
inline virtual 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 virtual 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 - 
virtual void initialize_rds(const Yaml &cfg) override