diff --git a/perception/autoware_image_projection_based_fusion/config/segmentation_pointcloud_fusion.param.yaml b/perception/autoware_image_projection_based_fusion/config/segmentation_pointcloud_fusion.param.yaml index 444f7d92ede4e..fdabb0c7055d8 100644 --- a/perception/autoware_image_projection_based_fusion/config/segmentation_pointcloud_fusion.param.yaml +++ b/perception/autoware_image_projection_based_fusion/config/segmentation_pointcloud_fusion.param.yaml @@ -22,4 +22,3 @@ # the maximum distance of pointcloud to be applied filter filter_distance_threshold: 60.0 - is_publish_debug_mask: false diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp index af7a4cb18ad61..c57d455300125 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp @@ -18,7 +18,6 @@ #include "autoware/image_projection_based_fusion/fusion_node.hpp" #include -#include #include #include @@ -45,9 +44,6 @@ class SegmentPointCloudFusionNode : public FusionNodeget_logger(), "filter_semantic_label_target: %s %d", item.first.c_str(), item.second); } - is_publish_debug_mask_ = declare_parameter("is_publish_debug_mask"); - pub_debug_mask_ptr_ = image_transport::create_publisher(this, "debug/mask"); } void SegmentPointCloudFusionNode::preprocess(__attribute__((unused)) PointCloud2 & pointcloud_msg) @@ -67,13 +65,6 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage( std::vector mask_data(input_mask.data.begin(), input_mask.data.end()); cv::Mat mask = perception_utils::runLengthDecoder(mask_data, input_mask.height, input_mask.width); - // publish debug mask - if (is_publish_debug_mask_) { - sensor_msgs::msg::Image::SharedPtr debug_mask_msg = - cv_bridge::CvImage(std_msgs::msg::Header(), "mono8", mask).toImageMsg(); - debug_mask_msg->header = input_mask.header; - pub_debug_mask_ptr_.publish(debug_mask_msg); - } const int orig_width = camera_info.width; const int orig_height = camera_info.height; // resize mask to the same size as the camera image