Skip to content

Commit ac5121a

Browse files
committed
revise template, inputs first and output at the last
Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
1 parent 79439cd commit ac5121a

File tree

12 files changed

+51
-54
lines changed

12 files changed

+51
-54
lines changed

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

+11-11
Original file line numberDiff line numberDiff line change
@@ -77,7 +77,7 @@ struct Det2dManager
7777
std::unique_ptr<std::mutex> mtx_ptr;
7878
};
7979

80-
template <class TargetMsg3D, class ObjType, class Msg2D>
80+
template <class Msg3D, class Msg2D, class ExportObj>
8181
class FusionNode : public rclcpp::Node
8282
{
8383
public:
@@ -95,7 +95,7 @@ class FusionNode : public rclcpp::Node
9595
const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_camera_info_msg,
9696
const std::size_t camera_id);
9797
// callback for main subscription
98-
void subCallback(const typename TargetMsg3D::ConstSharedPtr input_msg);
98+
void subCallback(const typename Msg3D::ConstSharedPtr input_msg);
9999
// callback for roi subscription
100100
void roiCallback(const typename Msg2D::ConstSharedPtr input_roi_msg, const std::size_t roi_i);
101101
// callback for timer
@@ -128,12 +128,12 @@ class FusionNode : public rclcpp::Node
128128
}
129129

130130
// Custom process methods
131-
virtual void preprocess(TargetMsg3D & output_msg);
131+
virtual void preprocess(Msg3D & output_msg);
132132
virtual void fuseOnSingleImage(
133-
const TargetMsg3D & input_msg, const Det2dManager<Msg2D> & det2d, const Msg2D & input_roi_msg,
134-
TargetMsg3D & output_msg) = 0;
135-
virtual void postprocess(TargetMsg3D & output_msg);
136-
virtual void publish(const TargetMsg3D & output_msg);
133+
const Msg3D & input_msg, const Det2dManager<Msg2D> & det2d, const Msg2D & input_roi_msg,
134+
Msg3D & output_msg) = 0;
135+
virtual void postprocess(Msg3D & output_msg);
136+
virtual void publish(const Msg3D & output_msg);
137137

138138
// Members
139139
std::size_t rois_number_{1};
@@ -154,21 +154,21 @@ class FusionNode : public rclcpp::Node
154154
double match_threshold_ms_{};
155155

156156
/** \brief A vector of subscriber. */
157-
typename rclcpp::Subscription<TargetMsg3D>::SharedPtr sub_;
157+
typename rclcpp::Subscription<Msg3D>::SharedPtr sub_;
158158
std::vector<typename rclcpp::Subscription<Msg2D>::SharedPtr> rois_subs_;
159159
std::vector<rclcpp::Subscription<sensor_msgs::msg::CameraInfo>::SharedPtr> camera_info_subs_;
160160

161161
// cache for fusion
162162
int64_t cached_det3d_msg_timestamp_;
163-
typename TargetMsg3D::SharedPtr cached_det3d_msg_ptr_;
163+
typename Msg3D::SharedPtr cached_det3d_msg_ptr_;
164164
std::mutex mutex_det3d_msg_;
165165

166166
// output publisher
167-
typename rclcpp::Publisher<TargetMsg3D>::SharedPtr pub_ptr_;
167+
typename rclcpp::Publisher<Msg3D>::SharedPtr pub_ptr_;
168168

169169
// debugger
170170
std::shared_ptr<Debugger> debugger_;
171-
virtual bool out_of_scope(const ObjType & obj) = 0;
171+
virtual bool out_of_scope(const ExportObj & obj) = 0;
172172
float filter_scope_min_x_;
173173
float filter_scope_max_x_;
174174
float filter_scope_min_y_;

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

+1-1
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@ inline bool isInsideBbox(
4242
}
4343

4444
class PointPaintingFusionNode
45-
: public FusionNode<sensor_msgs::msg::PointCloud2, DetectedObjects, DetectedObjectsWithFeature>
45+
: public FusionNode<sensor_msgs::msg::PointCloud2, DetectedObjectsWithFeature, DetectedObjects>
4646
{
4747
public:
4848
explicit PointPaintingFusionNode(const rclcpp::NodeOptions & options);

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

+1-1
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@ const std::map<std::string, uint8_t> IOU_MODE_MAP{{"iou", 0}, {"iou_x", 1}, {"io
2626

2727
class RoiClusterFusionNode
2828
: public FusionNode<
29-
DetectedObjectsWithFeature, DetectedObjectWithFeature, DetectedObjectsWithFeature>
29+
DetectedObjectsWithFeature, DetectedObjectsWithFeature, DetectedObjectWithFeature>
3030
{
3131
public:
3232
explicit RoiClusterFusionNode(const rclcpp::NodeOptions & options);

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

+1-1
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ namespace autoware::image_projection_based_fusion
3232
using sensor_msgs::msg::RegionOfInterest;
3333

3434
class RoiDetectedObjectFusionNode
35-
: public FusionNode<DetectedObjects, DetectedObject, DetectedObjectsWithFeature>
35+
: public FusionNode<DetectedObjects, DetectedObjectsWithFeature, DetectedObject>
3636
{
3737
public:
3838
explicit RoiDetectedObjectFusionNode(const rclcpp::NodeOptions & options);

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

+1-1
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@
2626
namespace autoware::image_projection_based_fusion
2727
{
2828
class RoiPointCloudFusionNode
29-
: public FusionNode<PointCloud2, DetectedObjectWithFeature, DetectedObjectsWithFeature>
29+
: public FusionNode<PointCloud2, DetectedObjectsWithFeature, DetectedObjectWithFeature>
3030
{
3131
private:
3232
int min_cluster_size_{1};

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

+1-1
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@
3434

3535
namespace autoware::image_projection_based_fusion
3636
{
37-
class SegmentPointCloudFusionNode : public FusionNode<PointCloud2, PointCloud2, Image>
37+
class SegmentPointCloudFusionNode : public FusionNode<PointCloud2, Image, PointCloud2>
3838
{
3939
private:
4040
rclcpp::Publisher<PointCloud2>::SharedPtr pub_pointcloud_ptr_;

perception/autoware_image_projection_based_fusion/src/fusion_node.cpp

+30-33
Original file line numberDiff line numberDiff line change
@@ -46,8 +46,8 @@ namespace autoware::image_projection_based_fusion
4646
{
4747
using autoware::universe_utils::ScopedTimeTrack;
4848

49-
template <class TargetMsg3D, class ObjType, class Msg2D>
50-
FusionNode<TargetMsg3D, ObjType, Msg2D>::FusionNode(
49+
template <class Msg3D, class Msg2D, class ExportObj>
50+
FusionNode<Msg3D, Msg2D, ExportObj>::FusionNode(
5151
const std::string & node_name, const rclcpp::NodeOptions & options)
5252
: Node(node_name, options), tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_)
5353
{
@@ -102,13 +102,12 @@ FusionNode<TargetMsg3D, ObjType, Msg2D>::FusionNode(
102102
}
103103

104104
// subscribe 3d detection
105-
std::function<void(const typename TargetMsg3D::ConstSharedPtr msg)> sub_callback =
105+
std::function<void(const typename Msg3D::ConstSharedPtr msg)> sub_callback =
106106
std::bind(&FusionNode::subCallback, this, std::placeholders::_1);
107-
sub_ =
108-
this->create_subscription<TargetMsg3D>("input", rclcpp::QoS(1).best_effort(), sub_callback);
107+
sub_ = this->create_subscription<Msg3D>("input", rclcpp::QoS(1).best_effort(), sub_callback);
109108

110109
// publisher
111-
pub_ptr_ = this->create_publisher<TargetMsg3D>("output", rclcpp::QoS{1});
110+
pub_ptr_ = this->create_publisher<Msg3D>("output", rclcpp::QoS{1});
112111

113112
// Set timer
114113
const auto period_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(
@@ -203,8 +202,8 @@ FusionNode<TargetMsg3D, ObjType, Msg2D>::FusionNode(
203202
filter_scope_max_z_ = declare_parameter<double>("filter_scope_max_z");
204203
}
205204

206-
template <class TargetMsg3D, class Obj, class Msg2D>
207-
void FusionNode<TargetMsg3D, Obj, Msg2D>::cameraInfoCallback(
205+
template <class Msg3D, class Msg2D, class ExportObj>
206+
void FusionNode<Msg3D, Msg2D, ExportObj>::cameraInfoCallback(
208207
const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_camera_info_msg,
209208
const std::size_t camera_id)
210209
{
@@ -219,15 +218,14 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::cameraInfoCallback(
219218
}
220219
}
221220

222-
template <class TargetMsg3D, class Obj, class Msg2D>
223-
void FusionNode<TargetMsg3D, Obj, Msg2D>::preprocess(TargetMsg3D & ouput_msg
224-
__attribute__((unused)))
221+
template <class Msg3D, class Msg2D, class ExportObj>
222+
void FusionNode<Msg3D, Msg2D, ExportObj>::preprocess(Msg3D & ouput_msg __attribute__((unused)))
225223
{
226224
// do nothing by default
227225
}
228226

229-
template <class TargetMsg3D, class Obj, class Msg2D>
230-
void FusionNode<TargetMsg3D, Obj, Msg2D>::exportProcess()
227+
template <class Msg3D, class Msg2D, class ExportObj>
228+
void FusionNode<Msg3D, Msg2D, ExportObj>::exportProcess()
231229
{
232230
timer_->cancel();
233231

@@ -254,9 +252,9 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::exportProcess()
254252
cached_det3d_msg_ptr_ = nullptr;
255253
}
256254

257-
template <class TargetMsg3D, class Obj, class Msg2D>
258-
void FusionNode<TargetMsg3D, Obj, Msg2D>::subCallback(
259-
const typename TargetMsg3D::ConstSharedPtr det3d_msg)
255+
template <class Msg3D, class Msg2D, class ExportObj>
256+
void FusionNode<Msg3D, Msg2D, ExportObj>::subCallback(
257+
const typename Msg3D::ConstSharedPtr det3d_msg)
260258
{
261259
std::unique_ptr<ScopedTimeTrack> st_ptr;
262260
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
@@ -285,7 +283,7 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::subCallback(
285283
stop_watch_ptr_->toc("processing_time", true);
286284

287285
// PROCESS: preprocess the main message
288-
typename TargetMsg3D::SharedPtr output_msg = std::make_shared<TargetMsg3D>(*det3d_msg);
286+
typename Msg3D::SharedPtr output_msg = std::make_shared<Msg3D>(*det3d_msg);
289287
preprocess(*output_msg);
290288

291289
// PROCESS: fuse the main message with the cached roi messages
@@ -368,8 +366,8 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::subCallback(
368366
}
369367
}
370368

371-
template <class TargetMsg3D, class Obj, class Msg2D>
372-
void FusionNode<TargetMsg3D, Obj, Msg2D>::roiCallback(
369+
template <class Msg3D, class Msg2D, class ExportObj>
370+
void FusionNode<Msg3D, Msg2D, ExportObj>::roiCallback(
373371
const typename Msg2D::ConstSharedPtr det2d_msg, const std::size_t roi_i)
374372
{
375373
std::unique_ptr<ScopedTimeTrack> st_ptr;
@@ -430,15 +428,14 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::roiCallback(
430428
det2d.cached_det2d_msgs[timestamp_nsec] = det2d_msg;
431429
}
432430

433-
template <class TargetMsg3D, class Obj, class Msg2D>
434-
void FusionNode<TargetMsg3D, Obj, Msg2D>::postprocess(TargetMsg3D & output_msg
435-
__attribute__((unused)))
431+
template <class Msg3D, class Msg2D, class ExportObj>
432+
void FusionNode<Msg3D, Msg2D, ExportObj>::postprocess(Msg3D & output_msg __attribute__((unused)))
436433
{
437434
// do nothing by default
438435
}
439436

440-
template <class TargetMsg3D, class Obj, class Msg2D>
441-
void FusionNode<TargetMsg3D, Obj, Msg2D>::timer_callback()
437+
template <class Msg3D, class Msg2D, class ExportObj>
438+
void FusionNode<Msg3D, Msg2D, ExportObj>::timer_callback()
442439
{
443440
std::unique_ptr<ScopedTimeTrack> st_ptr;
444441
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
@@ -468,8 +465,8 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::timer_callback()
468465
}
469466
}
470467

471-
template <class TargetMsg3D, class Obj, class Msg2D>
472-
void FusionNode<TargetMsg3D, Obj, Msg2D>::setPeriod(const int64_t new_period)
468+
template <class Msg3D, class Msg2D, class ExportObj>
469+
void FusionNode<Msg3D, Msg2D, ExportObj>::setPeriod(const int64_t new_period)
473470
{
474471
if (!timer_) {
475472
return;
@@ -485,8 +482,8 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::setPeriod(const int64_t new_period)
485482
}
486483
}
487484

488-
template <class TargetMsg3D, class Obj, class Msg2D>
489-
void FusionNode<TargetMsg3D, Obj, Msg2D>::publish(const TargetMsg3D & output_msg)
485+
template <class Msg3D, class Msg2D, class ExportObj>
486+
void FusionNode<Msg3D, Msg2D, ExportObj>::publish(const Msg3D & output_msg)
490487
{
491488
if (pub_ptr_->get_subscription_count() < 1) {
492489
return;
@@ -495,10 +492,10 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::publish(const TargetMsg3D & output_msg
495492
}
496493

497494
// explicit instantiation for the supported types
498-
template class FusionNode<DetectedObjects, DetectedObject, DetectedObjectsWithFeature>;
495+
template class FusionNode<DetectedObjects, DetectedObjectsWithFeature, DetectedObject>;
499496
template class FusionNode<
500-
DetectedObjectsWithFeature, DetectedObjectWithFeature, DetectedObjectsWithFeature>;
501-
template class FusionNode<PointCloud2, DetectedObjects, DetectedObjectsWithFeature>;
502-
template class FusionNode<PointCloud2, DetectedObjectWithFeature, DetectedObjectsWithFeature>;
503-
template class FusionNode<PointCloud2, PointCloud2, Image>;
497+
DetectedObjectsWithFeature, DetectedObjectsWithFeature, DetectedObjectWithFeature>;
498+
template class FusionNode<PointCloud2, DetectedObjectsWithFeature, DetectedObjects>;
499+
template class FusionNode<PointCloud2, DetectedObjectsWithFeature, DetectedObjectWithFeature>;
500+
template class FusionNode<PointCloud2, Image, PointCloud2>;
504501
} // namespace autoware::image_projection_based_fusion

perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -91,7 +91,7 @@ inline bool isUnknown(int label2d)
9191
}
9292

9393
PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & options)
94-
: FusionNode<sensor_msgs::msg::PointCloud2, DetectedObjects, DetectedObjectsWithFeature>(
94+
: FusionNode<sensor_msgs::msg::PointCloud2, DetectedObjectsWithFeature, DetectedObjects>(
9595
"pointpainting_fusion", options)
9696
{
9797
omp_num_threads_ = this->declare_parameter<int>("omp_params.num_threads");

perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ namespace autoware::image_projection_based_fusion
4141
using autoware::universe_utils::ScopedTimeTrack;
4242

4343
RoiClusterFusionNode::RoiClusterFusionNode(const rclcpp::NodeOptions & options)
44-
: FusionNode<DetectedObjectsWithFeature, DetectedObjectWithFeature, DetectedObjectsWithFeature>(
44+
: FusionNode<DetectedObjectsWithFeature, DetectedObjectsWithFeature, DetectedObjectWithFeature>(
4545
"roi_cluster_fusion", options)
4646
{
4747
trust_object_iou_mode_ = declare_parameter<std::string>("trust_object_iou_mode");

perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ namespace autoware::image_projection_based_fusion
3131
using autoware::universe_utils::ScopedTimeTrack;
3232

3333
RoiDetectedObjectFusionNode::RoiDetectedObjectFusionNode(const rclcpp::NodeOptions & options)
34-
: FusionNode<DetectedObjects, DetectedObject, DetectedObjectsWithFeature>(
34+
: FusionNode<DetectedObjects, DetectedObjectsWithFeature, DetectedObject>(
3535
"roi_detected_object_fusion", options)
3636
{
3737
fusion_params_.passthrough_lower_bound_probability_thresholds =

perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@ namespace autoware::image_projection_based_fusion
3737
using autoware::universe_utils::ScopedTimeTrack;
3838

3939
RoiPointCloudFusionNode::RoiPointCloudFusionNode(const rclcpp::NodeOptions & options)
40-
: FusionNode<PointCloud2, DetectedObjectWithFeature, DetectedObjectsWithFeature>(
40+
: FusionNode<PointCloud2, DetectedObjectsWithFeature, DetectedObjectWithFeature>(
4141
"roi_pointcloud_fusion", options)
4242
{
4343
fuse_unknown_only_ = declare_parameter<bool>("fuse_unknown_only");

perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@ namespace autoware::image_projection_based_fusion
3636
using autoware::universe_utils::ScopedTimeTrack;
3737

3838
SegmentPointCloudFusionNode::SegmentPointCloudFusionNode(const rclcpp::NodeOptions & options)
39-
: FusionNode<PointCloud2, PointCloud2, Image>("segmentation_pointcloud_fusion", options)
39+
: FusionNode<PointCloud2, Image, PointCloud2>("segmentation_pointcloud_fusion", options)
4040
{
4141
filter_distance_threshold_ = declare_parameter<float>("filter_distance_threshold");
4242
for (auto & item : filter_semantic_label_target_list_) {

0 commit comments

Comments
 (0)