Skip to content

Commit

Permalink
Refactor fusion_node.hpp and fusion_node.cpp for improved code organi…
Browse files Browse the repository at this point in the history
…zation and readability

Signed-off-by: Taekjin LEE <[email protected]>
  • Loading branch information
technolojin committed Dec 26, 2024
1 parent e4e666d commit d8646c2
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 15 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -165,18 +165,20 @@ class FusionNode : public rclcpp::Node
typename Msg3D::SharedPtr cached_det3d_msg_ptr_;
std::mutex mutex_det3d_msg_;

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

// debugger
std::shared_ptr<Debugger> debugger_;
// parameters for out_of_scope filter
float filter_scope_min_x_;
float filter_scope_max_x_;
float filter_scope_min_y_;
float filter_scope_max_y_;
float filter_scope_min_z_;
float filter_scope_max_z_;

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

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

/** \brief processing time publisher. **/
std::unique_ptr<autoware::universe_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_;
std::unique_ptr<autoware::universe_utils::DebugPublisher> debug_publisher_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -106,9 +106,6 @@ FusionNode<Msg3D, Msg2D, ExportObj>::FusionNode(
std::bind(&FusionNode::subCallback, this, std::placeholders::_1);
sub_ = this->create_subscription<Msg3D>("input", rclcpp::QoS(1).best_effort(), sub_callback);

// // publisher
// pub_ptr_ = this->create_publisher<Msg3D>("output", rclcpp::QoS{1});

// Set timer
const auto period_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(
std::chrono::duration<double, std::milli>(timeout_ms_));
Expand Down Expand Up @@ -159,6 +156,14 @@ FusionNode<Msg3D, Msg2D, ExportObj>::FusionNode(
det2d_list_.at(roi_i).input_offset_ms = input_offset_ms.at(roi_i);

Check warning on line 156 in perception/autoware_image_projection_based_fusion/src/fusion_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/fusion_node.cpp#L156

Added line #L156 was not covered by tests
}

// parameters for out_of_scope filter
filter_scope_min_x_ = declare_parameter<double>("filter_scope_min_x");
filter_scope_max_x_ = declare_parameter<double>("filter_scope_max_x");
filter_scope_min_y_ = declare_parameter<double>("filter_scope_min_y");
filter_scope_max_y_ = declare_parameter<double>("filter_scope_max_y");
filter_scope_min_z_ = declare_parameter<double>("filter_scope_min_z");
filter_scope_max_z_ = declare_parameter<double>("filter_scope_max_z");

// debugger
if (declare_parameter("debug_mode", false)) {
std::vector<std::string> input_camera_topics;
Expand Down Expand Up @@ -193,13 +198,6 @@ FusionNode<Msg3D, Msg2D, ExportObj>::FusionNode(
stop_watch_ptr_->tic("cyclic_time");
stop_watch_ptr_->tic("processing_time");
}

filter_scope_min_x_ = declare_parameter<double>("filter_scope_min_x");
filter_scope_max_x_ = declare_parameter<double>("filter_scope_max_x");
filter_scope_min_y_ = declare_parameter<double>("filter_scope_min_y");
filter_scope_max_y_ = declare_parameter<double>("filter_scope_max_y");
filter_scope_min_z_ = declare_parameter<double>("filter_scope_min_z");
filter_scope_max_z_ = declare_parameter<double>("filter_scope_max_z");
}

template <class Msg3D, class Msg2D, class ExportObj>
Expand Down

0 comments on commit d8646c2

Please sign in to comment.