Public Member Functions | Public Attributes | List of all members
floam::lidar::Lidar< T > Class Template Reference

#include <lidar.hpp>

Public Member Functions

template<>
void detectEdges (const pcl::PointCloud< pcl::PointXYZ >::Ptr &points, pcl::PointCloud< pcl::PointXYZL >::Ptr &edges)
 Scanner type. More...
 
void detectEdges (const pcl::PointCloud< pcl::PointXYZ >::Ptr &points, pcl::PointCloud< pcl::PointXYZL >::Ptr &edges)
 
template<>
void detectEdges (const pcl::PointCloud< pcl::PointXYZ >::Ptr &points, pcl::PointCloud< pcl::PointXYZL >::Ptr &edges)
 overload detectEdges for Scanner type More...
 
template<>
void detectEdges (const pcl::PointCloud< pcl::PointXYZ >::Ptr &points, pcl::PointCloud< pcl::PointXYZL >::Ptr &edges)
 overload detectEdges for Imager type More...
 
template<>
void detectEdges (const pcl::PointCloud< pcl::PointXYZ >::Ptr &points, pcl::PointCloud< pcl::PointXYZL >::Ptr &edges)
 Imager type. More...
 
void detectSurfaces (const pcl::PointCloud< pcl::PointXYZ >::Ptr &points, pcl::PointCloud< pcl::PointNormal >::Ptr &normals)
 
template<>
void detectSurfaces (const pcl::PointCloud< pcl::PointXYZ >::Ptr &points, pcl::PointCloud< pcl::PointNormal >::Ptr &normals)
 overload detectSurfaces for Scanner type More...
 
template<>
void detectSurfaces (const pcl::PointCloud< pcl::PointXYZ >::Ptr &points, pcl::PointCloud< pcl::PointNormal >::Ptr &normals)
 overload detectSurfaces for Imager type More...
 
template<>
void detectSurfaces (const pcl::PointCloud< pcl::PointXYZ >::Ptr &points, pcl::PointCloud< pcl::PointNormal >::Ptr &normals)
 Scanner type. More...
 
template<>
void detectSurfaces (const pcl::PointCloud< pcl::PointXYZ >::Ptr &points, pcl::PointCloud< pcl::PointNormal >::Ptr &normals)
 overloaded for Imager type More...
 

Public Attributes

std::vector< int > m_addedPoints
 
Eigen::Matrix< std::complex< double >, 3, 3 > m_covariance
 covariance objects More...
 
Eigen::Matrix< std::complex< double >, 3, 1 > m_eigenValues
 
pcl::KdTreeFLANN< pcl::PointXYZ > m_kdTree
 kdTree More...
 
std::vector< pcl::PointCloud< pcl::PointXYZ >::Ptr > m_lidarScans
 lidarScans More...
 
m_settings
 Settings for specific Lidar type. More...
 
floam::lidar::Total m_total
 Total counters (i.e. frames and time) More...
 
std::vector< int > pointSearch
 
std::vector< float > pointSquaredDistance
 

Detailed Description

template<class T>
class floam::lidar::Lidar< T >

Definition at line 22 of file lidar.hpp.

Member Function Documentation

◆ detectEdges() [1/5]

template<>
void floam::lidar::Lidar< floam::lidar::Scanner >::detectEdges ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  points,
pcl::PointCloud< pcl::PointXYZL >::Ptr &  edges 
)

Scanner type.

clear addedPoints

clear lidar scans

TODO(flynneva): use downsampling technique instead of just skipping points? number of points to skip

calculate radial distance to point

number of neighbor points found - 1

divide matrix by number of points - 1

calculate surface variation

end function

(flynneva) why 131?

TODO(flynneva): separate out this bit to function?

input: points, sectorSize output: cloudCurvature

end of potential cloudCurvature func

loop over sectors

Definition at line 25 of file lidar.cpp.

◆ detectEdges() [2/5]

template<class T>
void floam::lidar::Lidar< T >::detectEdges ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  points,
pcl::PointCloud< pcl::PointXYZL >::Ptr &  edges 
)

Detects edges from input pointcloud

Parameters
pointsinput pointcloud
edgesoutput edges

◆ detectEdges() [3/5]

template<>
void floam::lidar::Lidar< floam::lidar::Scanner >::detectEdges ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  points,
pcl::PointCloud< pcl::PointXYZL >::Ptr &  edges 
)

overload detectEdges for Scanner type

◆ detectEdges() [4/5]

template<>
void floam::lidar::Lidar< floam::lidar::Imager >::detectEdges ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  points,
pcl::PointCloud< pcl::PointXYZL >::Ptr &  edges 
)

overload detectEdges for Imager type

◆ detectEdges() [5/5]

template<>
void floam::lidar::Lidar< floam::lidar::Imager >::detectEdges ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  points,
pcl::PointCloud< pcl::PointXYZL >::Ptr &  edges 
)

Imager type.

Definition at line 305 of file lidar.cpp.

◆ detectSurfaces() [1/5]

template<class T>
void floam::lidar::Lidar< T >::detectSurfaces ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  points,
pcl::PointCloud< pcl::PointNormal >::Ptr &  normals 
)

Detects surface normals from input pointcloud

Parameters
pointsinput pointcloud
edgesoutput edges

◆ detectSurfaces() [2/5]

template<>
void floam::lidar::Lidar< floam::lidar::Scanner >::detectSurfaces ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  points,
pcl::PointCloud< pcl::PointNormal >::Ptr &  normals 
)

overload detectSurfaces for Scanner type

◆ detectSurfaces() [3/5]

template<>
void floam::lidar::Lidar< floam::lidar::Imager >::detectSurfaces ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  points,
pcl::PointCloud< pcl::PointNormal >::Ptr &  normals 
)

overload detectSurfaces for Imager type

◆ detectSurfaces() [4/5]

template<>
void floam::lidar::Lidar< floam::lidar::Scanner >::detectSurfaces ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  points,
pcl::PointCloud< pcl::PointNormal >::Ptr &  normals 
)

Scanner type.

Definition at line 328 of file lidar.cpp.

◆ detectSurfaces() [5/5]

template<>
void floam::lidar::Lidar< floam::lidar::Imager >::detectSurfaces ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  points,
pcl::PointCloud< pcl::PointNormal >::Ptr &  normals 
)

overloaded for Imager type

Definition at line 352 of file lidar.cpp.

Member Data Documentation

◆ m_addedPoints

template<class T>
std::vector<int> floam::lidar::Lidar< T >::m_addedPoints

Definition at line 50 of file lidar.hpp.

◆ m_covariance

template<class T>
Eigen::Matrix<std::complex<double>, 3, 3> floam::lidar::Lidar< T >::m_covariance

covariance objects

Definition at line 58 of file lidar.hpp.

◆ m_eigenValues

template<class T>
Eigen::Matrix<std::complex<double>, 3, 1> floam::lidar::Lidar< T >::m_eigenValues

Definition at line 59 of file lidar.hpp.

◆ m_kdTree

template<class T>
pcl::KdTreeFLANN<pcl::PointXYZ> floam::lidar::Lidar< T >::m_kdTree

kdTree

Definition at line 53 of file lidar.hpp.

◆ m_lidarScans

template<class T>
std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> floam::lidar::Lidar< T >::m_lidarScans

lidarScans

Definition at line 49 of file lidar.hpp.

◆ m_settings

template<class T>
T floam::lidar::Lidar< T >::m_settings

Settings for specific Lidar type.

Definition at line 44 of file lidar.hpp.

◆ m_total

template<class T>
floam::lidar::Total floam::lidar::Lidar< T >::m_total

Total counters (i.e. frames and time)

Definition at line 46 of file lidar.hpp.

◆ pointSearch

template<class T>
std::vector<int> floam::lidar::Lidar< T >::pointSearch

Definition at line 54 of file lidar.hpp.

◆ pointSquaredDistance

template<class T>
std::vector<float> floam::lidar::Lidar< T >::pointSquaredDistance

Definition at line 55 of file lidar.hpp.


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


floam
Author(s): Han Wang
autogenerated on Mon Feb 28 2022 22:25:11