Skip to content

Commit ec8c5a9

Browse files
takayuki5168KhalilSelyan
authored and
KhalilSelyan
committed
feat(obstacle_avoidance_planner): use polling subscriber (#7213)
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent 7e44745 commit ec8c5a9

File tree

2 files changed

+22
-20
lines changed
  • planning/obstacle_avoidance_planner

2 files changed

+22
-20
lines changed

planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222
#include "obstacle_avoidance_planner/type_alias.hpp"
2323
#include "rclcpp/rclcpp.hpp"
2424
#include "tier4_autoware_utils/ros/logger_level_configure.hpp"
25+
#include "tier4_autoware_utils/ros/polling_subscriber.hpp"
2526
#include "vehicle_info_util/vehicle_info_util.hpp"
2627

2728
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
@@ -83,16 +84,14 @@ class ObstacleAvoidancePlanner : public rclcpp::Node
8384
TrajectoryParam traj_param_{};
8485
EgoNearestParam ego_nearest_param_{};
8586

86-
// variables for subscribers
87-
Odometry::ConstSharedPtr ego_state_ptr_;
88-
8987
// interface publisher
9088
rclcpp::Publisher<Trajectory>::SharedPtr traj_pub_;
9189
rclcpp::Publisher<MarkerArray>::SharedPtr virtual_wall_pub_;
9290

9391
// interface subscriber
9492
rclcpp::Subscription<Path>::SharedPtr path_sub_;
95-
rclcpp::Subscription<Odometry>::SharedPtr odom_sub_;
93+
tier4_autoware_utils::InterProcessPollingSubscriber<Odometry> ego_odom_sub_{
94+
this, "~/input/odometry"};
9695

9796
// debug publisher
9897
rclcpp::Publisher<Trajectory>::SharedPtr debug_extended_traj_pub_;
@@ -113,8 +112,9 @@ class ObstacleAvoidancePlanner : public rclcpp::Node
113112
void resetPreviousData();
114113

115114
// main functions
116-
bool isDataReady(const Path & path, rclcpp::Clock clock) const;
117-
PlannerData createPlannerData(const Path & path) const;
115+
bool checkInputPath(const Path & path, rclcpp::Clock clock) const;
116+
PlannerData createPlannerData(
117+
const Path & path, const Odometry::ConstSharedPtr ego_odom_ptr) const;
118118
std::vector<TrajectoryPoint> generateOptimizedTrajectory(const PlannerData & planner_data);
119119
std::vector<TrajectoryPoint> extendTrajectory(
120120
const std::vector<TrajectoryPoint> & traj_points,

planning/obstacle_avoidance_planner/src/node.cpp

+16-14
Original file line numberDiff line numberDiff line change
@@ -95,8 +95,6 @@ ObstacleAvoidancePlanner::ObstacleAvoidancePlanner(const rclcpp::NodeOptions & n
9595
// interface subscriber
9696
path_sub_ = create_subscription<Path>(
9797
"~/input/path", 1, std::bind(&ObstacleAvoidancePlanner::onPath, this, std::placeholders::_1));
98-
odom_sub_ = create_subscription<Odometry>(
99-
"~/input/odometry", 1, [this](const Odometry::ConstSharedPtr msg) { ego_state_ptr_ = msg; });
10098

10199
// debug publisher
102100
debug_extended_traj_pub_ = create_publisher<Trajectory>("~/debug/extended_traj", 1);
@@ -224,8 +222,16 @@ void ObstacleAvoidancePlanner::onPath(const Path::ConstSharedPtr path_ptr)
224222
time_keeper_ptr_->init();
225223
time_keeper_ptr_->tic(__func__);
226224

227-
// check if data is ready and valid
228-
if (!isDataReady(*path_ptr, *get_clock())) {
225+
// check if input path is valid
226+
if (!checkInputPath(*path_ptr, *get_clock())) {
227+
return;
228+
}
229+
230+
// check if ego's odometry is valid
231+
const auto ego_odom_ptr = ego_odom_sub_.takeData();
232+
if (!ego_odom_ptr) {
233+
RCLCPP_INFO_SKIPFIRST_THROTTLE(
234+
get_logger(), *get_clock(), 5000, "Waiting for ego pose and twist.");
229235
return;
230236
}
231237

@@ -245,7 +251,7 @@ void ObstacleAvoidancePlanner::onPath(const Path::ConstSharedPtr path_ptr)
245251
}
246252

247253
// 1. create planner data
248-
const auto planner_data = createPlannerData(*path_ptr);
254+
const auto planner_data = createPlannerData(*path_ptr, ego_odom_ptr);
249255

250256
// 2. generate optimized trajectory
251257
const auto optimized_traj_points = generateOptimizedTrajectory(planner_data);
@@ -276,13 +282,8 @@ void ObstacleAvoidancePlanner::onPath(const Path::ConstSharedPtr path_ptr)
276282
published_time_publisher_->publish_if_subscribed(traj_pub_, output_traj_msg.header.stamp);
277283
}
278284

279-
bool ObstacleAvoidancePlanner::isDataReady(const Path & path, rclcpp::Clock clock) const
285+
bool ObstacleAvoidancePlanner::checkInputPath(const Path & path, rclcpp::Clock clock) const
280286
{
281-
if (!ego_state_ptr_) {
282-
RCLCPP_INFO_SKIPFIRST_THROTTLE(get_logger(), clock, 5000, "Waiting for ego pose and twist.");
283-
return false;
284-
}
285-
286287
if (path.points.size() < 2) {
287288
RCLCPP_INFO_SKIPFIRST_THROTTLE(get_logger(), clock, 5000, "Path points size is less than 1.");
288289
return false;
@@ -297,16 +298,17 @@ bool ObstacleAvoidancePlanner::isDataReady(const Path & path, rclcpp::Clock cloc
297298
return true;
298299
}
299300

300-
PlannerData ObstacleAvoidancePlanner::createPlannerData(const Path & path) const
301+
PlannerData ObstacleAvoidancePlanner::createPlannerData(
302+
const Path & path, const Odometry::ConstSharedPtr ego_odom_ptr) const
301303
{
302304
// create planner data
303305
PlannerData planner_data;
304306
planner_data.header = path.header;
305307
planner_data.traj_points = trajectory_utils::convertToTrajectoryPoints(path.points);
306308
planner_data.left_bound = path.left_bound;
307309
planner_data.right_bound = path.right_bound;
308-
planner_data.ego_pose = ego_state_ptr_->pose.pose;
309-
planner_data.ego_vel = ego_state_ptr_->twist.twist.linear.x;
310+
planner_data.ego_pose = ego_odom_ptr->pose.pose;
311+
planner_data.ego_vel = ego_odom_ptr->twist.twist.linear.x;
310312

311313
debug_data_ptr_->ego_pose = planner_data.ego_pose;
312314
return planner_data;

0 commit comments

Comments
 (0)