Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(planning_validator): use polling subscriber #7356

Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -18,6 +18,7 @@
#include "autoware_planning_validator/debug_marker.hpp"
#include "autoware_planning_validator/msg/planning_validator_status.hpp"
#include "tier4_autoware_utils/ros/logger_level_configure.hpp"
#include "tier4_autoware_utils/ros/polling_subscriber.hpp"
#include "tier4_autoware_utils/system/stop_watch.hpp"
#include "vehicle_info_util/vehicle_info_util.hpp"

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

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

rclcpp::Subscription<Odometry>::SharedPtr sub_kinematics_;
tier4_autoware_utils::InterProcessPollingSubscriber<Odometry> sub_kinematics_{
this, "~/input/kinematics"};
rclcpp::Subscription<Trajectory>::SharedPtr sub_traj_;
rclcpp::Publisher<Trajectory>::SharedPtr pub_traj_;
rclcpp::Publisher<PlanningValidatorStatus>::SharedPtr pub_status_;
6 changes: 3 additions & 3 deletions planning/planning_validator/src/planning_validator.cpp
Original file line number Diff line number Diff line change
@@ -32,9 +32,6 @@ PlanningValidator::PlanningValidator(const rclcpp::NodeOptions & options)
{
using std::placeholders::_1;

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

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

current_trajectory_ = msg;

// receive data
current_kinematics_ = sub_kinematics_.takeData();

if (!isDataReady()) return;

if (publish_diag_ && !diag_updater_) {