@@ -108,7 +108,8 @@ FusionNode<TargetMsg3D, ObjType, Msg2D>::FusionNode(
108
108
// subscribers
109
109
std::function<void (const typename TargetMsg3D::ConstSharedPtr msg)> sub_callback =
110
110
std::bind (&FusionNode::subCallback, this , std::placeholders::_1);
111
- sub_ = this ->create_subscription <TargetMsg3D>(" input" , rclcpp::QoS (1 ).best_effort (), sub_callback);
111
+ sub_ =
112
+ this ->create_subscription <TargetMsg3D>(" input" , rclcpp::QoS (1 ).best_effort (), sub_callback);
112
113
113
114
// publisher
114
115
pub_ptr_ = this ->create_publisher <TargetMsg3D>(" output" , rclcpp::QoS{1 });
@@ -154,13 +155,15 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::cameraInfoCallback(
154
155
}
155
156
156
157
template <class TargetMsg3D , class Obj , class Msg2D >
157
- void FusionNode<TargetMsg3D, Obj, Msg2D>::preprocess(TargetMsg3D & ouput_msg __attribute__ ((unused)))
158
+ void FusionNode<TargetMsg3D, Obj, Msg2D>::preprocess(TargetMsg3D & ouput_msg
159
+ __attribute__ ((unused)))
158
160
{
159
161
// do nothing by default
160
162
}
161
163
162
164
template <class TargetMsg3D , class Obj , class Msg2D >
163
- void FusionNode<TargetMsg3D, Obj, Msg2D>::subCallback(const typename TargetMsg3D::ConstSharedPtr input_msg)
165
+ void FusionNode<TargetMsg3D, Obj, Msg2D>::subCallback(
166
+ const typename TargetMsg3D::ConstSharedPtr input_msg)
164
167
{
165
168
if (cached_msg_.second != nullptr ) {
166
169
stop_watch_ptr_->toc (" processing_time" , true );
@@ -357,7 +360,8 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::roiCallback(
357
360
}
358
361
359
362
template <class TargetMsg3D , class Obj , class Msg2D >
360
- void FusionNode<TargetMsg3D, Obj, Msg2D>::postprocess(TargetMsg3D & output_msg __attribute__ ((unused)))
363
+ void FusionNode<TargetMsg3D, Obj, Msg2D>::postprocess(TargetMsg3D & output_msg
364
+ __attribute__ ((unused)))
361
365
{
362
366
// do nothing by default
363
367
}
0 commit comments