cpp-toolbox  0.0.1
A toolbox library for C++
Loading...
Searching...
No Matches
toolbox::io::kitti_odometry_pair_dataset_t< DataType > Class Template Reference

KITTI Odometry frame pair dataset loader. More...

#include <kitti_odometry_pair_dataset.hpp>

Inheritance diagram for toolbox::io::kitti_odometry_pair_dataset_t< DataType >:

Public Types

using pair_type = kitti_odometry_frame_pair_t< DataType >
 
using base_type = dataset_t< kitti_odometry_pair_dataset_t< DataType >, pair_type >
 
- Public Types inherited from toolbox::io::dataset_t< Derived, DataType >
using data_type = DataType
 数据类型别名/Type alias for data type
 

Public Member Functions

 kitti_odometry_pair_dataset_t (const std::string &sequence_path, std::size_t skip=1)
 Constructor.
 
void set_skip (std::size_t skip)
 Set skip parameter.
 
std::size_t get_skip () const
 Get current skip value.
 
void enable_overlap_computation (bool enable)
 Set whether to compute overlap ratio between frames.
 
void set_cache_size (std::size_t size)
 Set maximum pair cache size.
 
std::size_t size_impl () const
 Get number of frame pairs.
 
std::optional< pair_typeat_impl (std::size_t index) const
 Load frame pair at specific index.
 
const kitti_odometry_dataset_t< DataType > & get_base_dataset () const
 Get the underlying base dataset.
 
std::size_t get_source_frame_index (std::size_t pair_index) const
 Get source frame index for a pair.
 
std::size_t get_target_frame_index (std::size_t pair_index) const
 Get target frame index for a pair.
 
void clear_cache () const
 Clear pair cache.
 
std::vector< std::size_t > get_pairs_with_motion (DataType min_translation=0.1, DataType min_rotation=0.01) const
 Get pairs with specific relative motion threshold.
 
- Public Member Functions inherited from toolbox::io::dataset_t< Derived, DataType >
std::size_t size () const
 获取数据集大小/Get the size of the dataset
 
std::optional< DataType > operator[] (std::size_t index) const
 通过下标访问数据/Access data by index
 
std::optional< DataType > at (std::size_t index) const
 通过下标访问数据/Access data by index
 
std::optional< DataType > get_item (std::size_t index) const
 获取指定索引的数据/Get data at the specified index
 
std::optional< DataType > get_next ()
 获取下一个元素并推进内部索引/Get the next element and advance the internal index
 
std::optional< DataType > peek_next () const
 查看下一个元素但不推进索引/Peek the next element without advancing the index
 
void reset_iterator ()
 重置内部迭代器索引/Reset the internal iterator index
 
std::size_t current_index () const
 获取当前迭代器索引/Get the current iterator index
 
 dataset_t (const dataset_t &)=delete
 禁用拷贝构造/Copy constructor is disabled
 
dataset_toperator= (const dataset_t &)=delete
 禁用拷贝赋值/Copy assignment is disabled
 
 dataset_t (dataset_t &&)=delete
 禁用移动构造/Move constructor is disabled
 
dataset_toperator= (dataset_t &&)=delete
 禁用移动赋值/Move assignment is disabled
 

Additional Inherited Members

- Protected Member Functions inherited from toolbox::io::dataset_t< Derived, DataType >
 dataset_t ()=default
 构造函数/Constructor
 
 ~dataset_t ()=default
 析构函数/Destructor
 

Detailed Description

template<typename DataType = float>
class toolbox::io::kitti_odometry_pair_dataset_t< DataType >

KITTI Odometry frame pair dataset loader.

Template Parameters
DataTypeThe floating point type (float or double)

This dataset provides access to pairs of frames from KITTI sequences, useful for registration, odometry, and SLAM applications.

// Load pairs with skip=1 (consecutive frames)
kitti_odometry_pair_dataset_t<float> dataset("/path/to/kitti/sequences/00", 1);
for (const auto& pair : dataset) {
// Use relative transform as initial guess for ICP
icp.set_initial_transform(pair.relative_transform);
auto result = icp.align(pair.source_cloud, pair.target_cloud);
}
KITTI Odometry frame pair dataset loader.
Definition kitti_odometry_pair_dataset.hpp:34

Member Typedef Documentation

◆ base_type

template<typename DataType = float>
using toolbox::io::kitti_odometry_pair_dataset_t< DataType >::base_type = dataset_t<kitti_odometry_pair_dataset_t<DataType>, pair_type>

◆ pair_type

template<typename DataType = float>
using toolbox::io::kitti_odometry_pair_dataset_t< DataType >::pair_type = kitti_odometry_frame_pair_t<DataType>

Constructor & Destructor Documentation

◆ kitti_odometry_pair_dataset_t()

template<typename DataType >
toolbox::io::kitti_odometry_pair_dataset_t< DataType >::kitti_odometry_pair_dataset_t ( const std::string &  sequence_path,
std::size_t  skip = 1 
)
explicit

Constructor.

Parameters
sequence_pathPath to sequence directory
skipNumber of frames to skip between source and target (default 1)
Exceptions
kitti_invalid_sequenceif directory structure is invalid

Member Function Documentation

◆ at_impl()

template<typename DataType >
std::optional< kitti_odometry_frame_pair_t< DataType > > toolbox::io::kitti_odometry_pair_dataset_t< DataType >::at_impl ( std::size_t  index) const

Load frame pair at specific index.

Parameters
indexPair index (0-based)
Returns
Frame pair data or nullopt on error

◆ clear_cache()

template<typename DataType = float>
void toolbox::io::kitti_odometry_pair_dataset_t< DataType >::clear_cache ( ) const
inline

Clear pair cache.

◆ enable_overlap_computation()

template<typename DataType = float>
void toolbox::io::kitti_odometry_pair_dataset_t< DataType >::enable_overlap_computation ( bool  enable)
inline

Set whether to compute overlap ratio between frames.

Parameters
enableEnable overlap computation (can be slow)

◆ get_base_dataset()

template<typename DataType = float>
const kitti_odometry_dataset_t< DataType > & toolbox::io::kitti_odometry_pair_dataset_t< DataType >::get_base_dataset ( ) const
inline

Get the underlying base dataset.

Returns
Reference to base dataset

◆ get_pairs_with_motion()

template<typename DataType >
std::vector< std::size_t > toolbox::io::kitti_odometry_pair_dataset_t< DataType >::get_pairs_with_motion ( DataType  min_translation = 0.1,
DataType  min_rotation = 0.01 
) const

Get pairs with specific relative motion threshold.

Parameters
min_translationMinimum translation between frames (meters)
min_rotationMinimum rotation between frames (radians)
Returns
Indices of pairs meeting the criteria

◆ get_skip()

template<typename DataType = float>
std::size_t toolbox::io::kitti_odometry_pair_dataset_t< DataType >::get_skip ( ) const
inline

Get current skip value.

Returns
Number of frames between source and target

◆ get_source_frame_index()

template<typename DataType = float>
std::size_t toolbox::io::kitti_odometry_pair_dataset_t< DataType >::get_source_frame_index ( std::size_t  pair_index) const
inline

Get source frame index for a pair.

Parameters
pair_indexIndex of the pair
Returns
Source frame index in the sequence

◆ get_target_frame_index()

template<typename DataType = float>
std::size_t toolbox::io::kitti_odometry_pair_dataset_t< DataType >::get_target_frame_index ( std::size_t  pair_index) const
inline

Get target frame index for a pair.

Parameters
pair_indexIndex of the pair
Returns
Target frame index in the sequence

◆ set_cache_size()

template<typename DataType = float>
void toolbox::io::kitti_odometry_pair_dataset_t< DataType >::set_cache_size ( std::size_t  size)
inline

Set maximum pair cache size.

Parameters
sizeMaximum number of pairs to cache

◆ set_skip()

template<typename DataType = float>
void toolbox::io::kitti_odometry_pair_dataset_t< DataType >::set_skip ( std::size_t  skip)
inline

Set skip parameter.

Parameters
skipNumber of frames between source and target

◆ size_impl()

template<typename DataType = float>
std::size_t toolbox::io::kitti_odometry_pair_dataset_t< DataType >::size_impl ( ) const
inline

Get number of frame pairs.

Returns
Number of available pairs

The documentation for this class was generated from the following files: