@@ -321,6 +321,8 @@ void FreespacePlannerNode::onRoute(const LaneletRoute::ConstSharedPtr msg)
321
321
goal_pose_.header = msg->header ;
322
322
goal_pose_.pose = msg->goal_pose ;
323
323
324
+ is_new_parking_cycle_ = true ;
325
+
324
326
reset ();
325
327
}
326
328
@@ -447,13 +449,16 @@ void FreespacePlannerNode::onTimer()
447
449
// Must stop before replanning any new trajectory
448
450
const bool is_reset_required = !reset_in_progress_ && isPlanRequired ();
449
451
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
+ }
457
462
458
463
reset ();
459
464
@@ -476,6 +481,7 @@ void FreespacePlannerNode::onTimer()
476
481
477
482
// StopTrajectory
478
483
if (trajectory_.points .size () <= 1 ) {
484
+ is_new_parking_cycle_ = false ;
479
485
return ;
480
486
}
481
487
@@ -487,6 +493,8 @@ void FreespacePlannerNode::onTimer()
487
493
trajectory_pub_->publish (partial_trajectory_);
488
494
debug_pose_array_pub_->publish (trajectory2PoseArray (trajectory_));
489
495
debug_partial_pose_array_pub_->publish (trajectory2PoseArray (partial_trajectory_));
496
+
497
+ is_new_parking_cycle_ = false ;
490
498
}
491
499
492
500
void FreespacePlannerNode::planTrajectory ()
0 commit comments