Skip to content

Commit

Permalink
refactor(cluster_merger): remove unused variable and rename topic (au…
Browse files Browse the repository at this point in the history
…towarefoundation#8809)

Signed-off-by: badai-nguyen <[email protected]>
  • Loading branch information
badai-nguyen authored Sep 10, 2024
1 parent 5e18705 commit 14a499e
Show file tree
Hide file tree
Showing 3 changed files with 2 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="param_path" default="$(find-pkg-share autoware_cluster_merger)/config/cluster_merger.param.yaml"/>
<!-- Node -->
<node pkg="autoware_cluster_merger" exec="cluster_merger_node" name="autoware_cluster_merger" output="screen">
<remap from="~/output/clusters" to="$(var output/clusters)"/>
<remap from="output/clusters" to="$(var output/clusters)"/>
<remap from="input/cluster0" to="$(var input/cluster0)"/>
<remap from="input/cluster1" to="$(var input/cluster1)"/>
<param from="$(var param_path)"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ ClusterMergerNode::ClusterMergerNode(const rclcpp::NodeOptions & node_options)
sync_.registerCallback(std::bind(&ClusterMergerNode::objectsCallback, this, _1, _2));

// Publisher
pub_objects_ = create_publisher<DetectedObjectsWithFeature>("~/output/clusters", rclcpp::QoS{1});
pub_objects_ = create_publisher<DetectedObjectsWithFeature>("output/clusters", rclcpp::QoS{1});
}

void ClusterMergerNode::objectsCallback(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,6 @@ class ClusterMergerNode : public rclcpp::Node
tf2_ros::Buffer tf_buffer_;
tf2_ros::TransformListener tf_listener_;

rclcpp::Subscription<DetectedObjectsWithFeature>::SharedPtr sub_objects_{};
message_filters::Subscriber<DetectedObjectsWithFeature> objects0_sub_;
message_filters::Subscriber<DetectedObjectsWithFeature> objects1_sub_;
typedef message_filters::sync_policies::ApproximateTime<
Expand All @@ -58,9 +57,6 @@ class ClusterMergerNode : public rclcpp::Node

std::string output_frame_id_;

std::vector<rclcpp::Subscription<DetectedObjectsWithFeature>::SharedPtr> sub_objects_array{};
std::shared_ptr<autoware::universe_utils::TransformListener> transform_listener_;

void objectsCallback(
const DetectedObjectsWithFeature::ConstSharedPtr & input_objects0_msg,
const DetectedObjectsWithFeature::ConstSharedPtr & input_objects1_msg);
Expand Down

0 comments on commit 14a499e

Please sign in to comment.