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

Pass GlobalPlanner failing to HybridPlanningManager #2

Merged
merged 1 commit into from
Nov 23, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
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 @@ -119,18 +119,22 @@ void GlobalPlannerComponent::globalPlanningRequestCallback(
{
// Plan global trajectory
moveit_msgs::msg::MotionPlanResponse planning_solution = global_planner_instance_->plan(goal_handle);

// Publish global planning solution to the local planner
global_trajectory_pub_->publish(planning_solution);

// Send action response
auto result = std::make_shared<moveit_msgs::action::GlobalPlanner::Result>();
result->response = planning_solution;
goal_handle->succeed(result);

// Save newest planning solution
last_global_solution_ = planning_solution; // TODO(sjahr) Add Service to expose this

if (planning_solution.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS) {
// Publish global planning solution to the local planner
global_trajectory_pub_->publish(planning_solution);

// Send action response
auto result = std::make_shared<moveit_msgs::action::GlobalPlanner::Result>();
result->response = planning_solution;
goal_handle->succeed(result);

// Save newest planning solution
last_global_solution_ = planning_solution; // TODO(sjahr) Add Service to expose this
} else {
auto result = std::make_shared<moveit_msgs::action::GlobalPlanner::Result>();
result->response = planning_solution;
goal_handle->abort(result);
}
// Reset the global planner
global_planner_instance_->reset();
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -179,16 +179,24 @@ bool HybridPlanningManager::sendGlobalPlannerAction()
global_goal_options.result_callback =
[this](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::GlobalPlanner>::WrappedResult& global_result) {
// Reaction result from the latest event
ReactionResult reaction_result =
planner_logic_instance_->react(HybridPlanningEvent::GLOBAL_PLANNING_ACTION_FINISHED);
auto result = std::make_shared<moveit_msgs::action::HybridPlanner::Result>();
if (reaction_result.error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
if(global_result.code == rclcpp_action::ResultCode::SUCCEEDED)
{
ReactionResult reaction_result =
planner_logic_instance_->react(HybridPlanningEvent::GLOBAL_PLANNING_ACTION_FINISHED);
auto result = std::make_shared<moveit_msgs::action::HybridPlanner::Result>();
result->error_code.val = reaction_result.error_code.val;
result->error_message = reaction_result.error_message;
if (reaction_result.error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
{
auto result = std::make_shared<moveit_msgs::action::HybridPlanner::Result>();
result->error_code.val = reaction_result.error_code.val;
result->error_message = reaction_result.error_message;
hybrid_planning_goal_handle_->abort(result);
RCLCPP_ERROR(LOGGER, "Hybrid Planning Manager failed to react to '%s'", reaction_result.event.c_str());
}
} else {
auto result = std::make_shared<moveit_msgs::action::HybridPlanner::Result>();
result->error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
result->error_message = "Global planner failed to find a solution";
hybrid_planning_goal_handle_->abort(result);
RCLCPP_ERROR(LOGGER, "Hybrid Planning Manager failed to react to '%s'", reaction_result.event.c_str());
}
};

Expand Down