Apollo  v5.5.0
Open source self driving car software
point_cloud.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2018 The Apollo Authors. All Rights Reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *****************************************************************************/
16 
17 #pragma once
18 
19 #include <limits>
20 #include <memory>
21 #include <utility>
22 #include <vector>
23 
24 #include "Eigen/Dense"
25 
27 
28 namespace apollo {
29 namespace perception {
30 namespace base {
31 
32 template <class PointT>
33 class PointCloud {
34  public:
35  using PointType = PointT;
36  // @brief default constructor
37  PointCloud() = default;
38 
39  // @brief construct from input point cloud and specified indices
40  PointCloud(const PointCloud<PointT>& pc, const PointIndices& indices) {
41  CopyPointCloud(pc, indices);
42  }
43  PointCloud(const PointCloud<PointT>& pc, const std::vector<int>& indices) {
44  CopyPointCloud(pc, indices);
45  }
46  // @brief construct given width and height for organized point cloud
47  PointCloud(size_t width, size_t height, PointT point = PointT())
48  : width_(width), height_(height) {
49  points_.assign(width_ * height_, point);
50  }
51 
52  // @brief destructor
53  virtual ~PointCloud() = default;
54 
55  // @brief accessor of point via 2d indices for organized cloud,
56  // @return nullptr for non-organized cloud
57  inline const PointT* at(size_t col, size_t row) const {
58  return IsOrganized() ? &(points_[row * width_ + col]) : nullptr;
59  }
60  inline PointT* at(size_t col, size_t row) {
61  return IsOrganized() ? &(points_[row * width_ + col]) : nullptr;
62  }
63  inline const PointT* operator()(size_t col, size_t row) const {
64  return IsOrganized() ? &(points_[row * width_ + col]) : nullptr;
65  }
66  inline PointT* operator()(size_t col, size_t row) {
67  return IsOrganized() ? &(points_[row * width_ + col]) : nullptr;
68  }
69  // @brief whether the cloud is organized
70  inline bool IsOrganized() const { return height_ > 1; }
71  // @brief accessor of point cloud height
72  inline size_t height() const { return height_; }
73  // @brief accessor of point cloud width
74  inline size_t width() const { return width_; }
75  // @brief accessor of point size, wrapper of vector
76  inline size_t size() const { return points_.size(); }
77  // @brief reserve function wrapper of vector
78  inline virtual void reserve(size_t size) { points_.reserve(size); }
79  // @brief empty function wrapper of vector
80  inline bool empty() const { return points_.empty(); }
81  // @brief resize function wrapper of vector
82  inline virtual void resize(size_t size) {
83  points_.resize(size);
84  if (size != width_ * height_) {
85  width_ = size;
86  height_ = 1;
87  }
88  }
89  // @brief accessor of point via 1d index
90  inline const PointT& operator[](size_t n) const { return points_[n]; }
91  inline PointT& operator[](size_t n) { return points_[n]; }
92  inline const PointT& at(size_t n) const { return points_[n]; }
93  inline PointT& at(size_t n) { return points_[n]; }
94  // @brief front accessor wrapper of vector
95  inline const PointT& front() const { return points_.front(); }
96  inline PointT& front() { return points_.front(); }
97  // @brief back accessor wrapper of vector
98  inline const PointT& back() const { return points_.back(); }
99  inline PointT& back() { return points_.back(); }
100  // @brief push_back function wrapper of vector
101  inline virtual void push_back(const PointT& point) {
102  points_.push_back(point);
103  width_ = points_.size();
104  height_ = 1;
105  }
106  // @brief clear function wrapper of vector
107  inline virtual void clear() {
108  points_.clear();
109  width_ = height_ = 0;
110  }
111  // @brief swap point given source and target id
112  inline virtual bool SwapPoint(size_t source_id, size_t target_id) {
113  if (source_id < points_.size() && target_id < points_.size()) {
114  std::swap(points_[source_id], points_[target_id]);
115  width_ = points_.size();
116  height_ = 1;
117  return true;
118  }
119  return false;
120  }
121  // @brief copy point from another point cloud
122  inline bool CopyPoint(size_t id, size_t rhs_id,
123  const PointCloud<PointT>& rhs) {
124  if (id < points_.size() && rhs_id < rhs.points_.size()) {
125  points_[id] = rhs.points_[rhs_id];
126  return true;
127  }
128  return false;
129  }
130  // @brief copy point cloud
131  inline void CopyPointCloud(const PointCloud<PointT>& rhs,
132  const PointIndices& indices) {
133  CopyPointCloud(rhs, indices.indices);
134  }
135  template <typename IndexType>
136  inline void CopyPointCloud(const PointCloud<PointT>& rhs,
137  const std::vector<IndexType>& indices) {
138  width_ = indices.size();
139  height_ = 1;
140  points_.resize(indices.size());
141  for (size_t i = 0; i < indices.size(); ++i) {
142  points_[i] = rhs.points_[indices[i]];
143  }
144  }
145  template <typename IndexType>
147  const std::vector<IndexType>& indices) {
148  width_ = indices.size();
149  height_ = 1;
150  points_.resize(rhs.size() - indices.size());
151  std::vector<bool> mask(false, rhs.size());
152  for (size_t i = 0; i < indices.size(); ++i) {
153  mask[indices[i]] = true;
154  }
155  for (size_t i = 0; i < rhs.size(); ++i) {
156  if (!mask[i]) {
157  points_.push_back(rhs.points_[i]);
158  }
159  }
160  }
161 
162  // @brief swap point cloud
163  inline void SwapPointCloud(PointCloud<PointT>* rhs) {
164  points_.swap(rhs->points_);
165  std::swap(width_, rhs->width_);
166  std::swap(height_, rhs->height_);
168  std::swap(timestamp_, rhs->timestamp_);
169  }
170  typedef typename std::vector<PointT>::iterator iterator;
171  typedef typename std::vector<PointT>::const_iterator const_iterator;
172  // @brief vector iterator
173  inline iterator begin() { return points_.begin(); }
174  inline iterator end() { return points_.end(); }
175  inline const_iterator begin() const { return points_.begin(); }
176  inline const_iterator end() const { return points_.end(); }
177  typename std::vector<PointT>* mutable_points() { return &points_; }
178  const typename std::vector<PointT>& points() const { return points_; }
179 
180  // @brief cloud timestamp setter
181  void set_timestamp(const double timestamp) { timestamp_ = timestamp; }
182  // @brief cloud timestamp getter
183  double get_timestamp() { return timestamp_; }
184  // @brief sensor to world pose setter
185  void set_sensor_to_world_pose(const Eigen::Affine3d& sensor_to_world_pose) {
187  }
188  // @brief sensor to world pose getter
189  const Eigen::Affine3d& sensor_to_world_pose() {
190  return sensor_to_world_pose_;
191  }
192  // @brief rotate the point cloud and set rotation part of pose to identity
193  void RotatePointCloud(bool check_nan = false) {
194  Eigen::Vector3d point3d;
195  Eigen::Matrix3d rotation = sensor_to_world_pose_.linear();
196  for (auto& point : points_) {
197  if (!check_nan || (!std::isnan(point.x) && !std::isnan(point.y) &&
198  !std::isnan(point.z))) {
199  point3d << point.x, point.y, point.z;
200  point3d = rotation * point3d;
201  point.x = static_cast<typename PointT::Type>(point3d(0));
202  point.y = static_cast<typename PointT::Type>(point3d(1));
203  point.z = static_cast<typename PointT::Type>(point3d(2));
204  }
205  }
206  sensor_to_world_pose_.linear().setIdentity();
207  }
208  // @brief transform the point cloud, set the pose to identity
209  void TransformPointCloud(bool check_nan = false) {
210  Eigen::Vector3d point3d;
211  for (auto& point : points_) {
212  if (!check_nan || (!std::isnan(point.x) && !std::isnan(point.y) &&
213  !std::isnan(point.z))) {
214  point3d << point.x, point.y, point.z;
215  point3d = sensor_to_world_pose_ * point3d;
216  point.x = static_cast<typename PointT::Type>(point3d(0));
217  point.y = static_cast<typename PointT::Type>(point3d(1));
218  point.z = static_cast<typename PointT::Type>(point3d(2));
219  }
220  }
221  sensor_to_world_pose_.setIdentity();
222  }
223 
224  // @brief transform the point cloud and save to another pc
225  void TransformPointCloud(const Eigen::Affine3f& transform,
226  PointCloud<PointT>* out,
227  bool check_nan = false) const {
228  Eigen::Vector3f point3f;
229  PointT pt;
230  for (auto& point : points_) {
231  if (!check_nan || (!std::isnan(point.x) && !std::isnan(point.y) &&
232  !std::isnan(point.z))) {
233  point3f << point.x, point.y, point.z;
234  point3f = transform * point3f;
235  pt.x = static_cast<typename PointT::Type>(point3f(0));
236  pt.y = static_cast<typename PointT::Type>(point3f(1));
237  pt.z = static_cast<typename PointT::Type>(point3f(2));
238  out->push_back(pt);
239  }
240  }
241  }
242  // @brief check data member consistency
243  virtual bool CheckConsistency() const { return true; }
244 
245  protected:
246  std::vector<PointT> points_;
247  size_t width_ = 0;
248  size_t height_ = 0;
249 
250  Eigen::Affine3d sensor_to_world_pose_ = Eigen::Affine3d::Identity();
251  double timestamp_ = 0.0;
252 };
253 
254 // @brief Point cloud class split points and attributes storage
255 // for fast traversing
256 template <class PointT>
257 class AttributePointCloud : public PointCloud<PointT> {
258  public:
265  // @brief default constructor
266  AttributePointCloud() = default;
267 
268  // @brief construct from input point cloud and specified indices
270  const PointIndices& indices) {
271  CopyPointCloud(pc, indices);
272  }
274  const std::vector<int>& indices) {
275  CopyPointCloud(pc, indices);
276  }
277  // @brief construct given width and height for organized point cloud
278  AttributePointCloud(const size_t width, const size_t height,
279  const PointT point = PointT()) {
280  width_ = width;
281  height_ = height;
282  size_t size = width_ * height_;
283  points_.assign(size, point);
284  points_timestamp_.assign(size, 0.0);
285  points_height_.assign(size, std::numeric_limits<float>::max());
286  points_beam_id_.assign(size, -1);
287  points_label_.assign(size, 0);
288  }
289  // @brief destructor
290  virtual ~AttributePointCloud() = default;
291  // @brief add points of input cloud, return the self cloud
293  const AttributePointCloud<PointT>& rhs) {
294  points_.insert(points_.end(), rhs.points_.begin(), rhs.points_.end());
295  points_timestamp_.insert(points_timestamp_.end(),
296  rhs.points_timestamp_.begin(),
297  rhs.points_timestamp_.end());
298  points_height_.insert(points_height_.end(), rhs.points_height_.begin(),
299  rhs.points_height_.end());
300  points_beam_id_.insert(points_beam_id_.end(), rhs.points_beam_id_.begin(),
301  rhs.points_beam_id_.end());
302  points_label_.insert(points_label_.end(), rhs.points_label_.begin(),
303  rhs.points_label_.end());
304  width_ = width_ * height_ + rhs.width_ * rhs.height_;
305  height_ = 1;
306  return *this;
307  }
308  // @brief overrided reserve function wrapper of vector
309  inline void reserve(const size_t size) override {
310  points_.reserve(size);
311  points_timestamp_.reserve(size);
312  points_height_.reserve(size);
313  points_beam_id_.reserve(size);
314  points_label_.reserve(size);
315  }
316  // @brief overrided resize function wrapper of vector
317  inline void resize(const size_t size) override {
318  points_.resize(size);
319  points_timestamp_.resize(size, 0.0);
320  points_height_.resize(size, std::numeric_limits<float>::max());
321  points_beam_id_.resize(size, -1);
322  points_label_.resize(size, 0);
323  if (size != width_ * height_) {
324  width_ = size;
325  height_ = 1;
326  }
327  }
328  // @brief overrided push_back function wrapper of vector
329  inline void push_back(const PointT& point) override {
330  points_.push_back(point);
331  points_timestamp_.push_back(0.0);
332  points_height_.push_back(std::numeric_limits<float>::max());
333  points_beam_id_.push_back(-1);
334  points_label_.push_back(0);
335  width_ = points_.size();
336  height_ = 1;
337  }
338  inline void push_back(const PointT& point, double timestamp,
339  float height = std::numeric_limits<float>::max(),
340  int32_t beam_id = -1, uint8_t label = 0) {
341  points_.push_back(point);
342  points_timestamp_.push_back(timestamp);
343  points_height_.push_back(height);
344  points_beam_id_.push_back(beam_id);
345  points_label_.push_back(label);
346  width_ = points_.size();
347  height_ = 1;
348  }
349  // @brief overrided clear function wrapper of vector
350  inline void clear() override {
351  points_.clear();
352  points_timestamp_.clear();
353  points_height_.clear();
354  points_beam_id_.clear();
355  points_label_.clear();
356  width_ = height_ = 0;
357  }
358  // @brief overrided swap point given source and target id
359  inline bool SwapPoint(const size_t source_id,
360  const size_t target_id) override {
361  if (source_id < points_.size() && target_id < points_.size()) {
362  std::swap(points_[source_id], points_[target_id]);
363  std::swap(points_timestamp_[source_id], points_timestamp_[target_id]);
364  std::swap(points_height_[source_id], points_height_[target_id]);
365  std::swap(points_beam_id_[source_id], points_beam_id_[target_id]);
366  std::swap(points_label_[source_id], points_label_[target_id]);
367  width_ = points_.size();
368  height_ = 1;
369  return true;
370  }
371  return false;
372  }
373  // @brief copy point from another point cloud
374  inline bool CopyPoint(const size_t id, const size_t rhs_id,
375  const AttributePointCloud<PointT>& rhs) {
376  if (id < points_.size() && rhs_id < rhs.points_.size()) {
377  points_[id] = rhs.points_[rhs_id];
378  points_timestamp_[id] = rhs.points_timestamp_[rhs_id];
379  points_height_[id] = rhs.points_height_[rhs_id];
380  points_beam_id_[id] = rhs.points_beam_id_[rhs_id];
381  points_label_[id] = rhs.points_label_[rhs_id];
382  return true;
383  }
384  return false;
385  }
386  // @brief copy point cloud
388  const PointIndices& indices) {
389  CopyPointCloud(rhs, indices.indices);
390  }
391  template <typename IndexType>
393  const std::vector<IndexType>& indices) {
394  width_ = indices.size();
395  height_ = 1;
396  points_.resize(indices.size());
397  points_timestamp_.resize(indices.size());
398  points_height_.resize(indices.size());
399  points_beam_id_.resize(indices.size());
400  points_label_.resize(indices.size());
401  for (size_t i = 0; i < indices.size(); ++i) {
402  points_[i] = rhs.points_[indices[i]];
403  points_timestamp_[i] = rhs.points_timestamp_[indices[i]];
404  points_height_[i] = rhs.points_height_[indices[i]];
405  points_beam_id_[i] = rhs.points_beam_id_[indices[i]];
406  points_label_[i] = rhs.points_label_[indices[i]];
407  }
408  }
409 
410  // @brief swap point cloud
412  points_.swap(rhs->points_);
413  std::swap(width_, rhs->width_);
414  std::swap(height_, rhs->height_);
416  std::swap(timestamp_, rhs->timestamp_);
417  points_timestamp_.swap(rhs->points_timestamp_);
418  points_height_.swap(rhs->points_height_);
419  points_beam_id_.swap(rhs->points_beam_id_);
420  points_label_.swap(rhs->points_label_);
421  }
422  // @brief overrided check data member consistency
423  bool CheckConsistency() const override {
424  return ((points_.size() == points_timestamp_.size()) &&
425  (points_.size() == points_height_.size()) &&
426  (points_.size() == points_beam_id_.size()) &&
427  (points_.size() == points_label_.size()));
428  }
429 
430  size_t TransferToIndex(const size_t col, const size_t row) const {
431  return row * width_ + col;
432  }
433 
434  const std::vector<double>& points_timestamp() const {
435  return points_timestamp_;
436  }
437  double points_timestamp(size_t i) const { return points_timestamp_[i]; }
438  std::vector<double>* mutable_points_timestamp() { return &points_timestamp_; }
439 
440  const std::vector<float>& points_height() const { return points_height_; }
441  float& points_height(size_t i) { return points_height_[i]; }
442  const float& points_height(size_t i) const { return points_height_[i]; }
443  void SetPointHeight(size_t i, size_t j, float height) {
444  points_height_[i * width_ + j] = height;
445  }
446  void SetPointHeight(size_t i, float height) { points_height_[i] = height; }
447  std::vector<float>* mutable_points_height() { return &points_height_; }
448 
449  const std::vector<int32_t>& points_beam_id() const { return points_beam_id_; }
450  std::vector<int32_t>* mutable_points_beam_id() { return &points_beam_id_; }
451  const std::vector<uint8_t>& points_label() const { return points_label_; }
452  std::vector<uint8_t>* mutable_points_label() { return &points_label_; }
453 
454  uint8_t& points_label(size_t i) { return points_label_[i]; }
455  const uint8_t& points_label(size_t i) const { return points_label_[i]; }
456 
457  protected:
458  std::vector<double> points_timestamp_;
459  std::vector<float> points_height_;
460  std::vector<int32_t> points_beam_id_;
461  std::vector<uint8_t> points_label_;
462 };
463 
464 // typedef of point cloud indices
465 typedef std::shared_ptr<PointIndices> PointIndicesPtr;
466 typedef std::shared_ptr<const PointIndices> PointIndicesConstPtr;
467 
468 // typedef of point cloud
471 
472 typedef std::shared_ptr<PointFCloud> PointFCloudPtr;
473 typedef std::shared_ptr<const PointFCloud> PointFCloudConstPtr;
474 
475 typedef std::shared_ptr<PointDCloud> PointDCloudPtr;
476 typedef std::shared_ptr<const PointDCloud> PointDCloudConstPtr;
477 
478 // typedef of polygon
481 
482 typedef std::shared_ptr<PolygonFType> PolygonFTypePtr;
483 typedef std::shared_ptr<const PolygonFType> PolygonFTypeConstPtr;
484 
485 typedef std::shared_ptr<PolygonDType> PolygonDTypePtr;
486 typedef std::shared_ptr<const PolygonDType> PolygonDTypeConstPtr;
487 
488 } // namespace base
489 } // namespace perception
490 } // namespace apollo
void resize(const size_t size) override
Definition: point_cloud.h:317
AttributePointCloud & operator+=(const AttributePointCloud< PointT > &rhs)
Definition: point_cloud.h:292
const std::vector< PointT > & points() const
Definition: point_cloud.h:178
float & points_height(size_t i)
Definition: point_cloud.h:441
std::vector< uint8_t > points_label_
Definition: point_cloud.h:461
const std::vector< double > & points_timestamp() const
Definition: point_cloud.h:434
void push_back(const PointT &point, double timestamp, float height=std::numeric_limits< float >::max(), int32_t beam_id=-1, uint8_t label=0)
Definition: point_cloud.h:338
const PointT & back() const
Definition: point_cloud.h:98
bool empty() const
Definition: point_cloud.h:80
PointT & back()
Definition: point_cloud.h:99
double points_timestamp(size_t i) const
Definition: point_cloud.h:437
PointCloud< PointD > PolygonDType
Definition: point_cloud.h:480
std::shared_ptr< PolygonFType > PolygonFTypePtr
Definition: point_cloud.h:482
void SwapPointCloud(PointCloud< PointT > *rhs)
Definition: point_cloud.h:163
std::vector< int > indices
Definition: point.h:76
Definition: blob.h:72
bool IsOrganized() const
Definition: point_cloud.h:70
std::vector< int32_t > * mutable_points_beam_id()
Definition: point_cloud.h:450
std::shared_ptr< PointIndices > PointIndicesPtr
Definition: point_cloud.h:465
Definition: point.h:29
PointCloud< PointF > PolygonFType
Definition: point_cloud.h:479
void clear() override
Definition: point_cloud.h:350
virtual void clear()
Definition: point_cloud.h:107
void CopyPointCloud(const AttributePointCloud< PointT > &rhs, const std::vector< IndexType > &indices)
Definition: point_cloud.h:392
virtual void push_back(const PointT &point)
Definition: point_cloud.h:101
const Eigen::Affine3d & sensor_to_world_pose()
Definition: point_cloud.h:189
AttributePointCloud(const AttributePointCloud< PointT > &pc, const std::vector< int > &indices)
Definition: point_cloud.h:273
AttributePointCloud(const size_t width, const size_t height, const PointT point=PointT())
Definition: point_cloud.h:278
void CopyPointCloud(const AttributePointCloud< PointT > &rhs, const PointIndices &indices)
Definition: point_cloud.h:387
bool CopyPoint(size_t id, size_t rhs_id, const PointCloud< PointT > &rhs)
Definition: point_cloud.h:122
AttributePointCloud< PointD > PointDCloud
Definition: point_cloud.h:470
const std::vector< int32_t > & points_beam_id() const
Definition: point_cloud.h:449
bool CopyPoint(const size_t id, const size_t rhs_id, const AttributePointCloud< PointT > &rhs)
Definition: point_cloud.h:374
size_t size() const
Definition: point_cloud.h:76
std::vector< float > * mutable_points_height()
Definition: point_cloud.h:447
std::vector< PointT > points_
Definition: point_cloud.h:246
iterator end()
Definition: point_cloud.h:174
Definition: point_cloud.h:33
void set_sensor_to_world_pose(const Eigen::Affine3d &sensor_to_world_pose)
Definition: point_cloud.h:185
std::vector< int32_t > points_beam_id_
Definition: point_cloud.h:460
void CopyPointCloud(const PointCloud< PointT > &rhs, const std::vector< IndexType > &indices)
Definition: point_cloud.h:136
void CopyPointCloudExclude(const PointCloud< PointT > &rhs, const std::vector< IndexType > &indices)
Definition: point_cloud.h:146
PointCloud(const PointCloud< PointT > &pc, const PointIndices &indices)
Definition: point_cloud.h:40
std::vector< uint8_t > * mutable_points_label()
Definition: point_cloud.h:452
void SetPointHeight(size_t i, size_t j, float height)
Definition: point_cloud.h:443
void TransformPointCloud(bool check_nan=false)
Definition: point_cloud.h:209
AttributePointCloud(const AttributePointCloud< PointT > &pc, const PointIndices &indices)
Definition: point_cloud.h:269
size_t height_
Definition: point_cloud.h:248
std::shared_ptr< const PointFCloud > PointFCloudConstPtr
Definition: point_cloud.h:473
PointT * operator()(size_t col, size_t row)
Definition: point_cloud.h:66
PointCloud(size_t width, size_t height, PointT point=PointT())
Definition: point_cloud.h:47
std::vector< PointT > * mutable_points()
Definition: point_cloud.h:177
uint8_t & points_label(size_t i)
Definition: point_cloud.h:454
const PointT & operator[](size_t n) const
Definition: point_cloud.h:90
PointCloud(const PointCloud< PointT > &pc, const std::vector< int > &indices)
Definition: point_cloud.h:43
PointT & front()
Definition: point_cloud.h:96
size_t TransferToIndex(const size_t col, const size_t row) const
Definition: point_cloud.h:430
void SetPointHeight(size_t i, float height)
Definition: point_cloud.h:446
size_t height() const
Definition: point_cloud.h:72
std::shared_ptr< const PointDCloud > PointDCloudConstPtr
Definition: point_cloud.h:476
bool CheckConsistency() const override
Definition: point_cloud.h:423
std::vector< double > * mutable_points_timestamp()
Definition: point_cloud.h:438
double timestamp_
Definition: point_cloud.h:251
void CopyPointCloud(const PointCloud< PointT > &rhs, const PointIndices &indices)
Definition: point_cloud.h:131
size_t width() const
Definition: point_cloud.h:74
PointT & at(size_t n)
Definition: point_cloud.h:93
virtual void resize(size_t size)
Definition: point_cloud.h:82
PointT & operator[](size_t n)
Definition: point_cloud.h:91
const_iterator end() const
Definition: point_cloud.h:176
bool SwapPoint(const size_t source_id, const size_t target_id) override
Definition: point_cloud.h:359
std::shared_ptr< const PointIndices > PointIndicesConstPtr
Definition: point_cloud.h:466
std::shared_ptr< PointFCloud > PointFCloudPtr
Definition: point_cloud.h:472
const uint8_t & points_label(size_t i) const
Definition: point_cloud.h:455
double get_timestamp()
Definition: point_cloud.h:183
Eigen::Affine3d sensor_to_world_pose_
Definition: point_cloud.h:250
std::vector< PointT >::iterator iterator
Definition: point_cloud.h:170
const PointT & at(size_t n) const
Definition: point_cloud.h:92
void RotatePointCloud(bool check_nan=false)
Definition: point_cloud.h:193
std::shared_ptr< const PolygonFType > PolygonFTypeConstPtr
Definition: point_cloud.h:483
const_iterator begin() const
Definition: point_cloud.h:175
const std::vector< uint8_t > & points_label() const
Definition: point_cloud.h:451
const float & points_height(size_t i) const
Definition: point_cloud.h:442
void reserve(const size_t size) override
Definition: point_cloud.h:309
void set_timestamp(const double timestamp)
Definition: point_cloud.h:181
const PointT & front() const
Definition: point_cloud.h:95
const PointT * operator()(size_t col, size_t row) const
Definition: point_cloud.h:63
size_t width_
Definition: point_cloud.h:247
iterator begin()
Definition: point_cloud.h:173
void SwapPointCloud(AttributePointCloud< PointT > *rhs)
Definition: point_cloud.h:411
virtual bool SwapPoint(size_t source_id, size_t target_id)
Definition: point_cloud.h:112
std::vector< float > points_height_
Definition: point_cloud.h:459
virtual void reserve(size_t size)
Definition: point_cloud.h:78
virtual bool CheckConsistency() const
Definition: point_cloud.h:243
std::vector< PointT >::const_iterator const_iterator
Definition: point_cloud.h:171
std::shared_ptr< PointDCloud > PointDCloudPtr
Definition: point_cloud.h:475
std::shared_ptr< PolygonDType > PolygonDTypePtr
Definition: point_cloud.h:485
void TransformPointCloud(const Eigen::Affine3f &transform, PointCloud< PointT > *out, bool check_nan=false) const
Definition: point_cloud.h:225
std::shared_ptr< const PolygonDType > PolygonDTypeConstPtr
Definition: point_cloud.h:486
void push_back(const PointT &point) override
Definition: point_cloud.h:329
std::vector< double > points_timestamp_
Definition: point_cloud.h:458
const PointT * at(size_t col, size_t row) const
Definition: point_cloud.h:57
const std::vector< float > & points_height() const
Definition: point_cloud.h:440
AttributePointCloud< PointF > PointFCloud
Definition: point_cloud.h:469
PointT * at(size_t col, size_t row)
Definition: point_cloud.h:60