Skip to content

Commit

Permalink
Allow path end pose deviation revive (ros-navigation#4065)
Browse files Browse the repository at this point in the history
* Support stitching paths in compute path to poses

* Update nav2_planner/src/planner_server.cpp

Co-authored-by: Steve Macenski <stevenmacenski@gmail.com>

* Rename parameter to allow_path_through_poses_goal_deviation

* Fix description

* restore nav2_params

* missing whitespace

* lint fix

* removed parameter

Signed-off-by: gg <josho.wallace@gmail.com>

* Update planner_server.hpp

* Update planner_server.cpp

---------

Signed-off-by: gg <josho.wallace@gmail.com>
Co-authored-by: pepisg <pedro.gonzalez@eia.edu.co>
Co-authored-by: Pedro Alejandro González <71234974+pepisg@users.noreply.github.com>
Co-authored-by: Steve Macenski <stevenmacenski@gmail.com>
Signed-off-by: Brice <brice.renaudeau@gmail.com>
  • Loading branch information
4 people authored and BriceRenaudeau committed Jan 29, 2024
1 parent c290215 commit f3e8c2c
Showing 1 changed file with 4 additions and 1 deletion.
5 changes: 4 additions & 1 deletion nav2_planner/src/planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -400,7 +400,10 @@ void PlannerServer::computePlanThroughPoses()
if (i == 0) {
curr_start = start;
} else {
curr_start = goal->goals[i - 1];
// pick the end of the last planning task as the start for the next one
// to allow for path tolerance deviations
curr_start = concat_path.poses.back();
curr_start.header = concat_path.header;
}
curr_goal = goal->goals[i];

Expand Down

0 comments on commit f3e8c2c

Please sign in to comment.