42 #include <rclcpp/rclcpp.hpp>
43 #include <rclcpp_action/rclcpp_action.hpp>
47 #include <moveit_msgs/action/global_planner.hpp>
48 #include <moveit_msgs/msg/motion_plan_response.hpp>
68 virtual bool initialize(
const rclcpp::Node::SharedPtr& node) = 0;
75 virtual moveit_msgs::msg::MotionPlanResponse
plan(
76 const std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::GlobalPlanner>> global_goal_handle) = 0;
82 virtual bool reset() noexcept = 0;
virtual moveit_msgs::msg::MotionPlanResponse plan(const std::shared_ptr< rclcpp_action::ServerGoalHandle< moveit_msgs::action::GlobalPlanner >> global_goal_handle)=0
GlobalPlannerInterface & operator=(GlobalPlannerInterface &&)=default
GlobalPlannerInterface & operator=(const GlobalPlannerInterface &)=default
GlobalPlannerInterface(GlobalPlannerInterface &&)=default
virtual bool initialize(const rclcpp::Node::SharedPtr &node)=0
virtual bool reset() noexcept=0
GlobalPlannerInterface(const GlobalPlannerInterface &)=default
GlobalPlannerInterface()=default
virtual ~GlobalPlannerInterface()=default