cpp-toolbox  0.0.1
A toolbox library for C++
Loading...
Searching...
No Matches
semantic_kitti_dataset.hpp
Go to the documentation of this file.
1#pragma once
2
6
7#include <memory>
8#include <string>
9#include <optional>
10#include <set>
11#include <map>
12
13namespace toolbox::io {
14
45template<typename DataType = float>
47 public dataset_t<semantic_kitti_dataset_t<DataType>,
48 semantic_kitti_frame_t<DataType>> {
49public:
52
58 explicit semantic_kitti_dataset_t(const std::string& sequence_path);
59
64 void enable_label_validation(bool validate) {
65 validate_labels_ = validate;
66 }
67
72 void set_cache_size(std::size_t max_cached_frames) {
73 base_dataset_.set_cache_size(max_cached_frames);
74 label_cache_size_ = max_cached_frames;
75 // Trim label cache if needed
76 while (label_cache_.size() > label_cache_size_) {
77 label_cache_.erase(label_cache_.begin());
78 }
79 }
80
81 // ==================== Dataset Interface ====================
82
87 [[nodiscard]] std::size_t size_impl() const {
88 return base_dataset_.size();
89 }
90
96 [[nodiscard]] std::optional<frame_type> at_impl(std::size_t index) const;
97
98 // ==================== Semantic-Specific Methods ====================
99
105 [[nodiscard]] std::set<uint16_t> get_unique_labels(bool scan_all = false) const;
106
111 [[nodiscard]] std::map<uint16_t, std::string> get_label_names() const {
113 }
114
120 [[nodiscard]] std::map<uint16_t, std::size_t>
121 compute_label_statistics(std::size_t max_frames = 0) const;
122
129 [[nodiscard]] std::vector<std::size_t> get_frames_with_label(
130 uint16_t label,
131 std::size_t min_points = 1) const;
132
137 [[nodiscard]] bool has_labels() const { return has_labels_; }
138
144 [[nodiscard]] std::string get_label_file(std::size_t index) const {
145 if (index >= label_files_.size()) {
146 throw kitti_index_out_of_range(index, label_files_.size());
147 }
148 return label_files_[index];
149 }
150
155 [[nodiscard]] const kitti_odometry_dataset_t<DataType>&
156 get_base_dataset() const { return base_dataset_; }
157
161 void clear_cache() const {
162 base_dataset_.clear_cache();
163 label_cache_.clear();
164 unique_labels_cache_.clear();
165 }
166
167private:
171 void scan_label_files();
172
178 std::vector<uint32_t> load_labels(std::size_t index) const;
179
180 // ==================== Member Variables ====================
181
183 mutable kitti_odometry_dataset_t<DataType> base_dataset_;
184
186 std::string labels_path_;
187
189 std::vector<std::string> label_files_;
190
192 bool has_labels_;
193
195 bool validate_labels_ = true;
196
198 mutable std::map<std::size_t, std::vector<uint32_t>> label_cache_;
199
201 std::size_t label_cache_size_ = 100;
202
204 mutable std::set<uint16_t> unique_labels_cache_;
205 mutable bool unique_labels_cached_ = false;
206};
207
208} // namespace toolbox::io
209
210// Include implementation
数据集基类/Abstract base class for datasets
Definition dataset.hpp:33
Exception thrown when accessing out of bounds frame.
Definition kitti_exceptions.hpp:66
KITTI Odometry dataset loader.
Definition kitti_odometry_dataset.hpp:45
Semantic KITTI dataset loader.
Definition semantic_kitti_dataset.hpp:48
std::size_t size_impl() const
Get number of frames in the sequence.
Definition semantic_kitti_dataset.hpp:87
std::optional< frame_type > at_impl(std::size_t index) const
Load frame at specific index.
Definition semantic_kitti_dataset_impl.hpp:58
std::vector< std::size_t > get_frames_with_label(uint16_t label, std::size_t min_points=1) const
Get frames containing specific label.
Definition semantic_kitti_dataset_impl.hpp:191
std::map< uint16_t, std::string > get_label_names() const
Get label name mapping.
Definition semantic_kitti_dataset.hpp:111
std::set< uint16_t > get_unique_labels(bool scan_all=false) const
Get all unique labels in the dataset.
Definition semantic_kitti_dataset_impl.hpp:133
void enable_label_validation(bool validate)
Set whether to validate labels match point count.
Definition semantic_kitti_dataset.hpp:64
bool has_labels() const
Check if labels are available.
Definition semantic_kitti_dataset.hpp:137
const kitti_odometry_dataset_t< DataType > & get_base_dataset() const
Get the underlying base dataset.
Definition semantic_kitti_dataset.hpp:156
void clear_cache() const
Clear all caches.
Definition semantic_kitti_dataset.hpp:161
void set_cache_size(std::size_t max_cached_frames)
Set cache size for loaded frames.
Definition semantic_kitti_dataset.hpp:72
std::map< uint16_t, std::size_t > compute_label_statistics(std::size_t max_frames=0) const
Compute label statistics across all frames.
Definition semantic_kitti_dataset_impl.hpp:168
std::string get_label_file(std::size_t index) const
Get label file path for specific frame.
Definition semantic_kitti_dataset.hpp:144
std::map< uint16_t, std::string > get_label_map()
Get all label names mapping.
Definition kitti_extended_impl.hpp:492
< 用于列出目录下的文件/For listing files in a directory
Definition dataloader.hpp:15
Single frame data from Semantic KITTI dataset.
Definition kitti_types.hpp:100