Skip to content

Commit

Permalink
Refactor publisher types in fusion_node.hpp and node.hpp
Browse files Browse the repository at this point in the history
  • Loading branch information
technolojin committed Dec 26, 2024
1 parent 117fb7a commit e079772
Show file tree
Hide file tree
Showing 8 changed files with 16 additions and 25 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ class FusionNode : public rclcpp::Node
std::mutex mutex_det3d_msg_;

// output publisher
// typename rclcpp::Publisher<Msg3D>::SharedPtr pub_ptr_;
typename rclcpp::Publisher<ExportObj>::SharedPtr pub_ptr_;

// debugger
std::shared_ptr<Debugger> debugger_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,8 +57,7 @@ class PointPaintingFusionNode : public FusionNode<PointCloudMsgType, RoiMsgType,

void publish(const PointCloudMsgType & output_msg) override;

rclcpp::Publisher<DetectedObjects>::SharedPtr obj_pub_ptr_;
rclcpp::Publisher<PointCloudMsgType>::SharedPtr pub_ptr_;
rclcpp::Publisher<PointCloudMsgType>::SharedPtr point_pub_ptr_;

int omp_num_threads_{1};
float score_threshold_{0.0};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,6 @@ class RoiClusterFusionNode : public FusionNode<ClusterMsgType, RoiMsgType, Clust
const ClusterMsgType & input_cluster_msg, const Det2dManager<RoiMsgType> & det2d,
const RoiMsgType & input_roi_msg, ClusterMsgType & output_cluster_msg) override;

rclcpp::Publisher<ClusterMsgType>::SharedPtr pub_ptr_;

private:
std::string trust_object_iou_mode_{"iou"};
bool use_cluster_semantic_type_{false};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,6 @@ class RoiDetectedObjectFusionNode : public FusionNode<DetectedObjects, RoiMsgTyp

bool out_of_scope(const DetectedObject & obj);

rclcpp::Publisher<DetectedObjects>::SharedPtr pub_ptr_;

private:
struct
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,7 @@ class RoiPointCloudFusionNode : public FusionNode<PointCloudMsgType, RoiMsgType,
explicit RoiPointCloudFusionNode(const rclcpp::NodeOptions & options);

protected:
rclcpp::Publisher<ClusterMsgType>::SharedPtr pub_objects_ptr_;
rclcpp::Publisher<PointCloudMsgType>::SharedPtr pub_ptr_;
rclcpp::Publisher<PointCloudMsgType>::SharedPtr point_pub_ptr_;
rclcpp::Publisher<PointCloudMsgType>::SharedPtr cluster_debug_pub_;

void postprocess(PointCloudMsgType & pointcloud_msg) override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,9 +58,6 @@ class SegmentPointCloudFusionNode : public FusionNode<PointCloudMsgType, Image,

void publish(const PointCloudMsgType & output_msg) override;

// publisher
rclcpp::Publisher<PointCloudMsgType>::SharedPtr pub_ptr_;

// debug
image_transport::Publisher pub_debug_mask_ptr_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -162,8 +162,8 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt
"~/input/pointcloud", rclcpp::SensorDataQoS().keep_last(3), sub_callback);

// publisher
pub_ptr_ = this->create_publisher<PointCloudMsgType>("output", rclcpp::QoS{1});
obj_pub_ptr_ = this->create_publisher<DetectedObjects>("~/output/objects", rclcpp::QoS{1});
point_pub_ptr_ = this->create_publisher<PointCloudMsgType>("output", rclcpp::QoS{1});
pub_ptr_ = this->create_publisher<DetectedObjects>("~/output/objects", rclcpp::QoS{1});

detection_class_remapper_.setParameters(
allow_remapping_by_area_matrix, min_area_matrix, max_area_matrix);
Expand Down Expand Up @@ -383,7 +383,7 @@ void PointPaintingFusionNode::postprocess(PointCloudMsgType & painted_pointcloud
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

const auto objects_sub_count =
obj_pub_ptr_->get_subscription_count() + obj_pub_ptr_->get_intra_process_subscription_count();
pub_ptr_->get_subscription_count() + pub_ptr_->get_intra_process_subscription_count();
if (objects_sub_count < 1) {
return;
}
Expand Down Expand Up @@ -415,16 +415,16 @@ void PointPaintingFusionNode::postprocess(PointCloudMsgType & painted_pointcloud
detection_class_remapper_.mapClasses(output_msg);

if (objects_sub_count > 0) {
obj_pub_ptr_->publish(output_msg);
pub_ptr_->publish(output_msg);
}
}

void PointPaintingFusionNode::publish(const PointCloudMsgType & painted_pointcloud_msg)
{
if (pub_ptr_->get_subscription_count() < 1) {
if (point_pub_ptr_->get_subscription_count() < 1) {
return;
}
pub_ptr_->publish(painted_pointcloud_msg);
point_pub_ptr_->publish(painted_pointcloud_msg);
}

} // namespace autoware::image_projection_based_fusion
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,8 @@ RoiPointCloudFusionNode::RoiPointCloudFusionNode(const rclcpp::NodeOptions & opt
cluster_2d_tolerance_ = declare_parameter<double>("cluster_2d_tolerance");

// publisher
pub_ptr_ = this->create_publisher<PointCloudMsgType>("output", rclcpp::QoS{1});
pub_objects_ptr_ = this->create_publisher<ClusterMsgType>("output_clusters", rclcpp::QoS{1});
point_pub_ptr_ = this->create_publisher<PointCloudMsgType>("output", rclcpp::QoS{1});
pub_ptr_ = this->create_publisher<ClusterMsgType>("output_clusters", rclcpp::QoS{1});
cluster_debug_pub_ = this->create_publisher<PointCloudMsgType>("debug/clusters", 1);
}

Expand All @@ -55,8 +55,8 @@ void RoiPointCloudFusionNode::postprocess(PointCloudMsgType & pointcloud_msg)
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

const auto objects_sub_count = pub_objects_ptr_->get_subscription_count() +
pub_objects_ptr_->get_intra_process_subscription_count();
const auto objects_sub_count =
pub_ptr_->get_subscription_count() + pub_ptr_->get_intra_process_subscription_count();
if (objects_sub_count < 1) {
return;
}
Expand All @@ -66,7 +66,7 @@ void RoiPointCloudFusionNode::postprocess(PointCloudMsgType & pointcloud_msg)
output_msg.feature_objects = output_fused_objects_;

if (objects_sub_count > 0) {
pub_objects_ptr_->publish(output_msg);
pub_ptr_->publish(output_msg);
}
output_fused_objects_.clear();
// publish debug cluster
Expand Down Expand Up @@ -199,10 +199,10 @@ void RoiPointCloudFusionNode::fuseOnSingleImage(

void RoiPointCloudFusionNode::publish(const PointCloudMsgType & output_msg)
{
if (pub_ptr_->get_subscription_count() < 1) {
if (point_pub_ptr_->get_subscription_count() < 1) {
return;
}
pub_ptr_->publish(output_msg);
point_pub_ptr_->publish(output_msg);
}

} // namespace autoware::image_projection_based_fusion
Expand Down

0 comments on commit e079772

Please sign in to comment.