Apollo 10.0
自动驾驶开放平台
point_cloud.h
浏览该文件的文档.
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 <cstdint>
20#include <limits>
21#include <memory>
22#include <utility>
23#include <vector>
24
25#include "Eigen/Dense"
26
27#include "cyber/common/log.h"
30
31namespace apollo {
32namespace perception {
33namespace base {
34
35template <class PointT>
37 public:
38 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
39
40 public:
41 using PointType = PointT;
42 // @brief default constructor
43 PointCloud() = default;
44
45 // @brief construct from input point cloud and specified indices
46 PointCloud(const PointCloud<PointT>& pc, const PointIndices& indices) {
47 CopyPointCloud(pc, indices);
48 }
49 PointCloud(const PointCloud<PointT>& pc, const std::vector<int>& indices) {
50 CopyPointCloud(pc, indices);
51 }
52 // @brief construct given width and height for organized point cloud
53 PointCloud(size_t width, size_t height, PointT point = PointT())
55 points_.assign(width_ * height_, point);
56 }
57
58 // @brief destructor
59 virtual ~PointCloud() = default;
60
61 // @brief accessor of point via 2d indices for organized cloud,
62 // @return nullptr for non-organized cloud
63 inline const PointT* at(size_t col, size_t row) const {
64 return IsOrganized() ? &(points_[row * width_ + col]) : nullptr;
65 }
66 inline PointT* at(size_t col, size_t row) {
67 return IsOrganized() ? &(points_[row * width_ + col]) : nullptr;
68 }
69 inline const PointT* operator()(size_t col, size_t row) const {
70 return IsOrganized() ? &(points_[row * width_ + col]) : nullptr;
71 }
72 inline PointT* operator()(size_t col, size_t row) {
73 return IsOrganized() ? &(points_[row * width_ + col]) : nullptr;
74 }
75 // @brief whether the cloud is organized
76 inline bool IsOrganized() const { return height_ > 1; }
77 // @brief accessor of point cloud height
78 inline size_t height() const { return height_; }
79 // @brief accessor of point cloud width
80 inline size_t width() const { return width_; }
81 // @brief accessor of point size, wrapper of vector
82 inline size_t size() const { return points_.size(); }
83 // @brief reserve function wrapper of vector
84 inline virtual void reserve(size_t size) { points_.reserve(size); }
85 // @brief empty function wrapper of vector
86 inline bool empty() const { return points_.empty(); }
87 // @brief resize function wrapper of vector
88 inline virtual void resize(size_t size) {
89 points_.resize(size);
90 if (size != width_ * height_) {
91 width_ = size;
92 height_ = 1;
93 }
94 }
95 // @brief accessor of point via 1d index
96 inline const PointT& operator[](size_t n) const { return points_[n]; }
97 inline PointT& operator[](size_t n) { return points_[n]; }
98 inline const PointT& at(size_t n) const { return points_[n]; }
99 inline PointT& at(size_t n) { return points_[n]; }
100 // @brief front accessor wrapper of vector
101 inline const PointT& front() const { return points_.front(); }
102 inline PointT& front() { return points_.front(); }
103 // @brief back accessor wrapper of vector
104 inline const PointT& back() const { return points_.back(); }
105 inline PointT& back() { return points_.back(); }
106 // @brief push_back function wrapper of vector
107 inline virtual void push_back(const PointT& point) {
108 points_.push_back(point);
109 width_ = points_.size();
110 height_ = 1;
111 }
112 // @brief clear function wrapper of vector
113 inline virtual void clear() {
114 points_.clear();
115 width_ = height_ = 0;
116 }
117 // @brief swap point given source and target id
118 inline virtual bool SwapPoint(size_t source_id, size_t target_id) {
119 if (source_id < points_.size() && target_id < points_.size()) {
120 std::swap(points_[source_id], points_[target_id]);
121 width_ = points_.size();
122 height_ = 1;
123 return true;
124 }
125 return false;
126 }
127 // @brief copy point from another point cloud
128 inline bool CopyPoint(size_t id, size_t rhs_id,
129 const PointCloud<PointT>& rhs) {
130 if (id < points_.size() && rhs_id < rhs.points_.size()) {
131 points_[id] = rhs.points_[rhs_id];
132 return true;
133 }
134 return false;
135 }
136 // @brief copy point cloud
137 inline void CopyPointCloud(const PointCloud<PointT>& rhs,
138 const PointIndices& indices) {
139 CopyPointCloud(rhs, indices.indices);
140 }
141 template <typename IndexType>
142 inline void CopyPointCloud(const PointCloud<PointT>& rhs,
143 const std::vector<IndexType>& indices) {
144 width_ = indices.size();
145 height_ = 1;
146 points_.resize(indices.size());
147 for (size_t i = 0; i < indices.size(); ++i) {
148 points_[i] = rhs.points_[indices[i]];
149 }
150 }
151 template <typename IndexType>
153 const std::vector<IndexType>& indices) {
154 width_ = indices.size();
155 height_ = 1;
156 points_.resize(rhs.size() - indices.size());
157 std::vector<bool> mask(false, rhs.size());
158 for (size_t i = 0; i < indices.size(); ++i) {
159 mask[indices[i]] = true;
160 }
161 for (size_t i = 0; i < rhs.size(); ++i) {
162 if (!mask[i]) {
163 points_.push_back(rhs.points_[i]);
164 }
165 }
166 }
167
168 // @brief swap point cloud
170 points_.swap(rhs->points_);
171 std::swap(width_, rhs->width_);
172 std::swap(height_, rhs->height_);
174 std::swap(timestamp_, rhs->timestamp_);
175 }
176 typedef typename std::vector<PointT>::iterator iterator;
177 typedef typename std::vector<PointT>::const_iterator const_iterator;
178 // @brief vector iterator
179 inline iterator begin() { return points_.begin(); }
180 inline iterator end() { return points_.end(); }
181 inline const_iterator begin() const { return points_.begin(); }
182 inline const_iterator end() const { return points_.end(); }
183 typename std::vector<PointT>* mutable_points() { return &points_; }
184 const typename std::vector<PointT>& points() const { return points_; }
185
186 // @brief cloud timestamp setter
187 void set_timestamp(const double timestamp) { timestamp_ = timestamp; }
188 // @brief cloud timestamp getter
189 double get_timestamp() { return timestamp_; }
190 // @brief sensor to world pose setter
194 // @brief sensor to world pose getter
195 const Eigen::Affine3d& sensor_to_world_pose() {
197 }
198 // @brief rotate the point cloud and set rotation part of pose to identity
199 void RotatePointCloud(bool check_nan = false) {
200 Eigen::Vector3d point3d;
201 Eigen::Matrix3d rotation = sensor_to_world_pose_.linear();
202 for (auto& point : points_) {
203 if (!check_nan || (!std::isnan(point.x) && !std::isnan(point.y) &&
204 !std::isnan(point.z))) {
205 point3d << point.x, point.y, point.z;
206 point3d = rotation * point3d;
207 point.x = static_cast<typename PointT::Type>(point3d(0));
208 point.y = static_cast<typename PointT::Type>(point3d(1));
209 point.z = static_cast<typename PointT::Type>(point3d(2));
210 }
211 }
212 sensor_to_world_pose_.linear().setIdentity();
213 }
214 // @brief transform the point cloud, set the pose to identity
215 void TransformPointCloud(bool check_nan = false) {
216 Eigen::Vector3d point3d;
217 for (auto& point : points_) {
218 if (!check_nan || (!std::isnan(point.x) && !std::isnan(point.y) &&
219 !std::isnan(point.z))) {
220 point3d << point.x, point.y, point.z;
221 point3d = sensor_to_world_pose_ * point3d;
222 point.x = static_cast<typename PointT::Type>(point3d(0));
223 point.y = static_cast<typename PointT::Type>(point3d(1));
224 point.z = static_cast<typename PointT::Type>(point3d(2));
225 }
226 }
227 sensor_to_world_pose_.setIdentity();
228 }
229
230 // @brief transform the point cloud and save to another pc
231 void TransformPointCloud(const Eigen::Affine3f& transform,
233 bool check_nan = false) const {
234 Eigen::Vector3f point3f;
235 PointT pt;
236 for (auto& point : points_) {
237 if (!check_nan || (!std::isnan(point.x) && !std::isnan(point.y) &&
238 !std::isnan(point.z))) {
239 point3f << point.x, point.y, point.z;
240 point3f = transform * point3f;
241 pt.x = static_cast<typename PointT::Type>(point3f(0));
242 pt.y = static_cast<typename PointT::Type>(point3f(1));
243 pt.z = static_cast<typename PointT::Type>(point3f(2));
244 out->push_back(pt);
245 }
246 }
247 }
248 // @brief check data member consistency
249 virtual bool CheckConsistency() const { return true; }
250
251 protected:
252 std::vector<PointT> points_;
253 size_t width_ = 0;
254 size_t height_ = 0;
255
256 Eigen::Affine3d sensor_to_world_pose_ = Eigen::Affine3d::Identity();
257 double timestamp_ = 0.0;
258};
259
260// @brief Point cloud class split points and attributes storage
261// for fast traversing
262template <class PointT>
263class AttributePointCloud : public PointCloud<PointT> {
264 public:
265 using PointCloud<PointT>::points_;
266 using PointCloud<PointT>::width_;
267 using PointCloud<PointT>::height_;
268 using PointCloud<PointT>::IsOrganized;
270 using PointCloud<PointT>::timestamp_;
271 // @brief default constructor
273
274 // @brief construct from input point cloud and specified indices
276 const PointIndices& indices) {
277 CopyPointCloud(pc, indices);
278 }
280 const std::vector<int>& indices) {
281 CopyPointCloud(pc, indices);
282 }
283 // @brief construct given width and height for organized point cloud
284 AttributePointCloud(const size_t width, const size_t height,
285 const PointT point = PointT()) {
286 width_ = width;
287 height_ = height;
288 if (width_ > 0 && height_ > SIZE_MAX / width_) {
289 AFATAL << "overflow detected.";
290 exit(1);
291 }
292 size_t size = width_ * height_;
293 points_.assign(size, point);
294 points_timestamp_.assign(size, 0.0);
295 points_height_.assign(size, std::numeric_limits<float>::max());
296 points_beam_id_.assign(size, -1);
297 points_label_.assign(size, 0);
298 points_semantic_label_.assign(size, 0);
299 }
300 // @brief destructor
301 virtual ~AttributePointCloud() = default;
302 // @brief add points of input cloud, return the self cloud
304 const AttributePointCloud<PointT>& rhs) {
305 points_.insert(points_.end(), rhs.points_.begin(), rhs.points_.end());
307 rhs.points_timestamp_.begin(),
308 rhs.points_timestamp_.end());
309 points_height_.insert(points_height_.end(), rhs.points_height_.begin(),
310 rhs.points_height_.end());
311 points_beam_id_.insert(points_beam_id_.end(), rhs.points_beam_id_.begin(),
312 rhs.points_beam_id_.end());
313 points_label_.insert(points_label_.end(), rhs.points_label_.begin(),
314 rhs.points_label_.end());
316 rhs.points_semantic_label_.begin(),
317 rhs.points_semantic_label_.end());
318 width_ = width_ * height_ + rhs.width_ * rhs.height_;
319 height_ = 1;
320 return *this;
321 }
322 // @brief overrided reserve function wrapper of vector
323 inline void reserve(const size_t size) override {
324 points_.reserve(size);
325 points_timestamp_.reserve(size);
326 points_height_.reserve(size);
327 points_beam_id_.reserve(size);
328 points_label_.reserve(size);
330 }
331 // @brief overrided resize function wrapper of vector
332 inline void resize(const size_t size) override {
333 points_.resize(size);
334 points_timestamp_.resize(size, 0.0);
335 points_height_.resize(size, std::numeric_limits<float>::max());
336 points_beam_id_.resize(size, -1);
337 points_label_.resize(size, 0);
338 points_semantic_label_.resize(size, 0);
339 if (size != width_ * height_) {
340 width_ = size;
341 height_ = 1;
342 }
343 }
344 // @brief overrided push_back function wrapper of vector
345 inline void push_back(const PointT& point) override {
346 points_.push_back(point);
347 points_timestamp_.push_back(0.0);
348 points_height_.push_back(std::numeric_limits<float>::max());
349 points_beam_id_.push_back(-1);
350 points_label_.push_back(0);
351 points_semantic_label_.push_back(0);
352 width_ = points_.size();
353 height_ = 1;
354 }
355 inline void push_back(const PointT& point, double timestamp,
356 float height = std::numeric_limits<float>::max(),
357 int32_t beam_id = -1, uint8_t label = 0,
358 uint8_t semantic_label = 0) {
359 points_.push_back(point);
360 points_timestamp_.push_back(timestamp);
361 points_height_.push_back(height);
362 points_beam_id_.push_back(beam_id);
363 points_label_.push_back(label);
364 points_semantic_label_.push_back(semantic_label);
365 width_ = points_.size();
366 height_ = 1;
367 }
368 // @brief overrided clear function wrapper of vector
369 inline void clear() override {
370 points_.clear();
371 points_timestamp_.clear();
372 points_height_.clear();
373 points_beam_id_.clear();
374 points_label_.clear();
376 width_ = height_ = 0;
377 }
378 // @brief overrided swap point given source and target id
379 inline bool SwapPoint(const size_t source_id,
380 const size_t target_id) override {
381 if (source_id < points_.size() && target_id < points_.size()) {
382 std::swap(points_[source_id], points_[target_id]);
383 std::swap(points_timestamp_[source_id], points_timestamp_[target_id]);
384 std::swap(points_height_[source_id], points_height_[target_id]);
385 std::swap(points_beam_id_[source_id], points_beam_id_[target_id]);
386 std::swap(points_label_[source_id], points_label_[target_id]);
387 std::swap(points_semantic_label_[source_id],
388 points_semantic_label_[target_id]);
389 width_ = points_.size();
390 height_ = 1;
391 return true;
392 }
393 return false;
394 }
395 // @brief copy point from another point cloud
396 inline bool CopyPoint(const size_t id, const size_t rhs_id,
397 const AttributePointCloud<PointT>& rhs) {
398 if (id < points_.size() && rhs_id < rhs.points_.size()) {
399 points_[id] = rhs.points_[rhs_id];
400 points_timestamp_[id] = rhs.points_timestamp_[rhs_id];
401 points_height_[id] = rhs.points_height_[rhs_id];
402 points_beam_id_[id] = rhs.points_beam_id_[rhs_id];
403 points_label_[id] = rhs.points_label_[rhs_id];
405 return true;
406 }
407 return false;
408 }
409 // @brief copy point cloud
411 const PointIndices& indices) {
412 CopyPointCloud(rhs, indices.indices);
413 }
414 template <typename IndexType>
416 const std::vector<IndexType>& indices) {
417 width_ = indices.size();
418 height_ = 1;
419 points_.resize(indices.size());
420 points_timestamp_.resize(indices.size());
421 points_height_.resize(indices.size());
422 points_beam_id_.resize(indices.size());
423 points_label_.resize(indices.size());
424 points_semantic_label_.resize(indices.size());
425 for (size_t i = 0; i < indices.size(); ++i) {
426 points_[i] = rhs.points_[indices[i]];
427 points_timestamp_[i] = rhs.points_timestamp_[indices[i]];
428 points_height_[i] = rhs.points_height_[indices[i]];
429 points_beam_id_[i] = rhs.points_beam_id_[indices[i]];
430 points_label_[i] = rhs.points_label_[indices[i]];
432 }
433 }
434
435 // @brief swap point cloud
437 points_.swap(rhs->points_);
438 std::swap(width_, rhs->width_);
439 std::swap(height_, rhs->height_);
441 std::swap(timestamp_, rhs->timestamp_);
445 points_label_.swap(rhs->points_label_);
447 }
448 // @brief overrided check data member consistency
449 bool CheckConsistency() const override {
450 return ((points_.size() == points_timestamp_.size()) &&
451 (points_.size() == points_height_.size()) &&
452 (points_.size() == points_beam_id_.size()) &&
453 (points_.size() == points_label_.size()) &&
454 (points_.size() == points_semantic_label_.size()));
455 }
456
457 size_t TransferToIndex(const size_t col, const size_t row) const {
458 return row * width_ + col;
459 }
460
461 const std::vector<double>& points_timestamp() const {
462 return points_timestamp_;
463 }
464 double points_timestamp(size_t i) const { return points_timestamp_[i]; }
465 std::vector<double>* mutable_points_timestamp() { return &points_timestamp_; }
466
467 const std::vector<float>& points_height() const { return points_height_; }
468 float& points_height(size_t i) { return points_height_[i]; }
469 const float& points_height(size_t i) const { return points_height_[i]; }
470 void SetPointHeight(size_t i, size_t j, float height) {
471 points_height_[i * width_ + j] = height;
472 }
473 void SetPointHeight(size_t i, float height) { points_height_[i] = height; }
474 std::vector<float>* mutable_points_height() { return &points_height_; }
475
476 const std::vector<int32_t>& points_beam_id() const { return points_beam_id_; }
477 std::vector<int32_t>* mutable_points_beam_id() { return &points_beam_id_; }
478 int32_t& points_beam_id(size_t i) { return points_beam_id_[i]; }
479 const int32_t& points_beam_id(size_t i) const { return points_beam_id_[i]; }
480
481 const std::vector<uint8_t>& points_label() const { return points_label_; }
482 std::vector<uint8_t>* mutable_points_label() { return &points_label_; }
483
484 uint8_t& points_label(size_t i) { return points_label_[i]; }
485 const uint8_t& points_label(size_t i) const { return points_label_[i]; }
486
487 const std::vector<uint8_t>& points_semantic_label() const {
489 }
490 std::vector<uint8_t>* mutable_points_semantic_label() {
492 }
493
494 uint8_t& points_semantic_label(size_t i) {
495 return points_semantic_label_[i];
496 }
497 const uint8_t& points_semantic_label(size_t i) const {
498 return points_semantic_label_[i];
499 }
500
501 protected:
502 std::vector<double> points_timestamp_;
503 std::vector<float> points_height_;
504 std::vector<int32_t> points_beam_id_;
505 std::vector<uint8_t> points_label_;
506 std::vector<uint8_t> points_semantic_label_;
507};
508
509// typedef of point cloud indices
510typedef std::shared_ptr<PointIndices> PointIndicesPtr;
511typedef std::shared_ptr<const PointIndices> PointIndicesConstPtr;
512
513// typedef of point cloud
516
517typedef std::shared_ptr<PointFCloud> PointFCloudPtr;
518typedef std::shared_ptr<const PointFCloud> PointFCloudConstPtr;
519
520typedef std::shared_ptr<PointDCloud> PointDCloudPtr;
521typedef std::shared_ptr<const PointDCloud> PointDCloudConstPtr;
522
523// typedef of polygon
526
527typedef std::shared_ptr<PolygonFType> PolygonFTypePtr;
528typedef std::shared_ptr<const PolygonFType> PolygonFTypeConstPtr;
529
530typedef std::shared_ptr<PolygonDType> PolygonDTypePtr;
531typedef std::shared_ptr<const PolygonDType> PolygonDTypeConstPtr;
532
533} // namespace base
534} // namespace perception
535} // namespace apollo
const std::vector< double > & points_timestamp() const
const int32_t & points_beam_id(size_t i) const
AttributePointCloud(const size_t width, const size_t height, const PointT point=PointT())
const std::vector< float > & points_height() const
AttributePointCloud & operator+=(const AttributePointCloud< PointT > &rhs)
std::vector< float > * mutable_points_height()
AttributePointCloud(const AttributePointCloud< PointT > &pc, const PointIndices &indices)
void CopyPointCloud(const AttributePointCloud< PointT > &rhs, const PointIndices &indices)
void resize(const size_t size) override
const uint8_t & points_semantic_label(size_t i) const
void reserve(const size_t size) override
AttributePointCloud(const AttributePointCloud< PointT > &pc, const std::vector< int > &indices)
void push_back(const PointT &point, double timestamp, float height=std::numeric_limits< float >::max(), int32_t beam_id=-1, uint8_t label=0, uint8_t semantic_label=0)
const std::vector< int32_t > & points_beam_id() const
std::vector< int32_t > * mutable_points_beam_id()
void SwapPointCloud(AttributePointCloud< PointT > *rhs)
void SetPointHeight(size_t i, float height)
std::vector< uint8_t > * mutable_points_label()
std::vector< uint8_t > * mutable_points_semantic_label()
void CopyPointCloud(const AttributePointCloud< PointT > &rhs, const std::vector< IndexType > &indices)
const std::vector< uint8_t > & points_label() const
bool SwapPoint(const size_t source_id, const size_t target_id) override
size_t TransferToIndex(const size_t col, const size_t row) const
const float & points_height(size_t i) const
const uint8_t & points_label(size_t i) const
std::vector< double > * mutable_points_timestamp()
void push_back(const PointT &point) override
bool CopyPoint(const size_t id, const size_t rhs_id, const AttributePointCloud< PointT > &rhs)
void SetPointHeight(size_t i, size_t j, float height)
const std::vector< uint8_t > & points_semantic_label() const
bool CopyPoint(size_t id, size_t rhs_id, const PointCloud< PointT > &rhs)
const PointT * at(size_t col, size_t row) const
Definition point_cloud.h:63
PointCloud(const PointCloud< PointT > &pc, const PointIndices &indices)
Definition point_cloud.h:46
virtual void resize(size_t size)
Definition point_cloud.h:88
std::vector< PointT > * mutable_points()
void SwapPointCloud(PointCloud< PointT > *rhs)
virtual bool SwapPoint(size_t source_id, size_t target_id)
PointT * operator()(size_t col, size_t row)
Definition point_cloud.h:72
void CopyPointCloud(const PointCloud< PointT > &rhs, const PointIndices &indices)
const Eigen::Affine3d & sensor_to_world_pose()
void TransformPointCloud(const Eigen::Affine3f &transform, PointCloud< PointT > *out, bool check_nan=false) const
virtual void push_back(const PointT &point)
PointT * at(size_t col, size_t row)
Definition point_cloud.h:66
const PointT * operator()(size_t col, size_t row) const
Definition point_cloud.h:69
const PointT & operator[](size_t n) const
Definition point_cloud.h:96
std::vector< PointT >::const_iterator const_iterator
std::vector< PointT >::iterator iterator
PointCloud(const PointCloud< PointT > &pc, const std::vector< int > &indices)
Definition point_cloud.h:49
void set_timestamp(const double timestamp)
virtual void reserve(size_t size)
Definition point_cloud.h:84
virtual bool CheckConsistency() const
void set_sensor_to_world_pose(const Eigen::Affine3d &sensor_to_world_pose)
void CopyPointCloud(const PointCloud< PointT > &rhs, const std::vector< IndexType > &indices)
const std::vector< PointT > & points() const
void CopyPointCloudExclude(const PointCloud< PointT > &rhs, const std::vector< IndexType > &indices)
PointCloud(size_t width, size_t height, PointT point=PointT())
Definition point_cloud.h:53
const PointT & at(size_t n) const
Definition point_cloud.h:98
void TransformPointCloud(bool check_nan=false)
void RotatePointCloud(bool check_nan=false)
#define AFATAL
Definition log.h:45
std::shared_ptr< const PolygonFType > PolygonFTypeConstPtr
AttributePointCloud< PointF > PointFCloud
std::shared_ptr< PointDCloud > PointDCloudPtr
AttributePointCloud< PointD > PointDCloud
std::shared_ptr< const PolygonDType > PolygonDTypeConstPtr
std::shared_ptr< PolygonFType > PolygonFTypePtr
std::shared_ptr< PointFCloud > PointFCloudPtr
PointCloud< PointF > PolygonFType
std::shared_ptr< PointIndices > PointIndicesPtr
PointCloud< PointD > PolygonDType
std::shared_ptr< const PointDCloud > PointDCloudConstPtr
std::shared_ptr< PolygonDType > PolygonDTypePtr
std::shared_ptr< const PointIndices > PointIndicesConstPtr
std::shared_ptr< const PointFCloud > PointFCloudConstPtr
class register implement
Definition arena_queue.h:37