41#include <rclcpp/rclcpp.hpp>
42#include <moveit_msgs/msg/move_it_error_codes.hpp>
55 switch (planning_event)
58 event =
"Hybrid planning request received";
61 event =
"Global planning action successful";
64 event =
"Global planning action aborted";
67 event =
"Global planning action canceled";
70 event =
"Global solution available";
73 event =
"Local planning action successful";
76 event =
"Local planning action aborted";
79 event =
"Local planning action canceled";
82 event =
"Undefined event";
85 event =
"Global planning action rejected";
88 event =
"Local planning action rejected";
a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from...
virtual bool initialize()
virtual ReactionResult react(const std::string &event)=0
PlannerLogicInterface(const PlannerLogicInterface &)=default
PlannerLogicInterface & operator=(const PlannerLogicInterface &)=default
PlannerLogicInterface()=default
PlannerLogicInterface(PlannerLogicInterface &&)=default
virtual ReactionResult react(const HybridPlanningEvent &event)=0
virtual ~PlannerLogicInterface()=default
PlannerLogicInterface & operator=(PlannerLogicInterface &&)=default
@ GLOBAL_SOLUTION_AVAILABLE
@ GLOBAL_PLANNING_ACTION_SUCCESSFUL
@ GLOBAL_PLANNING_ACTION_ABORTED
@ HYBRID_PLANNING_REQUEST_RECEIVED
@ LOCAL_PLANNING_ACTION_REJECTED
@ GLOBAL_PLANNING_ACTION_REJECTED
@ LOCAL_PLANNING_ACTION_SUCCESSFUL
@ LOCAL_PLANNING_ACTION_ABORTED
@ GLOBAL_PLANNING_ACTION_CANCELED
@ LOCAL_PLANNING_ACTION_CANCELED
ReactionResult(const HybridPlanningEvent &planning_event, const std::string &error_msg, const int error_code, const HybridPlanningAction &action=HybridPlanningAction::DO_NOTHING)
moveit::core::MoveItErrorCode error_code
ReactionResult(const std::string &event, const std::string &error_msg, const int error_code, const HybridPlanningAction &action=HybridPlanningAction::DO_NOTHING)
HybridPlanningAction action
std::string error_message