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

#include <radar_point_cloud.h>

类 apollo::perception::base::AttributeRadarPointCloud< RadarPointT > 继承关系图:
apollo::perception::base::AttributeRadarPointCloud< RadarPointT > 的协作图:

Public 成员函数

 AttributeRadarPointCloud ()=default
 
 AttributeRadarPointCloud (const AttributeRadarPointCloud< RadarPointT > &pc, const PointIndices &indices)
 
 AttributeRadarPointCloud (const AttributeRadarPointCloud< RadarPointT > &pc, const std::vector< int > &indices)
 
 AttributeRadarPointCloud (const size_t width, const size_t height, const RadarPointT point=RadarPointT())
 
virtual ~AttributeRadarPointCloud ()=default
 
AttributeRadarPointCloudoperator+= (const AttributeRadarPointCloud< RadarPointT > &rhs)
 
void reserve (const size_t size) override
 
void resize (const size_t size) override
 
void push_back (const RadarPointT &point) override
 
void push_back (const RadarPointT &point, double timestamp, float height=std::numeric_limits< float >::max(), int32_t beam_id=-1, uint8_t 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 AttributeRadarPointCloud< RadarPointT > &rhs)
 
void CopyRadarPointCloud (const AttributeRadarPointCloud< RadarPointT > &rhs, const PointIndices &indices)
 
template<typename IndexType >
void CopyRadarPointCloud (const AttributeRadarPointCloud< RadarPointT > &rhs, const std::vector< IndexType > &indices)
 
void SwapRadarPointCloud (AttributeRadarPointCloud< RadarPointT > *rhs)
 
bool CheckConsistency () const override
 
size_t TransferToIndex (const size_t col, const size_t row) const
 
- Public 成员函数 继承自 apollo::perception::base::RadarPointCloud< RadarPointT >
 RadarPointCloud ()=default
 
 RadarPointCloud (const RadarPointCloud< RadarPointT > &pc, const PointIndices &indices)
 
 RadarPointCloud (const RadarPointCloud< RadarPointT > &pc, const std::vector< int > &indices)
 
 RadarPointCloud (size_t width, size_t height, RadarPointT point=RadarPointT())
 
virtual ~RadarPointCloud ()=default
 
const RadarPointT * at (size_t col, size_t row) const
 
RadarPointT * at (size_t col, size_t row)
 
const RadarPointT * operator() (size_t col, size_t row) const
 
RadarPointT * 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 RadarPointT & operator[] (size_t n) const
 
RadarPointT & operator[] (size_t n)
 
const RadarPointT & at (size_t n) const
 
RadarPointT & at (size_t n)
 
const RadarPointT & front () const
 
RadarPointT & front ()
 
const RadarPointT & back () const
 
RadarPointT & back ()
 
bool CopyPoint (size_t id, size_t rhs_id, const RadarPointCloud< RadarPointT > &rhs)
 
void CopyRadarPointCloud (const RadarPointCloud< RadarPointT > &rhs, const PointIndices &indices)
 
template<typename IndexType >
void CopyRadarPointCloud (const RadarPointCloud< RadarPointT > &rhs, const std::vector< IndexType > &indices)
 
template<typename IndexType >
void CopyRadarPointCloudExclude (const RadarPointCloud< RadarPointT > &rhs, const std::vector< IndexType > &indices)
 
void SwapRadarPointCloud (RadarPointCloud< RadarPointT > *rhs)
 
iterator begin ()
 
iterator end ()
 
const_iterator begin () const
 
const_iterator end () const
 
std::vector< RadarPointT > * mutable_points ()
 
const std::vector< RadarPointT > & 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 RotateRadarPointCloud (bool check_nan=false)
 
void TransformRadarPointCloud (bool check_nan=false)
 
void TransformRadarPointCloud (const Eigen::Affine3f &transform, RadarPointCloud< RadarPointT > *out, bool check_nan=false) const
 

额外继承的成员函数

- Public 类型 继承自 apollo::perception::base::RadarPointCloud< RadarPointT >
using PointType = RadarPointT
 
typedef std::vector< RadarPointT >::iterator iterator
 
typedef std::vector< RadarPointT >::const_iterator const_iterator
 
- Protected 属性 继承自 apollo::perception::base::RadarPointCloud< RadarPointT >
std::vector< RadarPointT > points_
 
size_t width_ = 0
 
size_t height_ = 0
 
Eigen::Affine3d sensor_to_world_pose_ = Eigen::Affine3d::Identity()
 
double timestamp_ = 0.0
 

详细描述

template<class RadarPointT>
class apollo::perception::base::AttributeRadarPointCloud< RadarPointT >

在文件 radar_point_cloud.h269 行定义.

构造及析构函数说明

◆ AttributeRadarPointCloud() [1/4]

template<class RadarPointT >
apollo::perception::base::AttributeRadarPointCloud< RadarPointT >::AttributeRadarPointCloud ( )
default

◆ AttributeRadarPointCloud() [2/4]

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

在文件 radar_point_cloud.h281 行定义.

282 {
283 CopyRadarPointCloud(pc, indices);
284 }
void CopyRadarPointCloud(const AttributeRadarPointCloud< RadarPointT > &rhs, const PointIndices &indices)

◆ AttributeRadarPointCloud() [3/4]

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

在文件 radar_point_cloud.h285 行定义.

286 {
287 CopyRadarPointCloud(pc, indices);
288 }

◆ AttributeRadarPointCloud() [4/4]

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

在文件 radar_point_cloud.h290 行定义.

291 {
292 width_ = width;
293 height_ = height;
294 if (width_ > 0 && height_ > SIZE_MAX / width_) {
295 AFATAL << "overflow detected.";
296 exit(1);
297 }
298 size_t size = width_ * height_;
299 points_.assign(size, point);
300 }
#define AFATAL
Definition log.h:45

◆ ~AttributeRadarPointCloud()

template<class RadarPointT >
virtual apollo::perception::base::AttributeRadarPointCloud< RadarPointT >::~AttributeRadarPointCloud ( )
virtualdefault

成员函数说明

◆ CheckConsistency()

template<class RadarPointT >
bool apollo::perception::base::AttributeRadarPointCloud< RadarPointT >::CheckConsistency ( ) const
inlineoverridevirtual

重载 apollo::perception::base::RadarPointCloud< RadarPointT > .

在文件 radar_point_cloud.h388 行定义.

388 {
389 return true;
390 }

◆ clear()

template<class RadarPointT >
void apollo::perception::base::AttributeRadarPointCloud< RadarPointT >::clear ( )
inlineoverridevirtual

重载 apollo::perception::base::RadarPointCloud< RadarPointT > .

在文件 radar_point_cloud.h337 行定义.

337 {
338 points_.clear();
339 width_ = height_ = 0;
340 }

◆ CopyPoint()

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

在文件 radar_point_cloud.h353 行定义.

354 {
355 if (id < points_.size() && rhs_id < rhs.points_.size()) {
356 points_[id] = rhs.points_[rhs_id];
357 return true;
358 }
359 return false;
360 }

◆ CopyRadarPointCloud() [1/2]

template<class RadarPointT >
void apollo::perception::base::AttributeRadarPointCloud< RadarPointT >::CopyRadarPointCloud ( const AttributeRadarPointCloud< RadarPointT > &  rhs,
const PointIndices indices 
)
inline

在文件 radar_point_cloud.h362 行定义.

364 {
365 CopyRadarPointCloud(rhs, indices.indices);
366 }

◆ CopyRadarPointCloud() [2/2]

template<class RadarPointT >
template<typename IndexType >
void apollo::perception::base::AttributeRadarPointCloud< RadarPointT >::CopyRadarPointCloud ( const AttributeRadarPointCloud< RadarPointT > &  rhs,
const std::vector< IndexType > &  indices 
)
inline

在文件 radar_point_cloud.h368 行定义.

370 {
371 width_ = indices.size();
372 height_ = 1;
373 points_.resize(indices.size());
374 for (size_t i = 0; i < indices.size(); ++i) {
375 points_[i] = rhs.points_[indices[i]];
376 }
377 }

◆ operator+=()

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

在文件 radar_point_cloud.h304 行定义.

305 {
306 points_.insert(points_.end(), rhs.points_.begin(), rhs.points_.end());
307 width_ = width_ * height_ + rhs.width_ * rhs.height_;
308 height_ = 1;
309 return *this;
310 }

◆ push_back() [1/2]

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

重载 apollo::perception::base::RadarPointCloud< RadarPointT > .

在文件 radar_point_cloud.h324 行定义.

324 {
325 points_.push_back(point);
326 width_ = points_.size();
327 height_ = 1;
328 }

◆ push_back() [2/2]

template<class RadarPointT >
void apollo::perception::base::AttributeRadarPointCloud< RadarPointT >::push_back ( const RadarPointT &  point,
double  timestamp,
float  height = std::numeric_limits<float>::max(),
int32_t  beam_id = -1,
uint8_t  label = 0 
)
inline

在文件 radar_point_cloud.h329 行定义.

331 {
332 points_.push_back(point);
333 width_ = points_.size();
334 height_ = 1;
335 }

◆ reserve()

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

重载 apollo::perception::base::RadarPointCloud< RadarPointT > .

在文件 radar_point_cloud.h312 行定义.

312 {
313 points_.reserve(size);
314 }

◆ resize()

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

重载 apollo::perception::base::RadarPointCloud< RadarPointT > .

在文件 radar_point_cloud.h316 行定义.

316 {
317 points_.resize(size);
318 if (size != width_ * height_) {
319 width_ = size;
320 height_ = 1;
321 }
322 }

◆ SwapPoint()

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

重载 apollo::perception::base::RadarPointCloud< RadarPointT > .

在文件 radar_point_cloud.h342 行定义.

343 {
344 if (source_id < points_.size() && target_id < points_.size()) {
345 std::swap(points_[source_id], points_[target_id]);
346 width_ = points_.size();
347 height_ = 1;
348 return true;
349 }
350 return false;
351 }

◆ SwapRadarPointCloud()

template<class RadarPointT >
void apollo::perception::base::AttributeRadarPointCloud< RadarPointT >::SwapRadarPointCloud ( AttributeRadarPointCloud< RadarPointT > *  rhs)
inline

在文件 radar_point_cloud.h380 行定义.

380 {
381 points_.swap(rhs->points_);
382 std::swap(width_, rhs->width_);
383 std::swap(height_, rhs->height_);
384 std::swap(sensor_to_world_pose_, rhs->sensor_to_world_pose_);
385 std::swap(timestamp_, rhs->timestamp_);
386 }

◆ TransferToIndex()

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

在文件 radar_point_cloud.h392 行定义.

392 {
393 return row * width_ + col;
394 }

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