Skip to content

Commit 308b11c

Browse files
committed
fix(occupancy_grid_map_outlier_filter): add intensity field (autowarefoundation#6797)
* fix(occupancy_grid_map_outlier_filter): add intensity field Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: add intensity Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: using empty padding field Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * refactor Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * Revert "refactor" This reverts commit d16b3e0. * refactor Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: radius filter Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * chore: typo Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: typo Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> --------- Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
1 parent 0c5abdd commit 308b11c

File tree

2 files changed

+175
-95
lines changed

2 files changed

+175
-95
lines changed

perception/occupancy_grid_map_outlier_filter/include/occupancy_grid_map_outlier_filter/occupancy_grid_map_outlier_filter_nodelet.hpp

+11-10
Original file line numberDiff line numberDiff line change
@@ -45,18 +45,16 @@ using geometry_msgs::msg::Pose;
4545
using nav_msgs::msg::OccupancyGrid;
4646
using sensor_msgs::msg::PointCloud2;
4747
using std_msgs::msg::Header;
48-
using PclPointCloud = pcl::PointCloud<pcl::PointXYZ>;
4948

5049
class RadiusSearch2dFilter
5150
{
5251
public:
5352
explicit RadiusSearch2dFilter(rclcpp::Node & node);
5453
void filter(
55-
const PclPointCloud & input, const Pose & pose, PclPointCloud & output,
56-
PclPointCloud & outlier);
54+
const PointCloud2 & input, const Pose & pose, PointCloud2 & output, PointCloud2 & outlier);
5755
void filter(
58-
const PclPointCloud & high_conf_input, const PclPointCloud & low_conf_input, const Pose & pose,
59-
PclPointCloud & output, PclPointCloud & outlier);
56+
const PointCloud2 & high_conf_input, const PointCloud2 & low_conf_input, const Pose & pose,
57+
PointCloud2 & output, PointCloud2 & outlier);
6058

6159
private:
6260
float search_radius_;
@@ -78,22 +76,25 @@ class OccupancyGridMapOutlierFilterComponent : public rclcpp::Node
7876
const PointCloud2::ConstSharedPtr & input_pointcloud);
7977
void filterByOccupancyGridMap(
8078
const OccupancyGrid & occupancy_grid_map, const PointCloud2 & pointcloud,
81-
PclPointCloud & high_confidence, PclPointCloud & low_confidence, PclPointCloud & out_ogm);
79+
PointCloud2 & high_confidence, PointCloud2 & low_confidence, PointCloud2 & out_ogm);
8280
void splitPointCloudFrontBack(
8381
const PointCloud2::ConstSharedPtr & input_pc, PointCloud2 & front_pc, PointCloud2 & behind_pc);
82+
void initializerPointCloud2(const PointCloud2 & input, PointCloud2 & output);
83+
void finalizePointCloud2(const PointCloud2 & input, PointCloud2 & output);
84+
void concatPointCloud2(PointCloud2 & output, const PointCloud2 & input);
8485

8586
private:
8687
class Debugger
8788
{
8889
public:
8990
explicit Debugger(OccupancyGridMapOutlierFilterComponent & node);
90-
void publishOutlier(const PclPointCloud & input, const Header & header);
91-
void publishHighConfidence(const PclPointCloud & input, const Header & header);
92-
void publishLowConfidence(const PclPointCloud & input, const Header & header);
91+
void publishOutlier(const PointCloud2 & input, const Header & header);
92+
void publishHighConfidence(const PointCloud2 & input, const Header & header);
93+
void publishLowConfidence(const PointCloud2 & input, const Header & header);
9394

9495
private:
9596
void transformToBaseLink(
96-
const PclPointCloud & input, const Header & header, PointCloud2 & output);
97+
const PointCloud2 & input, const Header & header, PointCloud2 & output);
9798
rclcpp::Publisher<PointCloud2>::SharedPtr outlier_pointcloud_pub_;
9899
rclcpp::Publisher<PointCloud2>::SharedPtr low_confidence_pointcloud_pub_;
99100
rclcpp::Publisher<PointCloud2>::SharedPtr high_confidence_pointcloud_pub_;

0 commit comments

Comments
 (0)