Apollo 10.0
自动驾驶开放平台
apollo::perception::base::AttributePointCloud< PointT > 模板类 参考

#include <point_cloud.h>

类 apollo::perception::base::AttributePointCloud< PointT > 继承关系图:
apollo::perception::base::AttributePointCloud< PointT > 的协作图:

Public 成员函数

 AttributePointCloud ()=default
 
 AttributePointCloud (const AttributePointCloud< PointT > &pc, const PointIndices &indices)
 
 AttributePointCloud (const AttributePointCloud< PointT > &pc, const std::vector< int > &indices)
 
 AttributePointCloud (const size_t width, const size_t height, const PointT point=PointT())
 
virtual ~AttributePointCloud ()=default
 
AttributePointCloudoperator+= (const AttributePointCloud< PointT > &rhs)
 
void reserve (const size_t size) override
 
void resize (const size_t size) override
 
void push_back (const PointT &point) override
 
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)
 
void clear () override
 
bool SwapPoint (const size_t source_id, const size_t target_id) override
 
bool CopyPoint (const size_t id, const size_t rhs_id, const AttributePointCloud< PointT > &rhs)
 
void CopyPointCloud (const AttributePointCloud< PointT > &rhs, const PointIndices &indices)
 
template<typename IndexType >
void CopyPointCloud (const AttributePointCloud< PointT > &rhs, const std::vector< IndexType > &indices)
 
void SwapPointCloud (AttributePointCloud< PointT > *rhs)
 
bool CheckConsistency () const override
 
size_t TransferToIndex (const size_t col, const size_t row) const
 
const std::vector< double > & points_timestamp () const
 
double points_timestamp (size_t i) const
 
std::vector< double > * mutable_points_timestamp ()
 
const std::vector< float > & points_height () const
 
float & points_height (size_t i)
 
const float & points_height (size_t i) const
 
void SetPointHeight (size_t i, size_t j, float height)
 
void SetPointHeight (size_t i, float height)
 
std::vector< float > * mutable_points_height ()
 
const std::vector< int32_t > & points_beam_id () const
 
std::vector< int32_t > * mutable_points_beam_id ()
 
int32_t & points_beam_id (size_t i)
 
const int32_t & points_beam_id (size_t i) const
 
const std::vector< uint8_t > & points_label () const
 
std::vector< uint8_t > * mutable_points_label ()
 
uint8_t & points_label (size_t i)
 
const uint8_t & points_label (size_t i) const
 
const std::vector< uint8_t > & points_semantic_label () const
 
std::vector< uint8_t > * mutable_points_semantic_label ()
 
uint8_t & points_semantic_label (size_t i)
 
const uint8_t & points_semantic_label (size_t i) const
 
- Public 成员函数 继承自 apollo::perception::base::PointCloud< PointT >
 PointCloud ()=default
 
 PointCloud (const PointCloud< PointT > &pc, const PointIndices &indices)
 
 PointCloud (const PointCloud< PointT > &pc, const std::vector< int > &indices)
 
 PointCloud (size_t width, size_t height, PointT point=PointT())
 
virtual ~PointCloud ()=default
 
const PointT * at (size_t col, size_t row) const
 
PointT * at (size_t col, size_t row)
 
const PointT * operator() (size_t col, size_t row) const
 
PointT * operator() (size_t col, size_t row)
 
bool IsOrganized () const
 
size_t height () const
 
size_t width () const
 
size_t size () const
 
bool empty () const
 
const PointT & operator[] (size_t n) const
 
PointT & operator[] (size_t n)
 
const PointT & at (size_t n) const
 
PointT & at (size_t n)
 
const PointT & front () const
 
PointT & front ()
 
const PointT & back () const
 
PointT & back ()
 
bool CopyPoint (size_t id, size_t rhs_id, const PointCloud< PointT > &rhs)
 
void CopyPointCloud (const PointCloud< PointT > &rhs, const PointIndices &indices)
 
template<typename IndexType >
void CopyPointCloud (const PointCloud< PointT > &rhs, const std::vector< IndexType > &indices)
 
template<typename IndexType >
void CopyPointCloudExclude (const PointCloud< PointT > &rhs, const std::vector< IndexType > &indices)
 
void SwapPointCloud (PointCloud< PointT > *rhs)
 
iterator begin ()
 
iterator end ()
 
const_iterator begin () const
 
const_iterator end () const
 
std::vector< PointT > * mutable_points ()
 
const std::vector< PointT > & points () const
 
void set_timestamp (const double timestamp)
 
double get_timestamp ()
 
void set_sensor_to_world_pose (const Eigen::Affine3d &sensor_to_world_pose)
 
const Eigen::Affine3d & sensor_to_world_pose ()
 
void RotatePointCloud (bool check_nan=false)
 
void TransformPointCloud (bool check_nan=false)
 
void TransformPointCloud (const Eigen::Affine3f &transform, PointCloud< PointT > *out, bool check_nan=false) const
 

Protected 属性

std::vector< double > points_timestamp_
 
std::vector< float > points_height_
 
std::vector< int32_t > points_beam_id_
 
std::vector< uint8_t > points_label_
 
std::vector< uint8_t > points_semantic_label_
 
- Protected 属性 继承自 apollo::perception::base::PointCloud< PointT >
std::vector< PointT > points_
 
size_t width_ = 0
 
size_t height_ = 0
 
Eigen::Affine3d sensor_to_world_pose_ = Eigen::Affine3d::Identity()
 
double timestamp_ = 0.0
 

额外继承的成员函数

- Public 类型 继承自 apollo::perception::base::PointCloud< PointT >
using PointType = PointT
 
typedef std::vector< PointT >::iterator iterator
 
typedef std::vector< PointT >::const_iterator const_iterator
 

详细描述

template<class PointT>
class apollo::perception::base::AttributePointCloud< PointT >

在文件 point_cloud.h263 行定义.

构造及析构函数说明

◆ AttributePointCloud() [1/4]

template<class PointT >
apollo::perception::base::AttributePointCloud< PointT >::AttributePointCloud ( )
default

◆ AttributePointCloud() [2/4]

template<class PointT >
apollo::perception::base::AttributePointCloud< PointT >::AttributePointCloud ( const AttributePointCloud< PointT > &  pc,
const PointIndices indices 
)
inline

在文件 point_cloud.h275 行定义.

276 {
277 CopyPointCloud(pc, indices);
278 }
void CopyPointCloud(const AttributePointCloud< PointT > &rhs, const PointIndices &indices)

◆ AttributePointCloud() [3/4]

template<class PointT >
apollo::perception::base::AttributePointCloud< PointT >::AttributePointCloud ( const AttributePointCloud< PointT > &  pc,
const std::vector< int > &  indices 
)
inline

在文件 point_cloud.h279 行定义.

280 {
281 CopyPointCloud(pc, indices);
282 }

◆ AttributePointCloud() [4/4]

template<class PointT >
apollo::perception::base::AttributePointCloud< PointT >::AttributePointCloud ( const size_t  width,
const size_t  height,
const PointT  point = PointT() 
)
inline

在文件 point_cloud.h284 行定义.

285 {
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 }
#define AFATAL
Definition log.h:45

◆ ~AttributePointCloud()

template<class PointT >
virtual apollo::perception::base::AttributePointCloud< PointT >::~AttributePointCloud ( )
virtualdefault

成员函数说明

◆ CheckConsistency()

template<class PointT >
bool apollo::perception::base::AttributePointCloud< PointT >::CheckConsistency ( ) const
inlineoverridevirtual

重载 apollo::perception::base::PointCloud< PointT > .

在文件 point_cloud.h449 行定义.

449 {
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 }

◆ clear()

template<class PointT >
void apollo::perception::base::AttributePointCloud< PointT >::clear ( )
inlineoverridevirtual

重载 apollo::perception::base::PointCloud< PointT > .

在文件 point_cloud.h369 行定义.

369 {
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 }

◆ CopyPoint()

template<class PointT >
bool apollo::perception::base::AttributePointCloud< PointT >::CopyPoint ( const size_t  id,
const size_t  rhs_id,
const AttributePointCloud< PointT > &  rhs 
)
inline

在文件 point_cloud.h396 行定义.

397 {
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];
404 points_semantic_label_[id] = rhs.points_semantic_label_[rhs_id];
405 return true;
406 }
407 return false;
408 }

◆ CopyPointCloud() [1/2]

template<class PointT >
void apollo::perception::base::AttributePointCloud< PointT >::CopyPointCloud ( const AttributePointCloud< PointT > &  rhs,
const PointIndices indices 
)
inline

在文件 point_cloud.h410 行定义.

411 {
412 CopyPointCloud(rhs, indices.indices);
413 }

◆ CopyPointCloud() [2/2]

template<class PointT >
template<typename IndexType >
void apollo::perception::base::AttributePointCloud< PointT >::CopyPointCloud ( const AttributePointCloud< PointT > &  rhs,
const std::vector< IndexType > &  indices 
)
inline

在文件 point_cloud.h415 行定义.

416 {
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]];
431 points_semantic_label_[i] = rhs.points_semantic_label_[indices[i]];
432 }
433 }

◆ mutable_points_beam_id()

template<class PointT >
std::vector< int32_t > * apollo::perception::base::AttributePointCloud< PointT >::mutable_points_beam_id ( )
inline

在文件 point_cloud.h477 行定义.

477{ return &points_beam_id_; }

◆ mutable_points_height()

template<class PointT >
std::vector< float > * apollo::perception::base::AttributePointCloud< PointT >::mutable_points_height ( )
inline

在文件 point_cloud.h474 行定义.

474{ return &points_height_; }

◆ mutable_points_label()

template<class PointT >
std::vector< uint8_t > * apollo::perception::base::AttributePointCloud< PointT >::mutable_points_label ( )
inline

在文件 point_cloud.h482 行定义.

482{ return &points_label_; }

◆ mutable_points_semantic_label()

template<class PointT >
std::vector< uint8_t > * apollo::perception::base::AttributePointCloud< PointT >::mutable_points_semantic_label ( )
inline

在文件 point_cloud.h490 行定义.

490 {
492 }

◆ mutable_points_timestamp()

template<class PointT >
std::vector< double > * apollo::perception::base::AttributePointCloud< PointT >::mutable_points_timestamp ( )
inline

在文件 point_cloud.h465 行定义.

465{ return &points_timestamp_; }

◆ operator+=()

template<class PointT >
AttributePointCloud & apollo::perception::base::AttributePointCloud< PointT >::operator+= ( const AttributePointCloud< PointT > &  rhs)
inline

在文件 point_cloud.h303 行定义.

304 {
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 }

◆ points_beam_id() [1/3]

template<class PointT >
const std::vector< int32_t > & apollo::perception::base::AttributePointCloud< PointT >::points_beam_id ( ) const
inline

在文件 point_cloud.h476 行定义.

476{ return points_beam_id_; }

◆ points_beam_id() [2/3]

template<class PointT >
int32_t & apollo::perception::base::AttributePointCloud< PointT >::points_beam_id ( size_t  i)
inline

在文件 point_cloud.h478 行定义.

478{ return points_beam_id_[i]; }

◆ points_beam_id() [3/3]

template<class PointT >
const int32_t & apollo::perception::base::AttributePointCloud< PointT >::points_beam_id ( size_t  i) const
inline

在文件 point_cloud.h479 行定义.

479{ return points_beam_id_[i]; }

◆ points_height() [1/3]

template<class PointT >
const std::vector< float > & apollo::perception::base::AttributePointCloud< PointT >::points_height ( ) const
inline

在文件 point_cloud.h467 行定义.

467{ return points_height_; }

◆ points_height() [2/3]

template<class PointT >
float & apollo::perception::base::AttributePointCloud< PointT >::points_height ( size_t  i)
inline

在文件 point_cloud.h468 行定义.

468{ return points_height_[i]; }

◆ points_height() [3/3]

template<class PointT >
const float & apollo::perception::base::AttributePointCloud< PointT >::points_height ( size_t  i) const
inline

在文件 point_cloud.h469 行定义.

469{ return points_height_[i]; }

◆ points_label() [1/3]

template<class PointT >
const std::vector< uint8_t > & apollo::perception::base::AttributePointCloud< PointT >::points_label ( ) const
inline

在文件 point_cloud.h481 行定义.

481{ return points_label_; }

◆ points_label() [2/3]

template<class PointT >
uint8_t & apollo::perception::base::AttributePointCloud< PointT >::points_label ( size_t  i)
inline

在文件 point_cloud.h484 行定义.

484{ return points_label_[i]; }

◆ points_label() [3/3]

template<class PointT >
const uint8_t & apollo::perception::base::AttributePointCloud< PointT >::points_label ( size_t  i) const
inline

在文件 point_cloud.h485 行定义.

485{ return points_label_[i]; }

◆ points_semantic_label() [1/3]

template<class PointT >
const std::vector< uint8_t > & apollo::perception::base::AttributePointCloud< PointT >::points_semantic_label ( ) const
inline

在文件 point_cloud.h487 行定义.

487 {
489 }

◆ points_semantic_label() [2/3]

template<class PointT >
uint8_t & apollo::perception::base::AttributePointCloud< PointT >::points_semantic_label ( size_t  i)
inline

在文件 point_cloud.h494 行定义.

494 {
495 return points_semantic_label_[i];
496 }

◆ points_semantic_label() [3/3]

template<class PointT >
const uint8_t & apollo::perception::base::AttributePointCloud< PointT >::points_semantic_label ( size_t  i) const
inline

在文件 point_cloud.h497 行定义.

497 {
498 return points_semantic_label_[i];
499 }

◆ points_timestamp() [1/2]

template<class PointT >
const std::vector< double > & apollo::perception::base::AttributePointCloud< PointT >::points_timestamp ( ) const
inline

在文件 point_cloud.h461 行定义.

461 {
462 return points_timestamp_;
463 }

◆ points_timestamp() [2/2]

template<class PointT >
double apollo::perception::base::AttributePointCloud< PointT >::points_timestamp ( size_t  i) const
inline

在文件 point_cloud.h464 行定义.

464{ return points_timestamp_[i]; }

◆ push_back() [1/2]

template<class PointT >
void apollo::perception::base::AttributePointCloud< PointT >::push_back ( const PointT &  point)
inlineoverridevirtual

重载 apollo::perception::base::PointCloud< PointT > .

在文件 point_cloud.h345 行定义.

345 {
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 }

◆ push_back() [2/2]

template<class PointT >
void apollo::perception::base::AttributePointCloud< PointT >::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 
)
inline

在文件 point_cloud.h355 行定义.

358 {
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 }

◆ reserve()

template<class PointT >
void apollo::perception::base::AttributePointCloud< PointT >::reserve ( const size_t  size)
inlineoverridevirtual

重载 apollo::perception::base::PointCloud< PointT > .

在文件 point_cloud.h323 行定义.

323 {
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 }

◆ resize()

template<class PointT >
void apollo::perception::base::AttributePointCloud< PointT >::resize ( const size_t  size)
inlineoverridevirtual

重载 apollo::perception::base::PointCloud< PointT > .

在文件 point_cloud.h332 行定义.

332 {
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 }

◆ SetPointHeight() [1/2]

template<class PointT >
void apollo::perception::base::AttributePointCloud< PointT >::SetPointHeight ( size_t  i,
float  height 
)
inline

在文件 point_cloud.h473 行定义.

473{ points_height_[i] = height; }

◆ SetPointHeight() [2/2]

template<class PointT >
void apollo::perception::base::AttributePointCloud< PointT >::SetPointHeight ( size_t  i,
size_t  j,
float  height 
)
inline

在文件 point_cloud.h470 行定义.

470 {
471 points_height_[i * width_ + j] = height;
472 }

◆ SwapPoint()

template<class PointT >
bool apollo::perception::base::AttributePointCloud< PointT >::SwapPoint ( const size_t  source_id,
const size_t  target_id 
)
inlineoverridevirtual

重载 apollo::perception::base::PointCloud< PointT > .

在文件 point_cloud.h379 行定义.

380 {
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 }

◆ SwapPointCloud()

template<class PointT >
void apollo::perception::base::AttributePointCloud< PointT >::SwapPointCloud ( AttributePointCloud< PointT > *  rhs)
inline

在文件 point_cloud.h436 行定义.

436 {
437 points_.swap(rhs->points_);
438 std::swap(width_, rhs->width_);
439 std::swap(height_, rhs->height_);
440 std::swap(sensor_to_world_pose_, rhs->sensor_to_world_pose_);
441 std::swap(timestamp_, rhs->timestamp_);
442 points_timestamp_.swap(rhs->points_timestamp_);
443 points_height_.swap(rhs->points_height_);
444 points_beam_id_.swap(rhs->points_beam_id_);
445 points_label_.swap(rhs->points_label_);
446 points_semantic_label_.swap(rhs->points_semantic_label_);
447 }

◆ TransferToIndex()

template<class PointT >
size_t apollo::perception::base::AttributePointCloud< PointT >::TransferToIndex ( const size_t  col,
const size_t  row 
) const
inline

在文件 point_cloud.h457 行定义.

457 {
458 return row * width_ + col;
459 }

类成员变量说明

◆ points_beam_id_

template<class PointT >
std::vector<int32_t> apollo::perception::base::AttributePointCloud< PointT >::points_beam_id_
protected

在文件 point_cloud.h504 行定义.

◆ points_height_

template<class PointT >
std::vector<float> apollo::perception::base::AttributePointCloud< PointT >::points_height_
protected

在文件 point_cloud.h503 行定义.

◆ points_label_

template<class PointT >
std::vector<uint8_t> apollo::perception::base::AttributePointCloud< PointT >::points_label_
protected

在文件 point_cloud.h505 行定义.

◆ points_semantic_label_

template<class PointT >
std::vector<uint8_t> apollo::perception::base::AttributePointCloud< PointT >::points_semantic_label_
protected

在文件 point_cloud.h506 行定义.

◆ points_timestamp_

template<class PointT >
std::vector<double> apollo::perception::base::AttributePointCloud< PointT >::points_timestamp_
protected

在文件 point_cloud.h502 行定义.


该类的文档由以下文件生成: