Skip to content

Commit 2ee7ac4

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 5887eb0 commit 2ee7ac4

File tree

1 file changed

+1
-1
lines changed

1 file changed

+1
-1
lines changed

moveit_planners/ompl/ompl_interface/src/model_based_planning_context.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -805,7 +805,7 @@ void ModelBasedPlanningContext::solve(planning_interface::MotionPlanDetailedResp
805805
if (moveit_result.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
806806
{
807807
RCLCPP_INFO(getLogger(), "Unable to solve the planning problem");
808-
res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
808+
res.error_code = moveit_result;
809809
return;
810810
}
811811

0 commit comments

Comments
 (0)