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

#include <point_cloud.h>

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

Public 类型

using PointType = PointT
 
typedef std::vector< PointT >::iterator iterator
 
typedef std::vector< PointT >::const_iterator const_iterator
 

Public 成员函数

 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
 
virtual void reserve (size_t size)
 
bool empty () const
 
virtual void resize (size_t size)
 
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 ()
 
virtual void push_back (const PointT &point)
 
virtual void clear ()
 
virtual bool SwapPoint (size_t source_id, size_t target_id)
 
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
 
virtual bool CheckConsistency () const
 

Protected 属性

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
 

详细描述

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

在文件 point_cloud.h36 行定义.

成员类型定义说明

◆ const_iterator

template<class PointT >
typedef std::vector<PointT>::const_iterator apollo::perception::base::PointCloud< PointT >::const_iterator

在文件 point_cloud.h177 行定义.

◆ iterator

template<class PointT >
typedef std::vector<PointT>::iterator apollo::perception::base::PointCloud< PointT >::iterator

在文件 point_cloud.h176 行定义.

◆ PointType

template<class PointT >
using apollo::perception::base::PointCloud< PointT >::PointType = PointT

在文件 point_cloud.h41 行定义.

构造及析构函数说明

◆ PointCloud() [1/4]

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

◆ PointCloud() [2/4]

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

在文件 point_cloud.h46 行定义.

46 {
47 CopyPointCloud(pc, indices);
48 }
void CopyPointCloud(const PointCloud< PointT > &rhs, const PointIndices &indices)

◆ PointCloud() [3/4]

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

在文件 point_cloud.h49 行定义.

49 {
50 CopyPointCloud(pc, indices);
51 }

◆ PointCloud() [4/4]

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

◆ ~PointCloud()

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

成员函数说明

◆ at() [1/4]

template<class PointT >
PointT * apollo::perception::base::PointCloud< PointT >::at ( size_t  col,
size_t  row 
)
inline

在文件 point_cloud.h66 行定义.

66 {
67 return IsOrganized() ? &(points_[row * width_ + col]) : nullptr;
68 }

◆ at() [2/4]

template<class PointT >
const PointT * apollo::perception::base::PointCloud< PointT >::at ( size_t  col,
size_t  row 
) const
inline

在文件 point_cloud.h63 行定义.

63 {
64 return IsOrganized() ? &(points_[row * width_ + col]) : nullptr;
65 }

◆ at() [3/4]

template<class PointT >
PointT & apollo::perception::base::PointCloud< PointT >::at ( size_t  n)
inline

在文件 point_cloud.h99 行定义.

99{ return points_[n]; }

◆ at() [4/4]

template<class PointT >
const PointT & apollo::perception::base::PointCloud< PointT >::at ( size_t  n) const
inline

在文件 point_cloud.h98 行定义.

98{ return points_[n]; }

◆ back() [1/2]

template<class PointT >
PointT & apollo::perception::base::PointCloud< PointT >::back ( )
inline

在文件 point_cloud.h105 行定义.

105{ return points_.back(); }

◆ back() [2/2]

template<class PointT >
const PointT & apollo::perception::base::PointCloud< PointT >::back ( ) const
inline

在文件 point_cloud.h104 行定义.

104{ return points_.back(); }

◆ begin() [1/2]

template<class PointT >
iterator apollo::perception::base::PointCloud< PointT >::begin ( )
inline

在文件 point_cloud.h179 行定义.

179{ return points_.begin(); }

◆ begin() [2/2]

template<class PointT >
const_iterator apollo::perception::base::PointCloud< PointT >::begin ( ) const
inline

在文件 point_cloud.h181 行定义.

181{ return points_.begin(); }

◆ CheckConsistency()

template<class PointT >
virtual bool apollo::perception::base::PointCloud< PointT >::CheckConsistency ( ) const
inlinevirtual

◆ clear()

◆ CopyPoint()

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

在文件 point_cloud.h128 行定义.

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

◆ CopyPointCloud() [1/2]

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

在文件 point_cloud.h137 行定义.

138 {
139 CopyPointCloud(rhs, indices.indices);
140 }

◆ CopyPointCloud() [2/2]

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

在文件 point_cloud.h142 行定义.

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

◆ CopyPointCloudExclude()

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

在文件 point_cloud.h152 行定义.

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

◆ empty()

template<class PointT >
bool apollo::perception::base::PointCloud< PointT >::empty ( ) const
inline

在文件 point_cloud.h86 行定义.

86{ return points_.empty(); }

◆ end() [1/2]

template<class PointT >
iterator apollo::perception::base::PointCloud< PointT >::end ( )
inline

在文件 point_cloud.h180 行定义.

180{ return points_.end(); }

◆ end() [2/2]

template<class PointT >
const_iterator apollo::perception::base::PointCloud< PointT >::end ( ) const
inline

在文件 point_cloud.h182 行定义.

182{ return points_.end(); }

◆ front() [1/2]

template<class PointT >
PointT & apollo::perception::base::PointCloud< PointT >::front ( )
inline

在文件 point_cloud.h102 行定义.

102{ return points_.front(); }

◆ front() [2/2]

template<class PointT >
const PointT & apollo::perception::base::PointCloud< PointT >::front ( ) const
inline

在文件 point_cloud.h101 行定义.

101{ return points_.front(); }

◆ get_timestamp()

template<class PointT >
double apollo::perception::base::PointCloud< PointT >::get_timestamp ( )
inline

在文件 point_cloud.h189 行定义.

◆ height()

template<class PointT >
size_t apollo::perception::base::PointCloud< PointT >::height ( ) const
inline

在文件 point_cloud.h78 行定义.

78{ return height_; }

◆ IsOrganized()

template<class PointT >
bool apollo::perception::base::PointCloud< PointT >::IsOrganized ( ) const
inline

在文件 point_cloud.h76 行定义.

76{ return height_ > 1; }

◆ mutable_points()

template<class PointT >
std::vector< PointT > * apollo::perception::base::PointCloud< PointT >::mutable_points ( )
inline

在文件 point_cloud.h183 行定义.

183{ return &points_; }

◆ operator()() [1/2]

template<class PointT >
PointT * apollo::perception::base::PointCloud< PointT >::operator() ( size_t  col,
size_t  row 
)
inline

在文件 point_cloud.h72 行定义.

72 {
73 return IsOrganized() ? &(points_[row * width_ + col]) : nullptr;
74 }

◆ operator()() [2/2]

template<class PointT >
const PointT * apollo::perception::base::PointCloud< PointT >::operator() ( size_t  col,
size_t  row 
) const
inline

在文件 point_cloud.h69 行定义.

69 {
70 return IsOrganized() ? &(points_[row * width_ + col]) : nullptr;
71 }

◆ operator[]() [1/2]

template<class PointT >
PointT & apollo::perception::base::PointCloud< PointT >::operator[] ( size_t  n)
inline

在文件 point_cloud.h97 行定义.

97{ return points_[n]; }

◆ operator[]() [2/2]

template<class PointT >
const PointT & apollo::perception::base::PointCloud< PointT >::operator[] ( size_t  n) const
inline

在文件 point_cloud.h96 行定义.

96{ return points_[n]; }

◆ points()

template<class PointT >
const std::vector< PointT > & apollo::perception::base::PointCloud< PointT >::points ( ) const
inline

在文件 point_cloud.h184 行定义.

184{ return points_; }

◆ push_back()

template<class PointT >
virtual void apollo::perception::base::PointCloud< PointT >::push_back ( const PointT &  point)
inlinevirtual

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

在文件 point_cloud.h107 行定义.

107 {
108 points_.push_back(point);
109 width_ = points_.size();
110 height_ = 1;
111 }

◆ reserve()

◆ resize()

template<class PointT >
virtual void apollo::perception::base::PointCloud< PointT >::resize ( size_t  size)
inlinevirtual

◆ RotatePointCloud()

template<class PointT >
void apollo::perception::base::PointCloud< PointT >::RotatePointCloud ( bool  check_nan = false)
inline

在文件 point_cloud.h199 行定义.

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

◆ sensor_to_world_pose()

template<class PointT >
const Eigen::Affine3d & apollo::perception::base::PointCloud< PointT >::sensor_to_world_pose ( )
inline

在文件 point_cloud.h195 行定义.

195 {
197 }

◆ set_sensor_to_world_pose()

template<class PointT >
void apollo::perception::base::PointCloud< PointT >::set_sensor_to_world_pose ( const Eigen::Affine3d &  sensor_to_world_pose)
inline

在文件 point_cloud.h191 行定义.

191 {
193 }
const Eigen::Affine3d & sensor_to_world_pose()

◆ set_timestamp()

template<class PointT >
void apollo::perception::base::PointCloud< PointT >::set_timestamp ( const double  timestamp)
inline

在文件 point_cloud.h187 行定义.

◆ size()

template<class PointT >
size_t apollo::perception::base::PointCloud< PointT >::size ( ) const
inline

在文件 point_cloud.h82 行定义.

82{ return points_.size(); }

◆ SwapPoint()

template<class PointT >
virtual bool apollo::perception::base::PointCloud< PointT >::SwapPoint ( size_t  source_id,
size_t  target_id 
)
inlinevirtual

apollo::perception::base::AttributePointCloud< PointT >, apollo::perception::base::AttributePointCloud< apollo::perception::base::Point > , 以及 apollo::perception::base::AttributePointCloud< PointD > 重载.

在文件 point_cloud.h118 行定义.

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

◆ SwapPointCloud()

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

在文件 point_cloud.h169 行定义.

169 {
170 points_.swap(rhs->points_);
171 std::swap(width_, rhs->width_);
172 std::swap(height_, rhs->height_);
173 std::swap(sensor_to_world_pose_, rhs->sensor_to_world_pose_);
174 std::swap(timestamp_, rhs->timestamp_);
175 }

◆ TransformPointCloud() [1/2]

template<class PointT >
void apollo::perception::base::PointCloud< PointT >::TransformPointCloud ( bool  check_nan = false)
inline

在文件 point_cloud.h215 行定义.

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

◆ TransformPointCloud() [2/2]

template<class PointT >
void apollo::perception::base::PointCloud< PointT >::TransformPointCloud ( const Eigen::Affine3f &  transform,
PointCloud< PointT > *  out,
bool  check_nan = false 
) const
inline

在文件 point_cloud.h231 行定义.

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

◆ width()

template<class PointT >
size_t apollo::perception::base::PointCloud< PointT >::width ( ) const
inline

在文件 point_cloud.h80 行定义.

80{ return width_; }

类成员变量说明

◆ height_

template<class PointT >
size_t apollo::perception::base::PointCloud< PointT >::height_ = 0
protected

在文件 point_cloud.h254 行定义.

◆ points_

template<class PointT >
std::vector<PointT> apollo::perception::base::PointCloud< PointT >::points_
protected

在文件 point_cloud.h252 行定义.

◆ sensor_to_world_pose_

template<class PointT >
Eigen::Affine3d apollo::perception::base::PointCloud< PointT >::sensor_to_world_pose_ = Eigen::Affine3d::Identity()
protected

在文件 point_cloud.h256 行定义.

◆ timestamp_

template<class PointT >
double apollo::perception::base::PointCloud< PointT >::timestamp_ = 0.0
protected

在文件 point_cloud.h257 行定义.

◆ width_

template<class PointT >
size_t apollo::perception::base::PointCloud< PointT >::width_ = 0
protected

在文件 point_cloud.h253 行定义.


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