45 local_planner_started_ =
false;
47 return ReactionResult(event,
"", moveit_msgs::msg::MoveItErrorCodes::SUCCESS,
51 return ReactionResult(event,
"Do nothing", moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
54 if (!local_planner_started_)
56 local_planner_started_ =
true;
57 return ReactionResult(event,
"", moveit_msgs::msg::MoveItErrorCodes::SUCCESS,
60 return ReactionResult(event,
"", moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
63 return ReactionResult(event,
"Global planner failed to find a solution",
64 moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED);
67 return ReactionResult(event,
"", moveit_msgs::msg::MoveItErrorCodes::SUCCESS,
71 return ReactionResult(event,
"Local planner failed to find a solution",
72 moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED);
75 return ReactionResult(event,
"Unknown event", moveit_msgs::msg::MoveItErrorCodes::FAILURE,
82 return ReactionResult(event,
"'Single-Plan-Execution' plugin cannot handle events given as string.",
83 moveit_msgs::msg::MoveItErrorCodes::FAILURE);
87 #include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
ReactionResult react(const HybridPlanningEvent &event) override
@ SEND_LOCAL_SOLVER_REQUEST
@ SEND_GLOBAL_SOLVER_REQUEST
@ GLOBAL_SOLUTION_AVAILABLE
@ GLOBAL_PLANNING_ACTION_SUCCESSFUL
@ GLOBAL_PLANNING_ACTION_ABORTED
@ HYBRID_PLANNING_REQUEST_RECEIVED
@ LOCAL_PLANNING_ACTION_SUCCESSFUL
@ LOCAL_PLANNING_ACTION_ABORTED