Public Member Functions | Private Member Functions | Private Attributes | List of all members
GroundFilter Class Reference

Public Member Functions

 GroundFilter ()
 

Private Member Functions

void FilterGround (const pcl::PointCloud< velodyne_pcl::PointXYZIRT >::ConstPtr &in_cloud_msg, pcl::PointCloud< velodyne_pcl::PointXYZIRT > &out_groundless_points, pcl::PointCloud< velodyne_pcl::PointXYZIRT > &out_ground_points)
 
void InitDepthMap (int in_width)
 
void InitLabelArray (int in_model)
 
void InitRadiusTable (int in_model)
 
void VelodyneCallback (const pcl::PointCloud< velodyne_pcl::PointXYZIRT >::ConstPtr &in_cloud_msg)
 

Private Attributes

Label class_label_ [64]
 
const int DEFAULT_HOR_RES = 2000
 
ros::Duration elap_time_
 
bool floor_removal_
 
ros::Publisher ground_points_pub_
 
std::string ground_topic
 
ros::Publisher groundless_points_pub_
 
int horizontal_res_
 
cv::Mat index_map_
 
double max_slope_
 
std::string no_ground_topic
 
ros::NodeHandle node_handle_
 
std::string point_topic_
 
ros::Subscriber points_node_sub_
 
double radius_table_ [64]
 
double sensor_height_
 
int sensor_model_
 
ros::Time t1_
 
ros::Time t2_
 
int vertical_res_
 
double vertical_thres_
 

Detailed Description

Definition at line 23 of file ring_ground_filter.cpp.

Constructor & Destructor Documentation

◆ GroundFilter()

GroundFilter::GroundFilter ( )

Definition at line 69 of file ring_ground_filter.cpp.

Member Function Documentation

◆ FilterGround()

void GroundFilter::FilterGround ( const pcl::PointCloud< velodyne_pcl::PointXYZIRT >::ConstPtr &  in_cloud_msg,
pcl::PointCloud< velodyne_pcl::PointXYZIRT > &  out_groundless_points,
pcl::PointCloud< velodyne_pcl::PointXYZIRT > &  out_ground_points 
)
private

Definition at line 198 of file ring_ground_filter.cpp.

◆ InitDepthMap()

void GroundFilter::InitDepthMap ( int  in_width)
private

Definition at line 192 of file ring_ground_filter.cpp.

◆ InitLabelArray()

void GroundFilter::InitLabelArray ( int  in_model)
private

Definition at line 118 of file ring_ground_filter.cpp.

◆ InitRadiusTable()

void GroundFilter::InitRadiusTable ( int  in_model)
private

Definition at line 126 of file ring_ground_filter.cpp.

◆ VelodyneCallback()

void GroundFilter::VelodyneCallback ( const pcl::PointCloud< velodyne_pcl::PointXYZIRT >::ConstPtr &  in_cloud_msg)
private

Definition at line 317 of file ring_ground_filter.cpp.

Member Data Documentation

◆ class_label_

Label GroundFilter::class_label_[64]
private

Definition at line 47 of file ring_ground_filter.cpp.

◆ DEFAULT_HOR_RES

const int GroundFilter::DEFAULT_HOR_RES = 2000
private

Definition at line 57 of file ring_ground_filter.cpp.

◆ elap_time_

ros::Duration GroundFilter::elap_time_
private

Definition at line 55 of file ring_ground_filter.cpp.

◆ floor_removal_

bool GroundFilter::floor_removal_
private

Definition at line 42 of file ring_ground_filter.cpp.

◆ ground_points_pub_

ros::Publisher GroundFilter::ground_points_pub_
private

Definition at line 34 of file ring_ground_filter.cpp.

◆ ground_topic

std::string GroundFilter::ground_topic
private

Definition at line 37 of file ring_ground_filter.cpp.

◆ groundless_points_pub_

ros::Publisher GroundFilter::groundless_points_pub_
private

Definition at line 33 of file ring_ground_filter.cpp.

◆ horizontal_res_

int GroundFilter::horizontal_res_
private

Definition at line 45 of file ring_ground_filter.cpp.

◆ index_map_

cv::Mat GroundFilter::index_map_
private

Definition at line 46 of file ring_ground_filter.cpp.

◆ max_slope_

double GroundFilter::max_slope_
private

Definition at line 40 of file ring_ground_filter.cpp.

◆ no_ground_topic

std::string GroundFilter::no_ground_topic
private

Definition at line 37 of file ring_ground_filter.cpp.

◆ node_handle_

ros::NodeHandle GroundFilter::node_handle_
private

Definition at line 31 of file ring_ground_filter.cpp.

◆ point_topic_

std::string GroundFilter::point_topic_
private

Definition at line 36 of file ring_ground_filter.cpp.

◆ points_node_sub_

ros::Subscriber GroundFilter::points_node_sub_
private

Definition at line 32 of file ring_ground_filter.cpp.

◆ radius_table_

double GroundFilter::radius_table_[64]
private

Definition at line 48 of file ring_ground_filter.cpp.

◆ sensor_height_

double GroundFilter::sensor_height_
private

Definition at line 39 of file ring_ground_filter.cpp.

◆ sensor_model_

int GroundFilter::sensor_model_
private

Definition at line 38 of file ring_ground_filter.cpp.

◆ t1_

ros::Time GroundFilter::t1_
private

Definition at line 53 of file ring_ground_filter.cpp.

◆ t2_

ros::Time GroundFilter::t2_
private

Definition at line 54 of file ring_ground_filter.cpp.

◆ vertical_res_

int GroundFilter::vertical_res_
private

Definition at line 44 of file ring_ground_filter.cpp.

◆ vertical_thres_

double GroundFilter::vertical_thres_
private

Definition at line 41 of file ring_ground_filter.cpp.


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


points_preprocessor
Author(s): n-patiphon , aohsato
autogenerated on Wed Mar 2 2022 00:12:07