Skip to content

Commit 5aa20fa

Browse files
use polling subscriber
Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
1 parent 2cd6436 commit 5aa20fa

File tree

2 files changed

+7
-4
lines changed

2 files changed

+7
-4
lines changed

planning/planning_validator/include/autoware_planning_validator/planning_validator.hpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include "autoware_planning_validator/debug_marker.hpp"
1919
#include "autoware_planning_validator/msg/planning_validator_status.hpp"
2020
#include "tier4_autoware_utils/ros/logger_level_configure.hpp"
21+
#include "tier4_autoware_utils/ros/polling_subscriber.hpp"
2122
#include "tier4_autoware_utils/system/stop_watch.hpp"
2223
#include "vehicle_info_util/vehicle_info_util.hpp"
2324

@@ -102,8 +103,10 @@ class PlanningValidator : public rclcpp::Node
102103

103104
void setStatus(DiagnosticStatusWrapper & stat, const bool & is_ok, const std::string & msg);
104105

105-
rclcpp::Subscription<Odometry>::SharedPtr sub_kinematics_;
106+
tier4_autoware_utils::InterProcessPollingSubscriber<Odometry> sub_kinematics_{
107+
this, "~/input/kinematics"};
106108
rclcpp::Subscription<Trajectory>::SharedPtr sub_traj_;
109+
107110
rclcpp::Publisher<Trajectory>::SharedPtr pub_traj_;
108111
rclcpp::Publisher<PlanningValidatorStatus>::SharedPtr pub_status_;
109112
rclcpp::Publisher<Float64Stamped>::SharedPtr pub_processing_time_ms_;

planning/planning_validator/src/planning_validator.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -32,9 +32,6 @@ PlanningValidator::PlanningValidator(const rclcpp::NodeOptions & options)
3232
{
3333
using std::placeholders::_1;
3434

35-
sub_kinematics_ = create_subscription<Odometry>(
36-
"~/input/kinematics", 1,
37-
[this](const Odometry::ConstSharedPtr msg) { current_kinematics_ = msg; });
3835
sub_traj_ = create_subscription<Trajectory>(
3936
"~/input/trajectory", 1, std::bind(&PlanningValidator::onTrajectory, this, _1));
4037

@@ -195,6 +192,9 @@ void PlanningValidator::onTrajectory(const Trajectory::ConstSharedPtr msg)
195192

196193
current_trajectory_ = msg;
197194

195+
// receive data
196+
current_kinematics_ = sub_kinematics_.takeData();
197+
198198
if (!isDataReady()) return;
199199

200200
if (publish_diag_ && !diag_updater_) {

0 commit comments

Comments
 (0)