Skip to content

Commit 02ec743

Browse files
author
Gaël Écorchard
committed
Do not overwrite the error code with OMPL interface
In case of failure, set the error code to the one returned by the planning pipeline's `solve` method rather than overwriting it with `PLANNING_FAILED`. Signed-off-by: Gaël Écorchard <gael@km-robotics.cz>
1 parent aeb03f7 commit 02ec743

File tree

1 file changed

+2
-5
lines changed

1 file changed

+2
-5
lines changed

moveit_planners/ompl/ompl_interface/src/model_based_planning_context.cpp

+2-5
Original file line numberDiff line numberDiff line change
@@ -802,12 +802,10 @@ void ModelBasedPlanningContext::solve(planning_interface::MotionPlanResponse& re
802802
void ModelBasedPlanningContext::solve(planning_interface::MotionPlanDetailedResponse& res)
803803
{
804804
res.planner_id = request_.planner_id;
805-
moveit_msgs::msg::MoveItErrorCodes moveit_result =
806-
solve(request_.allowed_planning_time, request_.num_planning_attempts);
807-
if (moveit_result.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
805+
res.error_code = solve(request_.allowed_planning_time, request_.num_planning_attempts);
806+
if (res.error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
808807
{
809808
RCLCPP_INFO(getLogger(), "Unable to solve the planning problem");
810-
res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
811809
return;
812810
}
813811

@@ -845,7 +843,6 @@ void ModelBasedPlanningContext::solve(planning_interface::MotionPlanDetailedResp
845843

846844
RCLCPP_DEBUG(getLogger(), "%s: Returning successful solution with %lu states", getName().c_str(),
847845
getOMPLSimpleSetup()->getSolutionPath().getStateCount());
848-
res.error_code.val = moveit_result.val;
849846
}
850847

851848
const moveit_msgs::msg::MoveItErrorCodes ModelBasedPlanningContext::solve(double timeout, unsigned int count)

0 commit comments

Comments
 (0)