@@ -95,8 +95,6 @@ ObstacleAvoidancePlanner::ObstacleAvoidancePlanner(const rclcpp::NodeOptions & n
95
95
// interface subscriber
96
96
path_sub_ = create_subscription<Path>(
97
97
" ~/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; });
100
98
101
99
// debug publisher
102
100
debug_extended_traj_pub_ = create_publisher<Trajectory>(" ~/debug/extended_traj" , 1 );
@@ -224,8 +222,16 @@ void ObstacleAvoidancePlanner::onPath(const Path::ConstSharedPtr path_ptr)
224
222
time_keeper_ptr_->init ();
225
223
time_keeper_ptr_->tic (__func__);
226
224
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." );
229
235
return ;
230
236
}
231
237
@@ -245,7 +251,7 @@ void ObstacleAvoidancePlanner::onPath(const Path::ConstSharedPtr path_ptr)
245
251
}
246
252
247
253
// 1. create planner data
248
- const auto planner_data = createPlannerData (*path_ptr);
254
+ const auto planner_data = createPlannerData (*path_ptr, ego_odom_ptr );
249
255
250
256
// 2. generate optimized trajectory
251
257
const auto optimized_traj_points = generateOptimizedTrajectory (planner_data);
@@ -276,13 +282,8 @@ void ObstacleAvoidancePlanner::onPath(const Path::ConstSharedPtr path_ptr)
276
282
published_time_publisher_->publish_if_subscribed (traj_pub_, output_traj_msg.header .stamp );
277
283
}
278
284
279
- bool ObstacleAvoidancePlanner::isDataReady (const Path & path, rclcpp::Clock clock) const
285
+ bool ObstacleAvoidancePlanner::checkInputPath (const Path & path, rclcpp::Clock clock) const
280
286
{
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
-
286
287
if (path.points .size () < 2 ) {
287
288
RCLCPP_INFO_SKIPFIRST_THROTTLE (get_logger (), clock , 5000 , " Path points size is less than 1." );
288
289
return false ;
@@ -297,16 +298,17 @@ bool ObstacleAvoidancePlanner::isDataReady(const Path & path, rclcpp::Clock cloc
297
298
return true ;
298
299
}
299
300
300
- PlannerData ObstacleAvoidancePlanner::createPlannerData (const Path & path) const
301
+ PlannerData ObstacleAvoidancePlanner::createPlannerData (
302
+ const Path & path, const Odometry::ConstSharedPtr ego_odom_ptr) const
301
303
{
302
304
// create planner data
303
305
PlannerData planner_data;
304
306
planner_data.header = path.header ;
305
307
planner_data.traj_points = trajectory_utils::convertToTrajectoryPoints (path.points );
306
308
planner_data.left_bound = path.left_bound ;
307
309
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 ;
310
312
311
313
debug_data_ptr_->ego_pose = planner_data.ego_pose ;
312
314
return planner_data;
0 commit comments