Apollo  6.0
Open source self driving car software
Public Types | Public Member Functions | Protected Attributes | List of all members
apollo::perception::base::PointCloud< PointT > Class Template Reference

#include <point_cloud.h>

Inheritance diagram for apollo::perception::base::PointCloud< PointT >:
Inheritance graph
Collaboration diagram for apollo::perception::base::PointCloud< PointT >:
Collaboration graph

Public Types

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

Public Member Functions

 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 Attributes

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
 

Member Typedef Documentation

◆ const_iterator

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

◆ iterator

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

◆ PointType

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

Constructor & Destructor Documentation

◆ 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

◆ PointCloud() [3/4]

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

◆ 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

Member Function Documentation

◆ at() [1/4]

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

◆ at() [2/4]

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

◆ at() [3/4]

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

◆ at() [4/4]

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

◆ back() [1/2]

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

◆ back() [2/2]

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

◆ begin() [1/2]

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

◆ begin() [2/2]

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

◆ CheckConsistency()

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

◆ clear()

template<class PointT>
virtual void apollo::perception::base::PointCloud< PointT >::clear ( void  )
inlinevirtual

◆ CopyPoint()

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

◆ CopyPointCloud() [1/2]

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

◆ 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

◆ CopyPointCloudExclude()

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

◆ empty()

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

◆ end() [1/2]

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

◆ end() [2/2]

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

◆ front() [1/2]

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

◆ front() [2/2]

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

◆ get_timestamp()

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

◆ height()

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

◆ IsOrganized()

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

◆ mutable_points()

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

◆ operator()() [1/2]

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

◆ operator()() [2/2]

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

◆ operator[]() [1/2]

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

◆ operator[]() [2/2]

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

◆ points()

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

◆ push_back()

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

◆ reserve()

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

◆ 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

◆ sensor_to_world_pose()

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

◆ 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

◆ set_timestamp()

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

◆ size()

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

◆ SwapPoint()

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

◆ SwapPointCloud()

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

◆ TransformPointCloud() [1/2]

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

◆ 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

◆ width()

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

Member Data Documentation

◆ height_

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

◆ points_

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

◆ sensor_to_world_pose_

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

◆ timestamp_

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

◆ width_

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

The documentation for this class was generated from the following file: