39 const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"hybrid_planning_manager");
61 local_planner_started_ =
false;
62 return ReactionResult(event,
"", moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
65 return ReactionResult(event,
"Do nothing", moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
68 if (!local_planner_started_)
74 local_planner_started_ =
true;
76 return ReactionResult(event,
"", moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
79 return ReactionResult(event,
"Global planner failed to find a solution",
80 moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED);
84 return ReactionResult(event,
"", moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
87 return ReactionResult(event,
"Local planner failed to find a solution",
88 moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED);
91 return ReactionResult(event,
"Unknown event", moveit_msgs::msg::MoveItErrorCodes::FAILURE);
97 return ReactionResult(event,
"'Single-Plan-Execution' plugin cannot handle events given as string.",
98 moveit_msgs::msg::MoveItErrorCodes::FAILURE);
102 #include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
std::shared_ptr< HybridPlanningManager > hybrid_planning_manager_
bool initialize(const std::shared_ptr< HybridPlanningManager > &hybrid_planning_manager) override
ReactionResult react(const HybridPlanningEvent &event) override
@ GLOBAL_SOLUTION_AVAILABLE
@ GLOBAL_PLANNING_ACTION_SUCCESSFUL
@ GLOBAL_PLANNING_ACTION_ABORTED
@ HYBRID_PLANNING_REQUEST_RECEIVED
@ LOCAL_PLANNING_ACTION_SUCCESSFUL
@ LOCAL_PLANNING_ACTION_ABORTED
const rclcpp::Logger LOGGER