Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Map ompl's APPROXIMATE_SOLUTION -> TIMED_OUT / PLANNING_FAILED #2455

Merged
merged 3 commits into from
Oct 17, 2023
Merged
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -976,7 +976,7 @@ void ompl_interface::ModelBasedPlanningContext::unregisterTerminationCondition()
int32_t ompl_interface::ModelBasedPlanningContext::logPlannerStatus(const og::SimpleSetupPtr& ompl_simple_setup)
{
auto result = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
ompl::base::PlannerStatus ompl_status = ompl_simple_setup->getLastPlannerStatus();
const ompl::base::PlannerStatus ompl_status = ompl_simple_setup->getLastPlannerStatus();
switch (ompl::base::PlannerStatus::StatusType(ompl_status))
{
case ompl::base::PlannerStatus::UNKNOWN:
Expand All @@ -1000,8 +1000,17 @@ int32_t ompl_interface::ModelBasedPlanningContext::logPlannerStatus(const og::Si
result = moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT;
break;
case ompl::base::PlannerStatus::APPROXIMATE_SOLUTION:
RCLCPP_WARN(LOGGER, "Solution is approximate");
result = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
// timeout is a common reason for APPROXIMATE_SOLUTION
if (ompl_simple_setup->getLastPlanComputationTime() > request_.allowed_planning_time)
{
RCLCPP_WARN(LOGGER, "Planning timed out");
rhaschke marked this conversation as resolved.
Show resolved Hide resolved
result = moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT;
}
else
{
RCLCPP_WARN(LOGGER, "Solution is approximate");
result = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
}
break;
case ompl::base::PlannerStatus::EXACT_SOLUTION:
result = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
Expand Down