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_ |
Definition at line 23 of file ring_ground_filter.cpp.
GroundFilter::GroundFilter | ( | ) |
Definition at line 69 of file ring_ground_filter.cpp.
|
private |
Definition at line 198 of file ring_ground_filter.cpp.
|
private |
Definition at line 192 of file ring_ground_filter.cpp.
|
private |
Definition at line 118 of file ring_ground_filter.cpp.
|
private |
Definition at line 126 of file ring_ground_filter.cpp.
|
private |
Definition at line 317 of file ring_ground_filter.cpp.
|
private |
Definition at line 47 of file ring_ground_filter.cpp.
|
private |
Definition at line 57 of file ring_ground_filter.cpp.
|
private |
Definition at line 55 of file ring_ground_filter.cpp.
|
private |
Definition at line 42 of file ring_ground_filter.cpp.
|
private |
Definition at line 34 of file ring_ground_filter.cpp.
|
private |
Definition at line 37 of file ring_ground_filter.cpp.
|
private |
Definition at line 33 of file ring_ground_filter.cpp.
|
private |
Definition at line 45 of file ring_ground_filter.cpp.
|
private |
Definition at line 46 of file ring_ground_filter.cpp.
|
private |
Definition at line 40 of file ring_ground_filter.cpp.
|
private |
Definition at line 37 of file ring_ground_filter.cpp.
|
private |
Definition at line 31 of file ring_ground_filter.cpp.
|
private |
Definition at line 36 of file ring_ground_filter.cpp.
|
private |
Definition at line 32 of file ring_ground_filter.cpp.
|
private |
Definition at line 48 of file ring_ground_filter.cpp.
|
private |
Definition at line 39 of file ring_ground_filter.cpp.
|
private |
Definition at line 38 of file ring_ground_filter.cpp.
|
private |
Definition at line 53 of file ring_ground_filter.cpp.
|
private |
Definition at line 54 of file ring_ground_filter.cpp.
|
private |
Definition at line 44 of file ring_ground_filter.cpp.
|
private |
Definition at line 41 of file ring_ground_filter.cpp.