From 27763db6b451e45e53e2e013f0088c61e15d0b5e Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Wed, 29 Nov 2023 13:18:05 +0900 Subject: [PATCH] fix(simple pure pursuit): last stop (#39) --- .../simple_pure_pursuit/src/simple_pure_pursuit.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/docker/aichallenge/aichallenge_ws/src/aichallenge_submit/autoware_micro/simple_pure_pursuit/src/simple_pure_pursuit.cpp b/docker/aichallenge/aichallenge_ws/src/aichallenge_submit/autoware_micro/simple_pure_pursuit/src/simple_pure_pursuit.cpp index 8ecbd5a..aa3ac2b 100644 --- a/docker/aichallenge/aichallenge_ws/src/aichallenge_submit/autoware_micro/simple_pure_pursuit/src/simple_pure_pursuit.cpp +++ b/docker/aichallenge/aichallenge_ws/src/aichallenge_submit/autoware_micro/simple_pure_pursuit/src/simple_pure_pursuit.cpp @@ -64,6 +64,8 @@ void SimplePurePursuit::onTimer() if ( (closet_traj_point_idx == trajectory_->points.size() - 1) || (trajectory_->points.size() <= 5)) { + cmd.longitudinal.speed = 0.0; + cmd.longitudinal.acceleration = -10.0; RCLCPP_INFO_THROTTLE(get_logger(), *get_clock(), 1000 /*ms*/, "reached to the goal"); } else { // get closest trajectory point from current position