Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes | Friends | List of all members
RayGroundFilter Class Reference

#include <ray_ground_filter.h>

Classes

struct  PointRH
 

Public Member Functions

 RayGroundFilter ()
 
void Run ()
 

Private Types

typedef std::vector< PointRHPointCloudRH
 

Private Member Functions

void ClassifyPointCloud (const std::vector< PointCloudRH > &in_radial_ordered_clouds, const size_t in_point_count, std::vector< void *> *out_ground_ptrs, std::vector< void *> *out_no_ground_ptrs)
 
void CloudCallback (const sensor_msgs::PointCloud2ConstPtr &in_sensor_cloud)
 
void ConvertAndTrim (const sensor_msgs::PointCloud2::Ptr in_transformed_cloud, const double in_clip_height, double in_min_distance, std::vector< PointCloudRH > *out_radial_ordered_clouds, std::vector< void *> *out_no_ground_ptrs)
 
void filterROSMsg (const sensor_msgs::PointCloud2ConstPtr in_origin_cloud, const std::vector< void *> &in_selector, const sensor_msgs::PointCloud2::Ptr out_filtered_msg)
 
void publish (ros::Publisher pub, const sensor_msgs::PointCloud2ConstPtr in_sensor_cloud, const std::vector< void *> &in_selector)
 
bool TransformPointCloud (const std::string &in_target_frame, const sensor_msgs::PointCloud2::ConstPtr &in_cloud_ptr, const sensor_msgs::PointCloud2::Ptr &out_cloud_ptr)
 
void update_config_params (const autoware_config_msgs::ConfigRayGroundFilter::ConstPtr &param)
 

Private Attributes

std::string base_frame_
 
double clipping_height_
 
double concentric_divider_distance_
 
size_t concentric_dividers_num_
 
ros::Subscriber config_node_sub_
 
double general_max_slope_
 
ros::Publisher ground_points_pub_
 
ros::Publisher groundless_points_pub_
 
std::string input_point_topic_
 
double local_max_slope_
 
double min_height_threshold_
 
double min_point_distance_
 
ros::NodeHandle node_handle_
 
ros::Subscriber points_node_sub_
 
double radial_divider_angle_
 
size_t radial_dividers_num_
 
double reclass_distance_threshold_
 
tf2_ros::Buffer tf_buffer_
 
tf2_ros::TransformListener tf_listener_
 

Friends

class RayGroundFilter_callback_Test
 

Detailed Description

Definition at line 38 of file ray_ground_filter.h.

Member Typedef Documentation

◆ PointCloudRH

typedef std::vector<PointRH> RayGroundFilter::PointCloudRH
private

Definition at line 76 of file ray_ground_filter.h.

Constructor & Destructor Documentation

◆ RayGroundFilter()

RayGroundFilter::RayGroundFilter ( )

Definition at line 418 of file ray_ground_filter.cpp.

Member Function Documentation

◆ ClassifyPointCloud()

void RayGroundFilter::ClassifyPointCloud ( const std::vector< PointCloudRH > &  in_radial_ordered_clouds,
const size_t  in_point_count,
std::vector< void *> *  out_ground_ptrs,
std::vector< void *> *  out_no_ground_ptrs 
)
private

Classifies Points in the PointCoud as Ground and Not Ground

Parameters
in_radial_ordered_cloudsVector of an Ordered PointsCloud ordered by radial distance from the origin
in_point_countTotal number of lidar point. This is used to reserve the output's vector memory
out_ground_indicesReturns the indices of the points classified as ground in the original PointCloud
out_no_ground_indicesReturns the indices of the points classified as not ground in the original PointCloud

Classifies Points in the PointCoud as Ground and Not Ground

Parameters
in_radial_ordered_cloudsVector of an Ordered PointsCloud ordered by radial distance from the origin
in_point_countTotal number of lidar point. This is used to reserve the output's vector memory
out_ground_ptrsReturns the original adress of the points classified as ground in the original PointCloud
out_no_ground_ptrsReturns the original adress of the points classified as not ground in the original PointCloud

Definition at line 151 of file ray_ground_filter.cpp.

◆ CloudCallback()

void RayGroundFilter::CloudCallback ( const sensor_msgs::PointCloud2ConstPtr &  in_sensor_cloud)
private

Definition at line 396 of file ray_ground_filter.cpp.

◆ ConvertAndTrim()

void RayGroundFilter::ConvertAndTrim ( const sensor_msgs::PointCloud2::Ptr  in_transformed_cloud,
const double  in_clip_height,
double  in_min_distance,
std::vector< PointCloudRH > *  out_radial_ordered_clouds,
std::vector< void *> *  out_no_ground_ptrs 
)
private

Convert the sensor_msgs::PointCloud2 into PointCloudRH and filter out the points too high or too close

Parameters
in_transformed_cloudInput Point Cloud to be organized in radial segments
in_clip_heightMaximum allowed height in the cloud
in_min_distanceMinimum valid distance, points closer than this will be removed.
out_radial_ordered_cloudsVector of Points Clouds, each element will contain the points ordered
out_no_ground_ptrsReturns the pointers to the points filtered out as no ground

Definition at line 266 of file ray_ground_filter.cpp.

◆ filterROSMsg()

void RayGroundFilter::filterROSMsg ( const sensor_msgs::PointCloud2ConstPtr  in_origin_cloud,
const std::vector< void *> &  in_selector,
const sensor_msgs::PointCloud2::Ptr  out_filtered_msg 
)
private

Extract the points pointed by in_selector from in_radial_ordered_clouds to copy them in out_no_ground_ptrs

Parameters
in_origin_cloudThe original cloud from which we want to copy the points
in_selectorThe pointers to the input cloud's binary blob. No checks are done so be carefull
out_filtered_msgReturns a cloud comprised of the selected points from the origin cloud

Definition at line 102 of file ray_ground_filter.cpp.

◆ publish()

void RayGroundFilter::publish ( ros::Publisher  pub,
const sensor_msgs::PointCloud2ConstPtr  in_sensor_cloud,
const std::vector< void *> &  in_selector 
)
private

Extract the points pointed by in_selector from in_radial_ordered_clouds to copy them in out_no_ground_ptrs

Parameters
pubThe ROS publisher on which to output the point cloud
in_sensor_cloudThe input point cloud from which to select the points to publish
in_selectorThe pointers to the input cloud's binary blob. No checks are done so be carefull

Definition at line 87 of file ray_ground_filter.cpp.

◆ Run()

void RayGroundFilter::Run ( )

Definition at line 425 of file ray_ground_filter.cpp.

◆ TransformPointCloud()

bool RayGroundFilter::TransformPointCloud ( const std::string &  in_target_frame,
const sensor_msgs::PointCloud2::ConstPtr &  in_cloud_ptr,
const sensor_msgs::PointCloud2::Ptr &  out_cloud_ptr 
)
private

Output transformed PointCloud from in_cloud_ptr->header.frame_id to in_target_frame

Parameters
in_target_frameCoordinate system to perform transform
in_cloud_ptrPointCloud to perform transform
out_cloud_ptrResulting transformed PointCloud
Return values
truetransform successed
falsetransform faild

Definition at line 53 of file ray_ground_filter.cpp.

◆ update_config_params()

void RayGroundFilter::update_config_params ( const autoware_config_msgs::ConfigRayGroundFilter::ConstPtr &  param)
private

Definition at line 32 of file ray_ground_filter.cpp.

Friends And Related Function Documentation

◆ RayGroundFilter_callback_Test

friend class RayGroundFilter_callback_Test
friend

Definition at line 139 of file ray_ground_filter.h.

Member Data Documentation

◆ base_frame_

std::string RayGroundFilter::base_frame_
private

Definition at line 51 of file ray_ground_filter.h.

◆ clipping_height_

double RayGroundFilter::clipping_height_
private

Definition at line 58 of file ray_ground_filter.h.

◆ concentric_divider_distance_

double RayGroundFilter::concentric_divider_distance_
private

Definition at line 56 of file ray_ground_filter.h.

◆ concentric_dividers_num_

size_t RayGroundFilter::concentric_dividers_num_
private

Definition at line 63 of file ray_ground_filter.h.

◆ config_node_sub_

ros::Subscriber RayGroundFilter::config_node_sub_
private

Definition at line 43 of file ray_ground_filter.h.

◆ general_max_slope_

double RayGroundFilter::general_max_slope_
private

Definition at line 53 of file ray_ground_filter.h.

◆ ground_points_pub_

ros::Publisher RayGroundFilter::ground_points_pub_
private

Definition at line 45 of file ray_ground_filter.h.

◆ groundless_points_pub_

ros::Publisher RayGroundFilter::groundless_points_pub_
private

Definition at line 44 of file ray_ground_filter.h.

◆ input_point_topic_

std::string RayGroundFilter::input_point_topic_
private

Definition at line 50 of file ray_ground_filter.h.

◆ local_max_slope_

double RayGroundFilter::local_max_slope_
private

Definition at line 54 of file ray_ground_filter.h.

◆ min_height_threshold_

double RayGroundFilter::min_height_threshold_
private

Definition at line 57 of file ray_ground_filter.h.

◆ min_point_distance_

double RayGroundFilter::min_point_distance_
private

Definition at line 59 of file ray_ground_filter.h.

◆ node_handle_

ros::NodeHandle RayGroundFilter::node_handle_
private

Definition at line 41 of file ray_ground_filter.h.

◆ points_node_sub_

ros::Subscriber RayGroundFilter::points_node_sub_
private

Definition at line 42 of file ray_ground_filter.h.

◆ radial_divider_angle_

double RayGroundFilter::radial_divider_angle_
private

Definition at line 55 of file ray_ground_filter.h.

◆ radial_dividers_num_

size_t RayGroundFilter::radial_dividers_num_
private

Definition at line 62 of file ray_ground_filter.h.

◆ reclass_distance_threshold_

double RayGroundFilter::reclass_distance_threshold_
private

Definition at line 60 of file ray_ground_filter.h.

◆ tf_buffer_

tf2_ros::Buffer RayGroundFilter::tf_buffer_
private

Definition at line 47 of file ray_ground_filter.h.

◆ tf_listener_

tf2_ros::TransformListener RayGroundFilter::tf_listener_
private

Definition at line 48 of file ray_ground_filter.h.


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


points_preprocessor
Author(s): n-patiphon , aohsato
autogenerated on Mon Feb 28 2022 22:12:01