#include <ray_ground_filter.h>
|
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 ¶m) |
|
Definition at line 38 of file ray_ground_filter.h.
◆ PointCloudRH
◆ RayGroundFilter()
RayGroundFilter::RayGroundFilter |
( |
| ) |
|
◆ 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_clouds | Vector of an Ordered PointsCloud ordered by radial distance from the origin |
in_point_count | Total number of lidar point. This is used to reserve the output's vector memory |
out_ground_indices | Returns the indices of the points classified as ground in the original PointCloud |
out_no_ground_indices | Returns 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_clouds | Vector of an Ordered PointsCloud ordered by radial distance from the origin |
in_point_count | Total number of lidar point. This is used to reserve the output's vector memory |
out_ground_ptrs | Returns the original adress of the points classified as ground in the original PointCloud |
out_no_ground_ptrs | Returns 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 |
◆ 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_cloud | Input Point Cloud to be organized in radial segments |
in_clip_height | Maximum allowed height in the cloud |
in_min_distance | Minimum valid distance, points closer than this will be removed. |
out_radial_ordered_clouds | Vector of Points Clouds, each element will contain the points ordered |
out_no_ground_ptrs | Returns 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_cloud | The original cloud from which we want to copy the points |
in_selector | The pointers to the input cloud's binary blob. No checks are done so be carefull |
out_filtered_msg | Returns 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
-
pub | The ROS publisher on which to output the point cloud |
in_sensor_cloud | The input point cloud from which to select the points to publish |
in_selector | The 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 |
( |
| ) |
|
◆ 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_frame | Coordinate system to perform transform |
in_cloud_ptr | PointCloud to perform transform |
out_cloud_ptr | Resulting transformed PointCloud |
- Return values
-
true | transform successed |
false | transform 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 |
◆ RayGroundFilter_callback_Test
friend class RayGroundFilter_callback_Test |
|
friend |
◆ base_frame_
std::string RayGroundFilter::base_frame_ |
|
private |
◆ clipping_height_
double RayGroundFilter::clipping_height_ |
|
private |
◆ concentric_divider_distance_
double RayGroundFilter::concentric_divider_distance_ |
|
private |
◆ concentric_dividers_num_
size_t RayGroundFilter::concentric_dividers_num_ |
|
private |
◆ config_node_sub_
◆ general_max_slope_
double RayGroundFilter::general_max_slope_ |
|
private |
◆ ground_points_pub_
◆ groundless_points_pub_
◆ input_point_topic_
std::string RayGroundFilter::input_point_topic_ |
|
private |
◆ local_max_slope_
double RayGroundFilter::local_max_slope_ |
|
private |
◆ min_height_threshold_
double RayGroundFilter::min_height_threshold_ |
|
private |
◆ min_point_distance_
double RayGroundFilter::min_point_distance_ |
|
private |
◆ node_handle_
◆ points_node_sub_
◆ radial_divider_angle_
double RayGroundFilter::radial_divider_angle_ |
|
private |
◆ radial_dividers_num_
size_t RayGroundFilter::radial_dividers_num_ |
|
private |
◆ reclass_distance_threshold_
double RayGroundFilter::reclass_distance_threshold_ |
|
private |
◆ tf_buffer_
◆ tf_listener_
The documentation for this class was generated from the following files: