24 #include "Eigen/Dense" 29 namespace perception {
32 template <
class Po
intT>
57 inline const PointT*
at(
size_t col,
size_t row)
const {
60 inline PointT*
at(
size_t col,
size_t row) {
63 inline const PointT*
operator()(
size_t col,
size_t row)
const {
92 inline const PointT&
at(
size_t n)
const {
return points_[n]; }
112 inline virtual bool SwapPoint(
size_t source_id,
size_t target_id) {
135 template <
typename IndexType>
137 const std::vector<IndexType>& indices) {
140 points_.resize(indices.size());
141 for (
size_t i = 0; i < indices.size(); ++i) {
145 template <
typename IndexType>
147 const std::vector<IndexType>& indices) {
151 std::vector<bool> mask(
false, rhs.
size());
152 for (
size_t i = 0; i < indices.size(); ++i) {
153 mask[indices[i]] =
true;
155 for (
size_t i = 0; i < rhs.
size(); ++i) {
170 typedef typename std::vector<PointT>::iterator
iterator;
194 Eigen::Vector3d point3d;
197 if (!check_nan || (!std::isnan(point.x) && !std::isnan(point.y) &&
198 !std::isnan(point.z))) {
199 point3d << point.x, point.y, point.z;
200 point3d = rotation * point3d;
201 point.x =
static_cast<typename PointT::Type
>(point3d(0));
202 point.y =
static_cast<typename PointT::Type
>(point3d(1));
203 point.z =
static_cast<typename PointT::Type
>(point3d(2));
210 Eigen::Vector3d point3d;
212 if (!check_nan || (!std::isnan(point.x) && !std::isnan(point.y) &&
213 !std::isnan(point.z))) {
214 point3d << point.x, point.y, point.z;
216 point.x =
static_cast<typename PointT::Type
>(point3d(0));
217 point.y =
static_cast<typename PointT::Type
>(point3d(1));
218 point.z =
static_cast<typename PointT::Type
>(point3d(2));
227 bool check_nan =
false)
const {
228 Eigen::Vector3f point3f;
231 if (!check_nan || (!std::isnan(point.x) && !std::isnan(point.y) &&
232 !std::isnan(point.z))) {
233 point3f << point.x, point.y, point.z;
234 point3f = transform * point3f;
235 pt.x =
static_cast<typename PointT::Type
>(point3f(0));
236 pt.y =
static_cast<typename PointT::Type
>(point3f(1));
237 pt.z =
static_cast<typename PointT::Type
>(point3f(2));
256 template <
class Po
intT>
274 const std::vector<int>& indices) {
279 const PointT point = PointT()) {
284 points_timestamp_.assign(size, 0.0);
285 points_height_.assign(size, std::numeric_limits<float>::max());
286 points_beam_id_.assign(size, -1);
287 points_label_.assign(size, 0);
295 points_timestamp_.insert(points_timestamp_.end(),
298 points_height_.insert(points_height_.end(), rhs.
points_height_.begin(),
300 points_beam_id_.insert(points_beam_id_.end(), rhs.
points_beam_id_.begin(),
302 points_label_.insert(points_label_.end(), rhs.
points_label_.begin(),
311 points_timestamp_.reserve(size);
312 points_height_.reserve(size);
313 points_beam_id_.reserve(size);
314 points_label_.reserve(size);
319 points_timestamp_.resize(size, 0.0);
320 points_height_.resize(size, std::numeric_limits<float>::max());
321 points_beam_id_.resize(size, -1);
322 points_label_.resize(size, 0);
331 points_timestamp_.push_back(0.0);
332 points_height_.push_back(std::numeric_limits<float>::max());
333 points_beam_id_.push_back(-1);
334 points_label_.push_back(0);
338 inline void push_back(
const PointT& point,
double timestamp,
339 float height = std::numeric_limits<float>::max(),
340 int32_t beam_id = -1, uint8_t label = 0) {
342 points_timestamp_.push_back(timestamp);
343 points_height_.push_back(height);
344 points_beam_id_.push_back(beam_id);
345 points_label_.push_back(label);
352 points_timestamp_.clear();
353 points_height_.clear();
354 points_beam_id_.clear();
355 points_label_.clear();
360 const size_t target_id)
override {
363 std::swap(points_timestamp_[source_id], points_timestamp_[target_id]);
364 std::swap(points_height_[source_id], points_height_[target_id]);
365 std::swap(points_beam_id_[source_id], points_beam_id_[target_id]);
366 std::swap(points_label_[source_id], points_label_[target_id]);
374 inline bool CopyPoint(
const size_t id,
const size_t rhs_id,
391 template <
typename IndexType>
393 const std::vector<IndexType>& indices) {
396 points_.resize(indices.size());
397 points_timestamp_.resize(indices.size());
398 points_height_.resize(indices.size());
399 points_beam_id_.resize(indices.size());
400 points_label_.resize(indices.size());
401 for (
size_t i = 0; i < indices.size(); ++i) {
424 return ((
points_.size() == points_timestamp_.size()) &&
425 (
points_.size() == points_height_.size()) &&
426 (
points_.size() == points_beam_id_.size()) &&
427 (
points_.size() == points_label_.size()));
431 return row *
width_ + col;
435 return points_timestamp_;
451 const std::vector<uint8_t>&
points_label()
const {
return points_label_; }
455 const uint8_t&
points_label(
size_t i)
const {
return points_label_[i]; }
void resize(const size_t size) override
Definition: point_cloud.h:317
AttributePointCloud & operator+=(const AttributePointCloud< PointT > &rhs)
Definition: point_cloud.h:292
const std::vector< PointT > & points() const
Definition: point_cloud.h:178
float & points_height(size_t i)
Definition: point_cloud.h:441
std::vector< uint8_t > points_label_
Definition: point_cloud.h:461
const std::vector< double > & points_timestamp() const
Definition: point_cloud.h:434
void push_back(const PointT &point, double timestamp, float height=std::numeric_limits< float >::max(), int32_t beam_id=-1, uint8_t label=0)
Definition: point_cloud.h:338
const PointT & back() const
Definition: point_cloud.h:98
bool empty() const
Definition: point_cloud.h:80
PointT & back()
Definition: point_cloud.h:99
double points_timestamp(size_t i) const
Definition: point_cloud.h:437
PointCloud< PointD > PolygonDType
Definition: point_cloud.h:480
std::shared_ptr< PolygonFType > PolygonFTypePtr
Definition: point_cloud.h:482
void SwapPointCloud(PointCloud< PointT > *rhs)
Definition: point_cloud.h:163
std::vector< int > indices
Definition: point.h:76
bool IsOrganized() const
Definition: point_cloud.h:70
std::vector< int32_t > * mutable_points_beam_id()
Definition: point_cloud.h:450
std::shared_ptr< PointIndices > PointIndicesPtr
Definition: point_cloud.h:465
PointCloud< PointF > PolygonFType
Definition: point_cloud.h:479
void clear() override
Definition: point_cloud.h:350
virtual void clear()
Definition: point_cloud.h:107
void CopyPointCloud(const AttributePointCloud< PointT > &rhs, const std::vector< IndexType > &indices)
Definition: point_cloud.h:392
virtual void push_back(const PointT &point)
Definition: point_cloud.h:101
const Eigen::Affine3d & sensor_to_world_pose()
Definition: point_cloud.h:189
AttributePointCloud(const AttributePointCloud< PointT > &pc, const std::vector< int > &indices)
Definition: point_cloud.h:273
AttributePointCloud(const size_t width, const size_t height, const PointT point=PointT())
Definition: point_cloud.h:278
void CopyPointCloud(const AttributePointCloud< PointT > &rhs, const PointIndices &indices)
Definition: point_cloud.h:387
bool CopyPoint(size_t id, size_t rhs_id, const PointCloud< PointT > &rhs)
Definition: point_cloud.h:122
AttributePointCloud< PointD > PointDCloud
Definition: point_cloud.h:470
const std::vector< int32_t > & points_beam_id() const
Definition: point_cloud.h:449
bool CopyPoint(const size_t id, const size_t rhs_id, const AttributePointCloud< PointT > &rhs)
Definition: point_cloud.h:374
size_t size() const
Definition: point_cloud.h:76
std::vector< float > * mutable_points_height()
Definition: point_cloud.h:447
std::vector< PointT > points_
Definition: point_cloud.h:246
iterator end()
Definition: point_cloud.h:174
Definition: point_cloud.h:33
void set_sensor_to_world_pose(const Eigen::Affine3d &sensor_to_world_pose)
Definition: point_cloud.h:185
virtual ~PointCloud()=default
std::vector< int32_t > points_beam_id_
Definition: point_cloud.h:460
void CopyPointCloud(const PointCloud< PointT > &rhs, const std::vector< IndexType > &indices)
Definition: point_cloud.h:136
void CopyPointCloudExclude(const PointCloud< PointT > &rhs, const std::vector< IndexType > &indices)
Definition: point_cloud.h:146
Definition: point_cloud.h:257
PointCloud(const PointCloud< PointT > &pc, const PointIndices &indices)
Definition: point_cloud.h:40
std::vector< uint8_t > * mutable_points_label()
Definition: point_cloud.h:452
void SetPointHeight(size_t i, size_t j, float height)
Definition: point_cloud.h:443
void TransformPointCloud(bool check_nan=false)
Definition: point_cloud.h:209
AttributePointCloud(const AttributePointCloud< PointT > &pc, const PointIndices &indices)
Definition: point_cloud.h:269
size_t height_
Definition: point_cloud.h:248
std::shared_ptr< const PointFCloud > PointFCloudConstPtr
Definition: point_cloud.h:473
PointT * operator()(size_t col, size_t row)
Definition: point_cloud.h:66
PointCloud(size_t width, size_t height, PointT point=PointT())
Definition: point_cloud.h:47
std::vector< PointT > * mutable_points()
Definition: point_cloud.h:177
uint8_t & points_label(size_t i)
Definition: point_cloud.h:454
const PointT & operator[](size_t n) const
Definition: point_cloud.h:90
PointCloud(const PointCloud< PointT > &pc, const std::vector< int > &indices)
Definition: point_cloud.h:43
PointT & front()
Definition: point_cloud.h:96
size_t TransferToIndex(const size_t col, const size_t row) const
Definition: point_cloud.h:430
void SetPointHeight(size_t i, float height)
Definition: point_cloud.h:446
size_t height() const
Definition: point_cloud.h:72
std::shared_ptr< const PointDCloud > PointDCloudConstPtr
Definition: point_cloud.h:476
bool CheckConsistency() const override
Definition: point_cloud.h:423
std::vector< double > * mutable_points_timestamp()
Definition: point_cloud.h:438
double timestamp_
Definition: point_cloud.h:251
void CopyPointCloud(const PointCloud< PointT > &rhs, const PointIndices &indices)
Definition: point_cloud.h:131
size_t width() const
Definition: point_cloud.h:74
PointT & at(size_t n)
Definition: point_cloud.h:93
virtual void resize(size_t size)
Definition: point_cloud.h:82
PointT & operator[](size_t n)
Definition: point_cloud.h:91
const_iterator end() const
Definition: point_cloud.h:176
bool SwapPoint(const size_t source_id, const size_t target_id) override
Definition: point_cloud.h:359
std::shared_ptr< const PointIndices > PointIndicesConstPtr
Definition: point_cloud.h:466
std::shared_ptr< PointFCloud > PointFCloudPtr
Definition: point_cloud.h:472
const uint8_t & points_label(size_t i) const
Definition: point_cloud.h:455
double get_timestamp()
Definition: point_cloud.h:183
Eigen::Affine3d sensor_to_world_pose_
Definition: point_cloud.h:250
std::vector< PointT >::iterator iterator
Definition: point_cloud.h:170
const PointT & at(size_t n) const
Definition: point_cloud.h:92
void RotatePointCloud(bool check_nan=false)
Definition: point_cloud.h:193
std::shared_ptr< const PolygonFType > PolygonFTypeConstPtr
Definition: point_cloud.h:483
const_iterator begin() const
Definition: point_cloud.h:175
const std::vector< uint8_t > & points_label() const
Definition: point_cloud.h:451
const float & points_height(size_t i) const
Definition: point_cloud.h:442
void reserve(const size_t size) override
Definition: point_cloud.h:309
void set_timestamp(const double timestamp)
Definition: point_cloud.h:181
const PointT & front() const
Definition: point_cloud.h:95
const PointT * operator()(size_t col, size_t row) const
Definition: point_cloud.h:63
size_t width_
Definition: point_cloud.h:247
iterator begin()
Definition: point_cloud.h:173
void SwapPointCloud(AttributePointCloud< PointT > *rhs)
Definition: point_cloud.h:411
virtual bool SwapPoint(size_t source_id, size_t target_id)
Definition: point_cloud.h:112
std::vector< float > points_height_
Definition: point_cloud.h:459
virtual void reserve(size_t size)
Definition: point_cloud.h:78
virtual bool CheckConsistency() const
Definition: point_cloud.h:243
std::vector< PointT >::const_iterator const_iterator
Definition: point_cloud.h:171
std::shared_ptr< PointDCloud > PointDCloudPtr
Definition: point_cloud.h:475
std::shared_ptr< PolygonDType > PolygonDTypePtr
Definition: point_cloud.h:485
void TransformPointCloud(const Eigen::Affine3f &transform, PointCloud< PointT > *out, bool check_nan=false) const
Definition: point_cloud.h:225
std::shared_ptr< const PolygonDType > PolygonDTypeConstPtr
Definition: point_cloud.h:486
void push_back(const PointT &point) override
Definition: point_cloud.h:329
std::vector< double > points_timestamp_
Definition: point_cloud.h:458
const PointT * at(size_t col, size_t row) const
Definition: point_cloud.h:57
const std::vector< float > & points_height() const
Definition: point_cloud.h:440
AttributePointCloud< PointF > PointFCloud
Definition: point_cloud.h:469
PointT * at(size_t col, size_t row)
Definition: point_cloud.h:60