19 #ifndef TRAJECTORY_PLANNER_NODE_BASE__TRAJECTORY_PLANNER_NODE_BASE_HPP_
20 #define TRAJECTORY_PLANNER_NODE_BASE__TRAJECTORY_PLANNER_NODE_BASE_HPP_
25 #include <rclcpp/rclcpp.hpp>
26 #include <rclcpp_action/rclcpp_action.hpp>
29 #include <autoware_auto_msgs/srv/had_map_service.hpp>
30 #include <autoware_auto_msgs/action/plan_trajectory.hpp>
31 #include <autoware_auto_msgs/msg/route.hpp>
35 #include <lanelet2_core/LaneletMap.h>
41 namespace trajectory_planner_node_base
66 const std::string & node_name,
67 const std::string & action_server_name,
68 const rclcpp::NodeOptions & options);
73 virtual HADMapService::Request create_map_request(
const Route & route) = 0;
79 const lanelet::LaneletMapPtr & lanelet_map_ptr) = 0;
82 using PlanTrajectoryAction = autoware_auto_msgs::action::PlanTrajectory;
83 using GoalHandle = rclcpp_action::ServerGoalHandle<PlanTrajectoryAction>;
86 rclcpp_action::Server<PlanTrajectoryAction>::SharedPtr m_planner_server;
87 rclcpp::Client<HADMapService>::SharedPtr m_map_client;
90 TRAJECTORY_PLANNER_NODE_BASE_LOCAL rclcpp_action::GoalResponse handle_goal(
91 const rclcpp_action::GoalUUID & uuid,
92 const std::shared_ptr<const PlanTrajectoryAction::Goal> goal);
93 TRAJECTORY_PLANNER_NODE_BASE_LOCAL rclcpp_action::CancelResponse handle_cancel(
94 const std::shared_ptr<GoalHandle> goal_handle);
95 TRAJECTORY_PLANNER_NODE_BASE_LOCAL
void handle_accepted(
96 const std::shared_ptr<GoalHandle> goal_handle);
97 void map_response(rclcpp::Client<HADMapService>::SharedFuture future);
102 std::shared_ptr<GoalHandle> m_goal_handle{
nullptr};
106 void start_planning();
107 void stop_planning();
113 #endif // TRAJECTORY_PLANNER_NODE_BASE__TRAJECTORY_PLANNER_NODE_BASE_HPP_