GLIM
Loading...
Searching...
No Matches
preprocessed_frame.hpp
1#pragma once
2
3#include <memory>
4#include <vector>
5#include <Eigen/Core>
6#include <glim/util/raw_points.hpp>
7
8namespace glim {
9
15public:
16 using Ptr = std::shared_ptr<PreprocessedFrame>;
17 using ConstPtr = std::shared_ptr<const PreprocessedFrame>;
18
23 int size() const { return points.size(); }
24
25public:
26 double stamp; // Timestamp at the beginning of the scan
27 double scan_end_time; // Timestamp at the end of the scan
28
29 std::vector<double> times; // Point timestamps w.r.t. the first pt
30 std::vector<double> intensities; // Point intensities
31 std::vector<Eigen::Vector4d> points; // Points (homogeneous coordinates)
32
33 int k_neighbors; // Number of neighbors of each point
34 std::vector<int> neighbors; // k-nearest neighbors of each point
35
36 RawPoints::ConstPtr raw_points;
37};
38
39} // namespace glim
Preprocessed point cloud.
Definition preprocessed_frame.hpp:14
int size() const
Number of points.
Definition preprocessed_frame.hpp:23