Skip to content

Commit

Permalink
feat(planning_validator): use polling subscriber (autowarefoundation#…
Browse files Browse the repository at this point in the history
…7356)

* use polling subscriber

Signed-off-by: kyoichi-sugahara <[email protected]>

---------

Signed-off-by: kyoichi-sugahara <[email protected]>
  • Loading branch information
kyoichi-sugahara authored Jun 10, 2024
1 parent 210513d commit 40cc412
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include "autoware_planning_validator/msg/planning_validator_status.hpp"
#include "autoware_vehicle_info_utils/vehicle_info_utils.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 <diagnostic_updater/diagnostic_updater.hpp>
Expand Down Expand Up @@ -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_;
Expand Down
6 changes: 3 additions & 3 deletions planning/planning_validator/src/planning_validator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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));

Expand Down Expand Up @@ -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_) {
Expand Down

0 comments on commit 40cc412

Please sign in to comment.