Skip to content

Commit 3b036b1

Browse files
authored
feat(autoware_velocity_smoother): use polling subscriber (autowarefoundation#7216)
feat(motion_velocity_smoother): use polling subscriber Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent 7d12dcf commit 3b036b1

File tree

2 files changed

+18
-31
lines changed
  • planning/autoware_velocity_smoother

2 files changed

+18
-31
lines changed

planning/autoware_velocity_smoother/include/autoware_velocity_smoother/node.hpp

+9-8
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@
3131
#include "tier4_autoware_utils/geometry/geometry.hpp"
3232
#include "tier4_autoware_utils/math/unit_conversion.hpp"
3333
#include "tier4_autoware_utils/ros/logger_level_configure.hpp"
34+
#include "tier4_autoware_utils/ros/polling_subscriber.hpp"
3435
#include "tier4_autoware_utils/ros/self_pose_listener.hpp"
3536
#include "tier4_autoware_utils/system/stop_watch.hpp"
3637

@@ -86,11 +87,15 @@ class VelocitySmootherNode : public rclcpp::Node
8687
rclcpp::Publisher<Trajectory>::SharedPtr pub_trajectory_;
8788
rclcpp::Publisher<MarkerArray>::SharedPtr pub_virtual_wall_;
8889
rclcpp::Publisher<StopSpeedExceeded>::SharedPtr pub_over_stop_velocity_;
89-
rclcpp::Subscription<Odometry>::SharedPtr sub_current_odometry_;
90-
rclcpp::Subscription<AccelWithCovarianceStamped>::SharedPtr sub_current_acceleration_;
9190
rclcpp::Subscription<Trajectory>::SharedPtr sub_current_trajectory_;
92-
rclcpp::Subscription<VelocityLimit>::SharedPtr sub_external_velocity_limit_;
93-
rclcpp::Subscription<OperationModeState>::SharedPtr sub_operation_mode_;
91+
tier4_autoware_utils::InterProcessPollingSubscriber<Odometry> sub_current_odometry_{
92+
this, "/localization/kinematic_state"};
93+
tier4_autoware_utils::InterProcessPollingSubscriber<AccelWithCovarianceStamped>
94+
sub_current_acceleration_{this, "~/input/acceleration"};
95+
tier4_autoware_utils::InterProcessPollingSubscriber<VelocityLimit> sub_external_velocity_limit_{
96+
this, "~/input/external_velocity_limit_mps"};
97+
tier4_autoware_utils::InterProcessPollingSubscriber<OperationModeState> sub_operation_mode_{
98+
this, "~/input/operation_mode_state"};
9499

95100
Odometry::ConstSharedPtr current_odometry_ptr_; // current odometry
96101
AccelWithCovarianceStamped::ConstSharedPtr current_acceleration_ptr_;
@@ -180,12 +185,8 @@ class VelocitySmootherNode : public rclcpp::Node
180185
const std::vector<rclcpp::Parameter> & parameters);
181186

182187
// topic callback
183-
void onCurrentOdometry(const Odometry::ConstSharedPtr msg);
184-
185188
void onCurrentTrajectory(const Trajectory::ConstSharedPtr msg);
186189

187-
void onExternalVelocityLimit(const VelocityLimit::ConstSharedPtr msg);
188-
189190
void calcExternalVelocityLimit();
190191

191192
// publish methods

planning/autoware_velocity_smoother/src/node.cpp

+9-23
Original file line numberDiff line numberDiff line change
@@ -58,19 +58,6 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti
5858
pub_over_stop_velocity_ = create_publisher<StopSpeedExceeded>("~/stop_speed_exceeded", 1);
5959
sub_current_trajectory_ = create_subscription<Trajectory>(
6060
"~/input/trajectory", 1, std::bind(&VelocitySmootherNode::onCurrentTrajectory, this, _1));
61-
sub_current_odometry_ = create_subscription<Odometry>(
62-
"/localization/kinematic_state", 1,
63-
std::bind(&VelocitySmootherNode::onCurrentOdometry, this, _1));
64-
sub_external_velocity_limit_ = create_subscription<VelocityLimit>(
65-
"~/input/external_velocity_limit_mps", 1,
66-
std::bind(&VelocitySmootherNode::onExternalVelocityLimit, this, _1));
67-
sub_current_acceleration_ = create_subscription<AccelWithCovarianceStamped>(
68-
"~/input/acceleration", 1, [this](const AccelWithCovarianceStamped::ConstSharedPtr msg) {
69-
current_acceleration_ptr_ = msg;
70-
});
71-
sub_operation_mode_ = create_subscription<OperationModeState>(
72-
"~/input/operation_mode_state", 1,
73-
[this](const OperationModeState::ConstSharedPtr msg) { operation_mode_ = *msg; });
7461

7562
// parameter update
7663
set_param_res_ =
@@ -319,16 +306,6 @@ void VelocitySmootherNode::publishTrajectory(const TrajectoryPoints & trajectory
319306
pub_trajectory_, publishing_trajectory.header.stamp);
320307
}
321308

322-
void VelocitySmootherNode::onCurrentOdometry(const Odometry::ConstSharedPtr msg)
323-
{
324-
current_odometry_ptr_ = msg;
325-
}
326-
327-
void VelocitySmootherNode::onExternalVelocityLimit(const VelocityLimit::ConstSharedPtr msg)
328-
{
329-
external_velocity_limit_ptr_ = msg;
330-
}
331-
332309
void VelocitySmootherNode::calcExternalVelocityLimit()
333310
{
334311
if (!external_velocity_limit_ptr_) {
@@ -441,6 +418,15 @@ void VelocitySmootherNode::onCurrentTrajectory(const Trajectory::ConstSharedPtr
441418

442419
base_traj_raw_ptr_ = msg;
443420

421+
// receive data
422+
current_odometry_ptr_ = sub_current_odometry_.takeData();
423+
current_acceleration_ptr_ = sub_current_acceleration_.takeData();
424+
external_velocity_limit_ptr_ = sub_external_velocity_limit_.takeData();
425+
const auto operation_mode_ptr = sub_operation_mode_.takeData();
426+
if (operation_mode_ptr) {
427+
operation_mode_ = *operation_mode_ptr;
428+
}
429+
444430
// guard
445431
if (!checkData()) {
446432
return;

0 commit comments

Comments
 (0)