Skip to content

Commit

Permalink
Set planner_id in reponses with OMPL interface (#2724)
Browse files Browse the repository at this point in the history
This avoids a warning `PlanningPipeline::generatePlan()`.

Signed-off-by: Gaël Écorchard <gael@km-robotics.cz>
Co-authored-by: Gaël Écorchard <gael@km-robotics.cz>
  • Loading branch information
galou and Gaël Écorchard authored Mar 5, 2024
1 parent c112941 commit 57fd700
Showing 1 changed file with 2 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -771,6 +771,7 @@ void ModelBasedPlanningContext::postSolve()

void ModelBasedPlanningContext::solve(planning_interface::MotionPlanResponse& res)
{
res.planner_id = request_.planner_id;
res.error_code = solve(request_.allowed_planning_time, request_.num_planning_attempts);
if (res.error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
{
Expand Down Expand Up @@ -800,6 +801,7 @@ void ModelBasedPlanningContext::solve(planning_interface::MotionPlanResponse& re

void ModelBasedPlanningContext::solve(planning_interface::MotionPlanDetailedResponse& res)
{
res.planner_id = request_.planner_id;
moveit_msgs::msg::MoveItErrorCodes moveit_result =
solve(request_.allowed_planning_time, request_.num_planning_attempts);
if (moveit_result.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
Expand Down

0 comments on commit 57fd700

Please sign in to comment.