Skip to content

Commit 441b544

Browse files
author
Gaël Écorchard
committed
Set planner_id in reponses with OMPL interface
This avoids a warning `PlanningPipeline::generatePlan()`. Signed-off-by: Gaël Écorchard <gael@km-robotics.cz>
1 parent 5887eb0 commit 441b544

File tree

1 file changed

+2
-0
lines changed

1 file changed

+2
-0
lines changed

moveit_planners/ompl/ompl_interface/src/model_based_planning_context.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -771,6 +771,7 @@ void ModelBasedPlanningContext::postSolve()
771771

772772
void ModelBasedPlanningContext::solve(planning_interface::MotionPlanResponse& res)
773773
{
774+
res.planner_id = request_.planner_id;
774775
res.error_code = solve(request_.allowed_planning_time, request_.num_planning_attempts);
775776
if (res.error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
776777
{
@@ -800,6 +801,7 @@ void ModelBasedPlanningContext::solve(planning_interface::MotionPlanResponse& re
800801

801802
void ModelBasedPlanningContext::solve(planning_interface::MotionPlanDetailedResponse& res)
802803
{
804+
res.planner_id = request_.planner_id;
803805
moveit_msgs::msg::MoveItErrorCodes moveit_result =
804806
solve(request_.allowed_planning_time, request_.num_planning_attempts);
805807
if (moveit_result.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)

0 commit comments

Comments
 (0)