19 #ifndef BEHAVIOR_PLANNER_NODES__BEHAVIOR_PLANNER_NODE_HPP_
20 #define BEHAVIOR_PLANNER_NODES__BEHAVIOR_PLANNER_NODE_HPP_
26 #include <rclcpp/rclcpp.hpp>
27 #include <rclcpp_action/rclcpp_action.hpp>
31 #include <autoware_auto_msgs/action/plan_trajectory.hpp>
32 #include <autoware_auto_msgs/msg/trajectory.hpp>
33 #include <autoware_auto_msgs/msg/trajectory_point.hpp>
34 #include <autoware_auto_msgs/msg/vehicle_kinematic_state.hpp>
35 #include <autoware_auto_msgs/msg/vehicle_state_report.hpp>
36 #include <autoware_auto_msgs/msg/vehicle_state_command.hpp>
37 #include <autoware_auto_msgs/srv/had_map_service.hpp>
38 #include <autoware_auto_msgs/srv/modify_trajectory.hpp>
42 #include <lanelet2_core/LaneletMap.h>
43 #include <tf2_ros/transform_listener.h>
44 #include <tf2_ros/buffer.h>
52 namespace behavior_planner_nodes
57 using autoware_auto_msgs::srv::ModifyTrajectory;
61 using autoware_auto_msgs::msg::VehicleStateCommand;
62 using autoware_auto_msgs::msg::VehicleStateReport;
83 rclcpp_action::Client<PlanTrajectoryAction>::SharedPtr m_lane_planner_client;
84 rclcpp_action::Client<PlanTrajectoryAction>::SharedPtr m_parking_planner_client;
85 rclcpp::Client<HADMapService>::SharedPtr m_map_client;
87 rclcpp::Client<ModifyTrajectory>::SharedPtr m_modify_trajectory_client;
88 rclcpp::Subscription<State>::SharedPtr m_ego_state_sub{};
89 rclcpp::Subscription<Route>::SharedPtr m_route_sub{};
90 rclcpp::Subscription<Trajectory>::SharedPtr m_lane_trajectory_sub{};
91 rclcpp::Subscription<Trajectory>::SharedPtr m_parking_trajectory_sub{};
92 rclcpp::Subscription<VehicleStateReport>::SharedPtr m_vehicle_state_report_sub{};
93 rclcpp::Publisher<Trajectory>::SharedPtr m_trajectory_pub{};
94 rclcpp::Publisher<Trajectory>::SharedPtr m_debug_trajectory_pub{};
95 rclcpp::Publisher<Trajectory>::SharedPtr m_debug_checkpoints_pub{};
96 rclcpp::Publisher<Route>::SharedPtr m_debug_subroute_pub{};
97 rclcpp::Publisher<VehicleStateCommand>::SharedPtr m_vehicle_state_command_pub{};
100 std::unique_ptr<behavior_planner::BehaviorPlanner> m_planner;
103 lanelet::LaneletMapPtr m_lanelet_map_ptr;
104 Route::SharedPtr m_route;
109 bool8_t m_requesting_trajectory;
112 std::shared_ptr<tf2_ros::Buffer> m_tf_buffer;
113 std::shared_ptr<tf2_ros::TransformListener> m_tf_listener;
116 void on_ego_state(
const State::SharedPtr & msg);
117 void on_route(
const Route::SharedPtr & msg);
118 void on_lane_trajectory(
const Trajectory::SharedPtr & msg);
119 void on_parking_trajectory(
const Trajectory::SharedPtr & msg);
120 void on_vehicle_state_report(
const VehicleStateReport::SharedPtr & msg);
121 void map_response(rclcpp::Client<HADMapService>::SharedFuture future);
122 void modify_trajectory_response(rclcpp::Client<ModifyTrajectory>::SharedFuture future);
123 void clear_trajectory_cache();
125 void goal_response_callback(std::shared_future<PlanTrajectoryGoalHandle::SharedPtr> future);
126 void feedback_callback(
127 PlanTrajectoryGoalHandle::SharedPtr goal_handle,
128 const std::shared_ptr<const PlanTrajectoryAction::Feedback> feedback);
129 void result_callback(
const PlanTrajectoryGoalHandle::WrappedResult & result);
135 void request_trajectory(
const RouteWithType & route_with_type);
140 #endif // BEHAVIOR_PLANNER_NODES__BEHAVIOR_PLANNER_NODE_HPP_