Skip to content

Commit f9a7366

Browse files
committed
feat(surround_obstacle_checker): use polling subscriber
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent 6fe9fc6 commit f9a7366

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
@@ -207,17 +207,6 @@ SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptio
207207
pub_velocity_limit_ = this->create_publisher<VelocityLimit>(
208208
"~/output/max_velocity", rclcpp::QoS{1}.transient_local());
209209

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

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

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

0 commit comments

Comments
 (0)