Commit 441b544 Gaël Écorchard
committed
1 parent 5887eb0 commit 441b544 Copy full SHA for 441b544
File tree 1 file changed +2
-0
lines changed
moveit_planners/ompl/ompl_interface/src
1 file changed +2
-0
lines changed Original file line number Diff line number Diff line change @@ -771,6 +771,7 @@ void ModelBasedPlanningContext::postSolve()
771
771
772
772
void ModelBasedPlanningContext::solve (planning_interface::MotionPlanResponse& res)
773
773
{
774
+ res.planner_id = request_.planner_id ;
774
775
res.error_code = solve (request_.allowed_planning_time , request_.num_planning_attempts );
775
776
if (res.error_code .val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
776
777
{
@@ -800,6 +801,7 @@ void ModelBasedPlanningContext::solve(planning_interface::MotionPlanResponse& re
800
801
801
802
void ModelBasedPlanningContext::solve (planning_interface::MotionPlanDetailedResponse& res)
802
803
{
804
+ res.planner_id = request_.planner_id ;
803
805
moveit_msgs::msg::MoveItErrorCodes moveit_result =
804
806
solve (request_.allowed_planning_time , request_.num_planning_attempts );
805
807
if (moveit_result.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
You can’t perform that action at this time.
0 commit comments