Skip to content

Commit 5a539f4

Browse files
Autumn60tkimura4
andauthored
feat(path_distance_calculator): change to read topic by polling (#7318)
replace Subscription to InterProcessPollingSubscriber Signed-off-by: Autumn60 <akiro.harada@tier4.jp> Co-authored-by: Autumn60 <akiro.harada@tier4.jp> Co-authored-by: Tomoya Kimura <tomoya.kimura@tier4.jp>
1 parent 45c068a commit 5a539f4

File tree

2 files changed

+4
-6
lines changed

2 files changed

+4
-6
lines changed

common/path_distance_calculator/src/path_distance_calculator.cpp

+1-4
Original file line numberDiff line numberDiff line change
@@ -25,15 +25,12 @@
2525
PathDistanceCalculator::PathDistanceCalculator(const rclcpp::NodeOptions & options)
2626
: Node("path_distance_calculator", options), self_pose_listener_(this)
2727
{
28-
sub_path_ = create_subscription<autoware_planning_msgs::msg::Path>(
29-
"~/input/path", rclcpp::QoS(1),
30-
[this](const autoware_planning_msgs::msg::Path::SharedPtr msg) { path_ = msg; });
3128
pub_dist_ =
3229
create_publisher<tier4_debug_msgs::msg::Float64Stamped>("~/output/distance", rclcpp::QoS(1));
3330

3431
using std::chrono_literals::operator""s;
3532
timer_ = rclcpp::create_timer(this, get_clock(), 1s, [this]() {
36-
const auto path = path_;
33+
const auto path = sub_path_.takeData();
3734
const auto pose = self_pose_listener_.getCurrentPose();
3835
if (!pose) {
3936
RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 5000, "no pose");

common/path_distance_calculator/src/path_distance_calculator.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#ifndef PATH_DISTANCE_CALCULATOR_HPP_
1616
#define PATH_DISTANCE_CALCULATOR_HPP_
1717

18+
#include <autoware/universe_utils/ros/polling_subscriber.hpp>
1819
#include <autoware/universe_utils/ros/self_pose_listener.hpp>
1920
#include <rclcpp/rclcpp.hpp>
2021

@@ -27,11 +28,11 @@ class PathDistanceCalculator : public rclcpp::Node
2728
explicit PathDistanceCalculator(const rclcpp::NodeOptions & options);
2829

2930
private:
30-
rclcpp::Subscription<autoware_planning_msgs::msg::Path>::SharedPtr sub_path_;
31+
autoware::universe_utils::InterProcessPollingSubscriber<autoware_planning_msgs::msg::Path>
32+
sub_path_{this, "~/input/path"};
3133
rclcpp::Publisher<tier4_debug_msgs::msg::Float64Stamped>::SharedPtr pub_dist_;
3234
rclcpp::TimerBase::SharedPtr timer_;
3335
autoware::universe_utils::SelfPoseListener self_pose_listener_;
34-
autoware_planning_msgs::msg::Path::SharedPtr path_;
3536
};
3637

3738
#endif // PATH_DISTANCE_CALCULATOR_HPP_

0 commit comments

Comments
 (0)