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

#include <radar_point_cloud.h>

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

Public 类型

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

Public 成员函数

 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
 
virtual void reserve (size_t size)
 
bool empty () const
 
virtual void resize (size_t size)
 
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 ()
 
virtual void push_back (const RadarPointT &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 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
 
virtual bool CheckConsistency () const
 

Protected 属性

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::RadarPointCloud< RadarPointT >

在文件 radar_point_cloud.h36 行定义.

成员类型定义说明

◆ const_iterator

template<class RadarPointT >
typedef std::vector<RadarPointT>::const_iterator apollo::perception::base::RadarPointCloud< RadarPointT >::const_iterator

在文件 radar_point_cloud.h183 行定义.

◆ iterator

template<class RadarPointT >
typedef std::vector<RadarPointT>::iterator apollo::perception::base::RadarPointCloud< RadarPointT >::iterator

在文件 radar_point_cloud.h182 行定义.

◆ PointType

template<class RadarPointT >
using apollo::perception::base::RadarPointCloud< RadarPointT >::PointType = RadarPointT

在文件 radar_point_cloud.h41 行定义.

构造及析构函数说明

◆ RadarPointCloud() [1/4]

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

◆ RadarPointCloud() [2/4]

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

在文件 radar_point_cloud.h46 行定义.

47 {
48 CopyRadarPointCloud(pc, indices);
49 }
void CopyRadarPointCloud(const RadarPointCloud< RadarPointT > &rhs, const PointIndices &indices)

◆ RadarPointCloud() [3/4]

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

在文件 radar_point_cloud.h50 行定义.

51 {
52 CopyRadarPointCloud(pc, indices);
53 }

◆ RadarPointCloud() [4/4]

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

◆ ~RadarPointCloud()

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

成员函数说明

◆ at() [1/4]

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

在文件 radar_point_cloud.h71 行定义.

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

◆ at() [2/4]

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

在文件 radar_point_cloud.h68 行定义.

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

◆ at() [3/4]

template<class RadarPointT >
RadarPointT & apollo::perception::base::RadarPointCloud< RadarPointT >::at ( size_t  n)
inline

在文件 radar_point_cloud.h104 行定义.

104{ return points_[n]; }

◆ at() [4/4]

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

在文件 radar_point_cloud.h103 行定义.

103{ return points_[n]; }

◆ back() [1/2]

template<class RadarPointT >
RadarPointT & apollo::perception::base::RadarPointCloud< RadarPointT >::back ( )
inline

在文件 radar_point_cloud.h110 行定义.

110{ return points_.back(); }

◆ back() [2/2]

template<class RadarPointT >
const RadarPointT & apollo::perception::base::RadarPointCloud< RadarPointT >::back ( ) const
inline

在文件 radar_point_cloud.h109 行定义.

109{ return points_.back(); }

◆ begin() [1/2]

template<class RadarPointT >
iterator apollo::perception::base::RadarPointCloud< RadarPointT >::begin ( )
inline

在文件 radar_point_cloud.h185 行定义.

185{ return points_.begin(); }

◆ begin() [2/2]

template<class RadarPointT >
const_iterator apollo::perception::base::RadarPointCloud< RadarPointT >::begin ( ) const
inline

在文件 radar_point_cloud.h187 行定义.

187{ return points_.begin(); }

◆ CheckConsistency()

template<class RadarPointT >
virtual bool apollo::perception::base::RadarPointCloud< RadarPointT >::CheckConsistency ( ) const
inlinevirtual

◆ clear()

template<class RadarPointT >
virtual void apollo::perception::base::RadarPointCloud< RadarPointT >::clear ( )
inlinevirtual

◆ CopyPoint()

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

在文件 radar_point_cloud.h133 行定义.

134 {
135 if (id < points_.size() && rhs_id < rhs.points_.size()) {
136 points_[id] = rhs.points_[rhs_id];
137 return true;
138 }
139 return false;
140 }

◆ CopyRadarPointCloud() [1/2]

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

在文件 radar_point_cloud.h142 行定义.

143 {
144 CopyRadarPointCloud(rhs, indices.indices);
145 }

◆ CopyRadarPointCloud() [2/2]

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

在文件 radar_point_cloud.h147 行定义.

148 {
149 width_ = indices.size();
150 height_ = 1;
151 points_.resize(indices.size());
152 for (size_t i = 0; i < indices.size(); ++i) {
153 points_[i] = rhs.points_[indices[i]];
154 }
155 }

◆ CopyRadarPointCloudExclude()

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

在文件 radar_point_cloud.h157 行定义.

159 {
160 width_ = indices.size();
161 height_ = 1;
162 points_.resize(rhs.size() - indices.size());
163 std::vector<bool> mask(false, rhs.size());
164 for (size_t i = 0; i < indices.size(); ++i) {
165 mask[indices[i]] = true;
166 }
167 for (size_t i = 0; i < rhs.size(); ++i) {
168 if (!mask[i]) {
169 points_.push_back(rhs.points_[i]);
170 }
171 }
172 }

◆ empty()

template<class RadarPointT >
bool apollo::perception::base::RadarPointCloud< RadarPointT >::empty ( ) const
inline

在文件 radar_point_cloud.h91 行定义.

91{ return points_.empty(); }

◆ end() [1/2]

template<class RadarPointT >
iterator apollo::perception::base::RadarPointCloud< RadarPointT >::end ( )
inline

在文件 radar_point_cloud.h186 行定义.

186{ return points_.end(); }

◆ end() [2/2]

template<class RadarPointT >
const_iterator apollo::perception::base::RadarPointCloud< RadarPointT >::end ( ) const
inline

在文件 radar_point_cloud.h188 行定义.

188{ return points_.end(); }

◆ front() [1/2]

template<class RadarPointT >
RadarPointT & apollo::perception::base::RadarPointCloud< RadarPointT >::front ( )
inline

在文件 radar_point_cloud.h107 行定义.

107{ return points_.front(); }

◆ front() [2/2]

template<class RadarPointT >
const RadarPointT & apollo::perception::base::RadarPointCloud< RadarPointT >::front ( ) const
inline

在文件 radar_point_cloud.h106 行定义.

106{ return points_.front(); }

◆ get_timestamp()

template<class RadarPointT >
double apollo::perception::base::RadarPointCloud< RadarPointT >::get_timestamp ( )
inline

在文件 radar_point_cloud.h195 行定义.

◆ height()

template<class RadarPointT >
size_t apollo::perception::base::RadarPointCloud< RadarPointT >::height ( ) const
inline

在文件 radar_point_cloud.h83 行定义.

83{ return height_; }

◆ IsOrganized()

template<class RadarPointT >
bool apollo::perception::base::RadarPointCloud< RadarPointT >::IsOrganized ( ) const
inline

在文件 radar_point_cloud.h81 行定义.

81{ return height_ > 1; }

◆ mutable_points()

template<class RadarPointT >
std::vector< RadarPointT > * apollo::perception::base::RadarPointCloud< RadarPointT >::mutable_points ( )
inline

在文件 radar_point_cloud.h189 行定义.

189{ return &points_; }

◆ operator()() [1/2]

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

在文件 radar_point_cloud.h77 行定义.

77 {
78 return IsOrganized() ? &(points_[row * width_ + col]) : nullptr;
79 }

◆ operator()() [2/2]

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

在文件 radar_point_cloud.h74 行定义.

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

◆ operator[]() [1/2]

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

在文件 radar_point_cloud.h102 行定义.

102{ return points_[n]; }

◆ operator[]() [2/2]

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

在文件 radar_point_cloud.h101 行定义.

101{ return points_[n]; }

◆ points()

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

在文件 radar_point_cloud.h190 行定义.

190{ return points_; }

◆ push_back()

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

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

在文件 radar_point_cloud.h112 行定义.

112 {
113 points_.push_back(point);
114 width_ = points_.size();
115 height_ = 1;
116 }

◆ reserve()

template<class RadarPointT >
virtual void apollo::perception::base::RadarPointCloud< RadarPointT >::reserve ( size_t  size)
inlinevirtual

◆ resize()

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

◆ RotateRadarPointCloud()

template<class RadarPointT >
void apollo::perception::base::RadarPointCloud< RadarPointT >::RotateRadarPointCloud ( bool  check_nan = false)
inline

在文件 radar_point_cloud.h205 行定义.

205 {
206 Eigen::Vector3d point3d;
207 Eigen::Matrix3d rotation = sensor_to_world_pose_.linear();
208 for (auto& point : points_) {
209 if (!check_nan || (!std::isnan(point.x) && !std::isnan(point.y) &&
210 !std::isnan(point.z))) {
211 point3d << point.x, point.y, point.z;
212 point3d = rotation * point3d;
213 point.x = static_cast<typename RadarPointT::Type>(point3d(0));
214 point.y = static_cast<typename RadarPointT::Type>(point3d(1));
215 point.z = static_cast<typename RadarPointT::Type>(point3d(2));
216 }
217 }
218 sensor_to_world_pose_.linear().setIdentity();
219 }

◆ sensor_to_world_pose()

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

在文件 radar_point_cloud.h201 行定义.

201 {
203 }

◆ set_sensor_to_world_pose()

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

在文件 radar_point_cloud.h197 行定义.

◆ set_timestamp()

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

在文件 radar_point_cloud.h193 行定义.

◆ size()

template<class RadarPointT >
size_t apollo::perception::base::RadarPointCloud< RadarPointT >::size ( ) const
inline

在文件 radar_point_cloud.h87 行定义.

87{ return points_.size(); }

◆ SwapPoint()

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

apollo::perception::base::AttributeRadarPointCloud< RadarPointT > , 以及 apollo::perception::base::AttributeRadarPointCloud< apollo::perception::base::RadarPoint > 重载.

在文件 radar_point_cloud.h123 行定义.

123 {
124 if (source_id < points_.size() && target_id < points_.size()) {
125 std::swap(points_[source_id], points_[target_id]);
126 width_ = points_.size();
127 height_ = 1;
128 return true;
129 }
130 return false;
131 }

◆ SwapRadarPointCloud()

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

在文件 radar_point_cloud.h175 行定义.

175 {
176 points_.swap(rhs->points_);
177 std::swap(width_, rhs->width_);
178 std::swap(height_, rhs->height_);
179 std::swap(sensor_to_world_pose_, rhs->sensor_to_world_pose_);
180 std::swap(timestamp_, rhs->timestamp_);
181 }

◆ TransformRadarPointCloud() [1/2]

template<class RadarPointT >
void apollo::perception::base::RadarPointCloud< RadarPointT >::TransformRadarPointCloud ( bool  check_nan = false)
inline

在文件 radar_point_cloud.h221 行定义.

221 {
222 Eigen::Vector3d point3d;
223 for (auto& point : points_) {
224 if (!check_nan || (!std::isnan(point.x) && !std::isnan(point.y) &&
225 !std::isnan(point.z))) {
226 point3d << point.x, point.y, point.z;
227 point3d = sensor_to_world_pose_ * point3d;
228 point.x = static_cast<typename RadarPointT::Type>(point3d(0));
229 point.y = static_cast<typename RadarPointT::Type>(point3d(1));
230 point.z = static_cast<typename RadarPointT::Type>(point3d(2));
231 }
232 }
233 sensor_to_world_pose_.setIdentity();
234 }

◆ TransformRadarPointCloud() [2/2]

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

在文件 radar_point_cloud.h237 行定义.

239 {
240 Eigen::Vector3f point3f;
241 RadarPointT pt;
242 for (auto& point : points_) {
243 if (!check_nan || (!std::isnan(point.x) && !std::isnan(point.y) &&
244 !std::isnan(point.z))) {
245 point3f << point.x, point.y, point.z;
246 point3f = transform * point3f;
247 pt.x = static_cast<typename RadarPointT::Type>(point3f(0));
248 pt.y = static_cast<typename RadarPointT::Type>(point3f(1));
249 pt.z = static_cast<typename RadarPointT::Type>(point3f(2));
250 out->push_back(pt);
251 }
252 }
253 }

◆ width()

template<class RadarPointT >
size_t apollo::perception::base::RadarPointCloud< RadarPointT >::width ( ) const
inline

在文件 radar_point_cloud.h85 行定义.

85{ return width_; }

类成员变量说明

◆ height_

template<class RadarPointT >
size_t apollo::perception::base::RadarPointCloud< RadarPointT >::height_ = 0
protected

在文件 radar_point_cloud.h260 行定义.

◆ points_

template<class RadarPointT >
std::vector<RadarPointT> apollo::perception::base::RadarPointCloud< RadarPointT >::points_
protected

在文件 radar_point_cloud.h258 行定义.

◆ sensor_to_world_pose_

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

在文件 radar_point_cloud.h262 行定义.

◆ timestamp_

template<class RadarPointT >
double apollo::perception::base::RadarPointCloud< RadarPointT >::timestamp_ = 0.0
protected

在文件 radar_point_cloud.h263 行定义.

◆ width_

template<class RadarPointT >
size_t apollo::perception::base::RadarPointCloud< RadarPointT >::width_ = 0
protected

在文件 radar_point_cloud.h259 行定义.


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