Skip to content

Commit

Permalink
fix: skip publish debug mask
Browse files Browse the repository at this point in the history
Signed-off-by: badai-nguyen <[email protected]>
  • Loading branch information
badai-nguyen committed Aug 19, 2024
1 parent 7dc5af1 commit 30fa9ae
Show file tree
Hide file tree
Showing 4 changed files with 1 addition and 24 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -22,4 +22,3 @@

# the maximum distance of pointcloud to be applied filter
filter_distance_threshold: 60.0
is_publish_debug_mask: false
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#include "autoware/image_projection_based_fusion/fusion_node.hpp"

#include <autoware/image_projection_based_fusion/utils/utils.hpp>
#include <image_transport/image_transport.hpp>

#include <string>
#include <utility>
Expand All @@ -45,9 +44,6 @@ class SegmentPointCloudFusionNode : public FusionNode<PointCloud2, PointCloud2,
{"BIKE", false}, {"ROAD", false}, {"SIDEWALK", false}, {"ROAD_PAINT", false},
{"CURBSTONE", false}, {"CROSSWALK", false}, {"VEGETATION", false}, {"SKY", false}};

image_transport::Publisher pub_debug_mask_ptr_;
bool is_publish_debug_mask_;

public:
explicit SegmentPointCloudFusionNode(const rclcpp::NodeOptions & options);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -114,18 +114,9 @@
"description": "A maximum distance of pointcloud to apply filter [m].",
"default": 60.0,
"minimum": 0.0
},
"is_publish_debug_mask": {
"type": "boolean",
"description": "If true, debug mask image will be published.",
"default": false
}
},
"required": [
"filter_semantic_label_target",
"filter_distance_threshold",
"is_publish_debug_mask"
]
"required": ["filter_semantic_label_target", "filter_distance_threshold"]
}
},
"properties": {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,6 @@ SegmentPointCloudFusionNode::SegmentPointCloudFusionNode(const rclcpp::NodeOptio
RCLCPP_INFO(
this->get_logger(), "filter_semantic_label_target: %s %d", item.first.c_str(), item.second);
}
is_publish_debug_mask_ = declare_parameter<bool>("is_publish_debug_mask");
pub_debug_mask_ptr_ = image_transport::create_publisher(this, "debug/mask");
}

void SegmentPointCloudFusionNode::preprocess(__attribute__((unused)) PointCloud2 & pointcloud_msg)
Expand All @@ -67,13 +65,6 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage(
std::vector<uint8_t> 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
Expand Down

0 comments on commit 30fa9ae

Please sign in to comment.