Skip to content

Commit f5a5a56

Browse files
committed
Refactor publisher types in fusion_node.hpp and node.hpp
Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
1 parent ad5c361 commit f5a5a56

File tree

8 files changed

+16
-25
lines changed

8 files changed

+16
-25
lines changed

perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -166,7 +166,7 @@ class FusionNode : public rclcpp::Node
166166
std::mutex mutex_det3d_msg_;
167167

168168
// output publisher
169-
// typename rclcpp::Publisher<Msg3D>::SharedPtr pub_ptr_;
169+
typename rclcpp::Publisher<ExportObj>::SharedPtr pub_ptr_;
170170

171171
// debugger
172172
std::shared_ptr<Debugger> debugger_;

perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -57,8 +57,7 @@ class PointPaintingFusionNode : public FusionNode<PointCloudMsgType, RoiMsgType,
5757

5858
void publish(const PointCloudMsgType & output_msg) override;
5959

60-
rclcpp::Publisher<DetectedObjects>::SharedPtr obj_pub_ptr_;
61-
rclcpp::Publisher<PointCloudMsgType>::SharedPtr pub_ptr_;
60+
rclcpp::Publisher<PointCloudMsgType>::SharedPtr point_pub_ptr_;
6261

6362
int omp_num_threads_{1};
6463
float score_threshold_{0.0};

perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_cluster_fusion/node.hpp

-2
Original file line numberDiff line numberDiff line change
@@ -38,8 +38,6 @@ class RoiClusterFusionNode : public FusionNode<ClusterMsgType, RoiMsgType, Clust
3838
const ClusterMsgType & input_cluster_msg, const Det2dManager<RoiMsgType> & det2d,
3939
const RoiMsgType & input_roi_msg, ClusterMsgType & output_cluster_msg) override;
4040

41-
rclcpp::Publisher<ClusterMsgType>::SharedPtr pub_ptr_;
42-
4341
private:
4442
std::string trust_object_iou_mode_{"iou"};
4543
bool use_cluster_semantic_type_{false};

perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_detected_object_fusion/node.hpp

-2
Original file line numberDiff line numberDiff line change
@@ -56,8 +56,6 @@ class RoiDetectedObjectFusionNode : public FusionNode<DetectedObjects, RoiMsgTyp
5656

5757
bool out_of_scope(const DetectedObject & obj);
5858

59-
rclcpp::Publisher<DetectedObjects>::SharedPtr pub_ptr_;
60-
6159
private:
6260
struct
6361
{

perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -31,8 +31,7 @@ class RoiPointCloudFusionNode : public FusionNode<PointCloudMsgType, RoiMsgType,
3131
explicit RoiPointCloudFusionNode(const rclcpp::NodeOptions & options);
3232

3333
protected:
34-
rclcpp::Publisher<ClusterMsgType>::SharedPtr pub_objects_ptr_;
35-
rclcpp::Publisher<PointCloudMsgType>::SharedPtr pub_ptr_;
34+
rclcpp::Publisher<PointCloudMsgType>::SharedPtr point_pub_ptr_;
3635
rclcpp::Publisher<PointCloudMsgType>::SharedPtr cluster_debug_pub_;
3736

3837
void postprocess(PointCloudMsgType & pointcloud_msg) override;

perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp

-3
Original file line numberDiff line numberDiff line change
@@ -58,9 +58,6 @@ class SegmentPointCloudFusionNode : public FusionNode<PointCloudMsgType, Image,
5858

5959
void publish(const PointCloudMsgType & output_msg) override;
6060

61-
// publisher
62-
rclcpp::Publisher<PointCloudMsgType>::SharedPtr pub_ptr_;
63-
6461
// debug
6562
image_transport::Publisher pub_debug_mask_ptr_;
6663

perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -162,8 +162,8 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt
162162
"~/input/pointcloud", rclcpp::SensorDataQoS().keep_last(3), sub_callback);
163163

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

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

385385
const auto objects_sub_count =
386-
obj_pub_ptr_->get_subscription_count() + obj_pub_ptr_->get_intra_process_subscription_count();
386+
pub_ptr_->get_subscription_count() + pub_ptr_->get_intra_process_subscription_count();
387387
if (objects_sub_count < 1) {
388388
return;
389389
}
@@ -415,16 +415,16 @@ void PointPaintingFusionNode::postprocess(PointCloudMsgType & painted_pointcloud
415415
detection_class_remapper_.mapClasses(output_msg);
416416

417417
if (objects_sub_count > 0) {
418-
obj_pub_ptr_->publish(output_msg);
418+
pub_ptr_->publish(output_msg);
419419
}
420420
}
421421

422422
void PointPaintingFusionNode::publish(const PointCloudMsgType & painted_pointcloud_msg)
423423
{
424-
if (pub_ptr_->get_subscription_count() < 1) {
424+
if (point_pub_ptr_->get_subscription_count() < 1) {
425425
return;
426426
}
427-
pub_ptr_->publish(painted_pointcloud_msg);
427+
point_pub_ptr_->publish(painted_pointcloud_msg);
428428
}
429429

430430
} // namespace autoware::image_projection_based_fusion

perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -45,8 +45,8 @@ RoiPointCloudFusionNode::RoiPointCloudFusionNode(const rclcpp::NodeOptions & opt
4545
cluster_2d_tolerance_ = declare_parameter<double>("cluster_2d_tolerance");
4646

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

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

58-
const auto objects_sub_count = pub_objects_ptr_->get_subscription_count() +
59-
pub_objects_ptr_->get_intra_process_subscription_count();
58+
const auto objects_sub_count =
59+
pub_ptr_->get_subscription_count() + pub_ptr_->get_intra_process_subscription_count();
6060
if (objects_sub_count < 1) {
6161
return;
6262
}
@@ -66,7 +66,7 @@ void RoiPointCloudFusionNode::postprocess(PointCloudMsgType & pointcloud_msg)
6666
output_msg.feature_objects = output_fused_objects_;
6767

6868
if (objects_sub_count > 0) {
69-
pub_objects_ptr_->publish(output_msg);
69+
pub_ptr_->publish(output_msg);
7070
}
7171
output_fused_objects_.clear();
7272
// publish debug cluster
@@ -199,10 +199,10 @@ void RoiPointCloudFusionNode::fuseOnSingleImage(
199199

200200
void RoiPointCloudFusionNode::publish(const PointCloudMsgType & output_msg)
201201
{
202-
if (pub_ptr_->get_subscription_count() < 1) {
202+
if (point_pub_ptr_->get_subscription_count() < 1) {
203203
return;
204204
}
205-
pub_ptr_->publish(output_msg);
205+
point_pub_ptr_->publish(output_msg);
206206
}
207207

208208
} // namespace autoware::image_projection_based_fusion

0 commit comments

Comments
 (0)