Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(occupancy_grid_map_outlier_filter): add intensity field #6797

Merged
Show file tree
Hide file tree
Changes from 8 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -46,18 +46,16 @@ using geometry_msgs::msg::Pose;
using nav_msgs::msg::OccupancyGrid;
using sensor_msgs::msg::PointCloud2;
using std_msgs::msg::Header;
using PclPointCloud = pcl::PointCloud<pcl::PointXYZ>;

class RadiusSearch2dFilter
{
public:
explicit RadiusSearch2dFilter(rclcpp::Node & node);
void filter(
const PclPointCloud & input, const Pose & pose, PclPointCloud & output,
PclPointCloud & outlier);
const PointCloud2 & input, const Pose & pose, PointCloud2 & output, PointCloud2 & outlier);
void filter(
const PclPointCloud & high_conf_input, const PclPointCloud & low_conf_input, const Pose & pose,
PclPointCloud & output, PclPointCloud & outlier);
const PointCloud2 & high_conf_input, const PointCloud2 & low_conf_input, const Pose & pose,
PointCloud2 & output, PointCloud2 & outlier);

private:
float search_radius_;
Expand All @@ -79,22 +77,25 @@ class OccupancyGridMapOutlierFilterComponent : public rclcpp::Node
const PointCloud2::ConstSharedPtr & input_pointcloud);
void filterByOccupancyGridMap(
const OccupancyGrid & occupancy_grid_map, const PointCloud2 & pointcloud,
PclPointCloud & high_confidence, PclPointCloud & low_confidence, PclPointCloud & out_ogm);
PointCloud2 & high_confidence, PointCloud2 & low_confidence, PointCloud2 & out_ogm);
void splitPointCloudFrontBack(
const PointCloud2::ConstSharedPtr & input_pc, PointCloud2 & front_pc, PointCloud2 & behind_pc);
void initializerPointCloud2(const PointCloud2 & input, PointCloud2 & output);
void finalizePointCloud2(const PointCloud2 & input, PointCloud2 & output);
void concatPointCloud2(PointCloud2 & output, const PointCloud2 & input);

private:
class Debugger
{
public:
explicit Debugger(OccupancyGridMapOutlierFilterComponent & node);
void publishOutlier(const PclPointCloud & input, const Header & header);
void publishHighConfidence(const PclPointCloud & input, const Header & header);
void publishLowConfidence(const PclPointCloud & input, const Header & header);
void publishOutlier(const PointCloud2 & input, const Header & header);
void publishHighConfidence(const PointCloud2 & input, const Header & header);
void publishLowConfidence(const PointCloud2 & input, const Header & header);

private:
void transformToBaseLink(
const PclPointCloud & input, const Header & header, PointCloud2 & output);
const PointCloud2 & input, const Header & header, PointCloud2 & output);
rclcpp::Publisher<PointCloud2>::SharedPtr outlier_pointcloud_pub_;
rclcpp::Publisher<PointCloud2>::SharedPtr low_confidence_pointcloud_pub_;
rclcpp::Publisher<PointCloud2>::SharedPtr high_confidence_pointcloud_pub_;
Expand Down
Loading
Loading