Skip to content

Commit 1ff6276

Browse files
ahmeddesokyebrahimvividf
authored andcommitted
fix(freespace_planner): fix motion_velocity_smoother error while parking (autowarefoundation#6713)
* fix(freespace_planner): prevent publishing stop trajectory with only one point in a new parking cycle --------- Signed-off-by: Ahmed Ebrahim <ahmed.ebrahim@leodrive.ai> Signed-off-by: vividf <yihsiang.fang@tier4.jp>
1 parent 1a729a4 commit 1ff6276

File tree

2 files changed

+16
-7
lines changed

2 files changed

+16
-7
lines changed

planning/freespace_planner/include/freespace_planner/freespace_planner_node.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -134,6 +134,7 @@ class FreespacePlannerNode : public rclcpp::Node
134134
size_t target_index_;
135135
bool is_completed_ = false;
136136
bool reset_in_progress_ = false;
137+
bool is_new_parking_cycle_ = true;
137138

138139
LaneletRoute::ConstSharedPtr route_;
139140
OccupancyGrid::ConstSharedPtr occupancy_grid_;

planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp

+15-7
Original file line numberDiff line numberDiff line change
@@ -321,6 +321,8 @@ void FreespacePlannerNode::onRoute(const LaneletRoute::ConstSharedPtr msg)
321321
goal_pose_.header = msg->header;
322322
goal_pose_.pose = msg->goal_pose;
323323

324+
is_new_parking_cycle_ = true;
325+
324326
reset();
325327
}
326328

@@ -447,13 +449,16 @@ void FreespacePlannerNode::onTimer()
447449
// Must stop before replanning any new trajectory
448450
const bool is_reset_required = !reset_in_progress_ && isPlanRequired();
449451
if (is_reset_required) {
450-
// Stop before planning new trajectory
451-
const auto stop_trajectory = partial_trajectory_.points.empty()
452-
? createStopTrajectory(current_pose_)
453-
: createStopTrajectory(partial_trajectory_);
454-
trajectory_pub_->publish(stop_trajectory);
455-
debug_pose_array_pub_->publish(trajectory2PoseArray(stop_trajectory));
456-
debug_partial_pose_array_pub_->publish(trajectory2PoseArray(stop_trajectory));
452+
// Stop before planning new trajectory, except in a new parking cycle as the vehicle already
453+
// stops.
454+
if (!is_new_parking_cycle_) {
455+
const auto stop_trajectory = partial_trajectory_.points.empty()
456+
? createStopTrajectory(current_pose_)
457+
: createStopTrajectory(partial_trajectory_);
458+
trajectory_pub_->publish(stop_trajectory);
459+
debug_pose_array_pub_->publish(trajectory2PoseArray(stop_trajectory));
460+
debug_partial_pose_array_pub_->publish(trajectory2PoseArray(stop_trajectory));
461+
}
457462

458463
reset();
459464

@@ -476,6 +481,7 @@ void FreespacePlannerNode::onTimer()
476481

477482
// StopTrajectory
478483
if (trajectory_.points.size() <= 1) {
484+
is_new_parking_cycle_ = false;
479485
return;
480486
}
481487

@@ -487,6 +493,8 @@ void FreespacePlannerNode::onTimer()
487493
trajectory_pub_->publish(partial_trajectory_);
488494
debug_pose_array_pub_->publish(trajectory2PoseArray(trajectory_));
489495
debug_partial_pose_array_pub_->publish(trajectory2PoseArray(partial_trajectory_));
496+
497+
is_new_parking_cycle_ = false;
490498
}
491499

492500
void FreespacePlannerNode::planTrajectory()

0 commit comments

Comments
 (0)