35template <
class Po
intT>
38 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
63 inline const PointT*
at(
size_t col,
size_t row)
const {
66 inline PointT*
at(
size_t col,
size_t row) {
69 inline const PointT*
operator()(
size_t col,
size_t row)
const {
98 inline const PointT&
at(
size_t n)
const {
return points_[n]; }
118 inline virtual bool SwapPoint(
size_t source_id,
size_t target_id) {
141 template <
typename IndexType>
143 const std::vector<IndexType>& indices) {
146 points_.resize(indices.size());
147 for (
size_t i = 0; i < indices.size(); ++i) {
151 template <
typename IndexType>
153 const std::vector<IndexType>& indices) {
157 std::vector<bool> mask(
false, rhs.
size());
158 for (
size_t i = 0; i < indices.size(); ++i) {
159 mask[indices[i]] =
true;
161 for (
size_t i = 0; i < rhs.
size(); ++i) {
176 typedef typename std::vector<PointT>::iterator
iterator;
200 Eigen::Vector3d point3d;
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));
216 Eigen::Vector3d point3d;
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;
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));
233 bool check_nan =
false)
const {
234 Eigen::Vector3f point3f;
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));
262template <
class Po
intT>
280 const std::vector<int>& indices) {
285 const PointT point = PointT()) {
289 AFATAL <<
"overflow detected.";
355 inline void push_back(
const PointT& point,
double timestamp,
356 float height = std::numeric_limits<float>::max(),
357 int32_t beam_id = -1, uint8_t label = 0,
358 uint8_t semantic_label = 0) {
380 const size_t target_id)
override {
396 inline bool CopyPoint(
const size_t id,
const size_t rhs_id,
414 template <
typename IndexType>
416 const std::vector<IndexType>& indices) {
419 points_.resize(indices.size());
425 for (
size_t i = 0; i < indices.size(); ++i) {
458 return row *
width_ + col;
const std::vector< double > & points_timestamp() const
const int32_t & points_beam_id(size_t i) const
AttributePointCloud(const size_t width, const size_t height, const PointT point=PointT())
uint8_t & points_label(size_t i)
const std::vector< float > & points_height() const
uint8_t & points_semantic_label(size_t i)
AttributePointCloud & operator+=(const AttributePointCloud< PointT > &rhs)
std::vector< float > * mutable_points_height()
AttributePointCloud(const AttributePointCloud< PointT > &pc, const PointIndices &indices)
void CopyPointCloud(const AttributePointCloud< PointT > &rhs, const PointIndices &indices)
void resize(const size_t size) override
const uint8_t & points_semantic_label(size_t i) const
void reserve(const size_t size) override
AttributePointCloud(const AttributePointCloud< PointT > &pc, const std::vector< int > &indices)
int32_t & points_beam_id(size_t i)
std::vector< uint8_t > points_label_
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)
std::vector< float > points_height_
const std::vector< int32_t > & points_beam_id() const
std::vector< int32_t > * mutable_points_beam_id()
void SwapPointCloud(AttributePointCloud< PointT > *rhs)
bool CheckConsistency() const override
void SetPointHeight(size_t i, float height)
std::vector< uint8_t > * mutable_points_label()
double points_timestamp(size_t i) const
std::vector< uint8_t > * mutable_points_semantic_label()
void CopyPointCloud(const AttributePointCloud< PointT > &rhs, const std::vector< IndexType > &indices)
const std::vector< uint8_t > & points_label() const
bool SwapPoint(const size_t source_id, const size_t target_id) override
std::vector< double > points_timestamp_
size_t TransferToIndex(const size_t col, const size_t row) const
const float & points_height(size_t i) const
float & points_height(size_t i)
std::vector< uint8_t > points_semantic_label_
const uint8_t & points_label(size_t i) const
virtual ~AttributePointCloud()=default
std::vector< double > * mutable_points_timestamp()
void push_back(const PointT &point) override
bool CopyPoint(const size_t id, const size_t rhs_id, const AttributePointCloud< PointT > &rhs)
void SetPointHeight(size_t i, size_t j, float height)
const std::vector< uint8_t > & points_semantic_label() const
std::vector< int32_t > points_beam_id_
AttributePointCloud()=default
bool CopyPoint(size_t id, size_t rhs_id, const PointCloud< PointT > &rhs)
const PointT * at(size_t col, size_t row) const
PointCloud(const PointCloud< PointT > &pc, const PointIndices &indices)
virtual void resize(size_t size)
virtual ~PointCloud()=default
const PointT & front() const
std::vector< PointT > * mutable_points()
void SwapPointCloud(PointCloud< PointT > *rhs)
virtual bool SwapPoint(size_t source_id, size_t target_id)
PointT * operator()(size_t col, size_t row)
void CopyPointCloud(const PointCloud< PointT > &rhs, const PointIndices &indices)
const Eigen::Affine3d & sensor_to_world_pose()
void TransformPointCloud(const Eigen::Affine3f &transform, PointCloud< PointT > *out, bool check_nan=false) const
const_iterator end() const
virtual void push_back(const PointT &point)
PointT * at(size_t col, size_t row)
Eigen::Affine3d sensor_to_world_pose_
const PointT * operator()(size_t col, size_t row) const
const PointT & operator[](size_t n) const
std::vector< PointT >::const_iterator const_iterator
PointT & operator[](size_t n)
std::vector< PointT >::iterator iterator
PointCloud(const PointCloud< PointT > &pc, const std::vector< int > &indices)
void set_timestamp(const double timestamp)
std::vector< PointT > points_
virtual void reserve(size_t size)
virtual bool CheckConsistency() const
void set_sensor_to_world_pose(const Eigen::Affine3d &sensor_to_world_pose)
void CopyPointCloud(const PointCloud< PointT > &rhs, const std::vector< IndexType > &indices)
const std::vector< PointT > & points() const
void CopyPointCloudExclude(const PointCloud< PointT > &rhs, const std::vector< IndexType > &indices)
PointCloud(size_t width, size_t height, PointT point=PointT())
const_iterator begin() const
const PointT & back() const
const PointT & at(size_t n) const
void TransformPointCloud(bool check_nan=false)
void RotatePointCloud(bool check_nan=false)
std::shared_ptr< const PolygonFType > PolygonFTypeConstPtr
AttributePointCloud< PointF > PointFCloud
std::shared_ptr< PointDCloud > PointDCloudPtr
AttributePointCloud< PointD > PointDCloud
std::shared_ptr< const PolygonDType > PolygonDTypeConstPtr
std::shared_ptr< PolygonFType > PolygonFTypePtr
std::shared_ptr< PointFCloud > PointFCloudPtr
PointCloud< PointF > PolygonFType
std::shared_ptr< PointIndices > PointIndicesPtr
PointCloud< PointD > PolygonDType
std::shared_ptr< const PointDCloud > PointDCloudConstPtr
std::shared_ptr< PolygonDType > PolygonDTypePtr
std::shared_ptr< const PointIndices > PointIndicesConstPtr
std::shared_ptr< const PointFCloud > PointFCloudConstPtr
std::vector< int > indices