Skip to content

Commit 767e8f7

Browse files
takayuki5168kminoda
authored andcommitted
feat(surround_obstacle_checker): use polling subscriber (autowarefoundation#7215)
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent 50fd4e1 commit 767e8f7

File tree

2 files changed

+11
-30
lines changed
  • planning/surround_obstacle_checker

2 files changed

+11
-30
lines changed

planning/surround_obstacle_checker/include/surround_obstacle_checker/node.hpp

+7-3
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
#include "surround_obstacle_checker/debug_marker.hpp"
1919
#include "tier4_autoware_utils/ros/logger_level_configure.hpp"
20+
#include "tier4_autoware_utils/ros/polling_subscriber.hpp"
2021

2122
#include <motion_utils/vehicle/vehicle_state_checker.hpp>
2223
#include <rclcpp/rclcpp.hpp>
@@ -110,9 +111,12 @@ class SurroundObstacleCheckerNode : public rclcpp::Node
110111
rclcpp::TimerBase::SharedPtr timer_;
111112

112113
// publisher and subscriber
113-
rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr sub_pointcloud_;
114-
rclcpp::Subscription<PredictedObjects>::SharedPtr sub_dynamic_objects_;
115-
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odometry_;
114+
tier4_autoware_utils::InterProcessPollingSubscriber<nav_msgs::msg::Odometry> sub_odometry_{
115+
this, "~/input/odometry"};
116+
tier4_autoware_utils::InterProcessPollingSubscriber<sensor_msgs::msg::PointCloud2>
117+
sub_pointcloud_{this, "~/input/pointcloud"};
118+
tier4_autoware_utils::InterProcessPollingSubscriber<PredictedObjects> sub_dynamic_objects_{
119+
this, "~/input/objects"};
116120
rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticStatus>::SharedPtr pub_stop_reason_;
117121
rclcpp::Publisher<VelocityLimitClearCommand>::SharedPtr pub_clear_velocity_limit_;
118122
rclcpp::Publisher<VelocityLimit>::SharedPtr pub_velocity_limit_;

planning/surround_obstacle_checker/src/node.cpp

+4-27
Original file line numberDiff line numberDiff line change
@@ -206,17 +206,6 @@ SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptio
206206
pub_velocity_limit_ = this->create_publisher<VelocityLimit>(
207207
"~/output/max_velocity", rclcpp::QoS{1}.transient_local());
208208

209-
// Subscribers
210-
sub_pointcloud_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
211-
"~/input/pointcloud", rclcpp::SensorDataQoS(),
212-
std::bind(&SurroundObstacleCheckerNode::onPointCloud, this, std::placeholders::_1));
213-
sub_dynamic_objects_ = this->create_subscription<PredictedObjects>(
214-
"~/input/objects", 1,
215-
std::bind(&SurroundObstacleCheckerNode::onDynamicObjects, this, std::placeholders::_1));
216-
sub_odometry_ = this->create_subscription<nav_msgs::msg::Odometry>(
217-
"~/input/odometry", 1,
218-
std::bind(&SurroundObstacleCheckerNode::onOdometry, this, std::placeholders::_1));
219-
220209
// Parameter callback
221210
set_param_res_ = this->add_on_set_parameters_callback(
222211
std::bind(&SurroundObstacleCheckerNode::onParam, this, std::placeholders::_1));
@@ -282,6 +271,10 @@ rcl_interfaces::msg::SetParametersResult SurroundObstacleCheckerNode::onParam(
282271

283272
void SurroundObstacleCheckerNode::onTimer()
284273
{
274+
odometry_ptr_ = sub_odometry_.takeData();
275+
pointcloud_ptr_ = sub_pointcloud_.takeData();
276+
object_ptr_ = sub_dynamic_objects_.takeData();
277+
285278
if (!odometry_ptr_) {
286279
RCLCPP_INFO_THROTTLE(
287280
this->get_logger(), *this->get_clock(), 5000 /* ms */, "waiting for current velocity...");
@@ -377,22 +370,6 @@ void SurroundObstacleCheckerNode::onTimer()
377370
debug_ptr_->publish();
378371
}
379372

380-
void SurroundObstacleCheckerNode::onPointCloud(
381-
const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
382-
{
383-
pointcloud_ptr_ = msg;
384-
}
385-
386-
void SurroundObstacleCheckerNode::onDynamicObjects(const PredictedObjects::ConstSharedPtr msg)
387-
{
388-
object_ptr_ = msg;
389-
}
390-
391-
void SurroundObstacleCheckerNode::onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg)
392-
{
393-
odometry_ptr_ = msg;
394-
}
395-
396373
std::optional<Obstacle> SurroundObstacleCheckerNode::getNearestObstacle() const
397374
{
398375
const auto nearest_pointcloud = getNearestObstacleByPointCloud();

0 commit comments

Comments
 (0)