Autoware.Auto
lane_planner_node.hpp
Go to the documentation of this file.
1 // Copyright 2020 The Autoware Foundation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
18 
19 #ifndef LANE_PLANNER_NODES__LANE_PLANNER_NODE_HPP_
20 #define LANE_PLANNER_NODES__LANE_PLANNER_NODE_HPP_
21 
23 
26 
27 #include <string>
28 #include <memory>
29 
30 namespace autoware
31 {
32 namespace lane_planner_nodes
33 {
34 
40 
44 
47 class LANE_PLANNER_PUBLIC LanePlannerNode : public TrajectoryPlannerNodeBase
48 {
49 public:
53  explicit LanePlannerNode(const rclcpp::NodeOptions & options);
54 
55 private:
56  std::unique_ptr<lane_planner::LanePlanner> m_planner;
57 
59  // Implementer should request for relevent map objects for their planner
60  HADMapService::Request create_map_request(const Route & route) override;
61 
63  // It should return the trajectory and status (SUCCESS, FAIL)
64  Trajectory plan_trajectory(
65  const Route & route,
66  const lanelet::LaneletMapPtr & lanelet_map_ptr) override;
67 };
68 
69 
70 } // namespace lane_planner_nodes
71 } // namespace autoware
72 
73 #endif // LANE_PLANNER_NODES__LANE_PLANNER_NODE_HPP_
double float64_t
Definition: types.hpp:37
decltype(autoware_auto_msgs::msg::TrajectoryPoint::x) Real
Definition: motion_common.hpp:33
float float32_t
Definition: types.hpp:36
autoware_auto_msgs::srv::HADMapService HADMapService
Definition: off_map_obstacles_filter_node.cpp:35
autoware_auto_msgs::msg::Trajectory Trajectory
Definition: motion_common.hpp:37
ROS 2 Node for hello world.
Definition: lane_planner_node.hpp:47
ROS 2 Wrapper Node for Trajectory Planner.
Definition: trajectory_planner_node_base.hpp:58
This file defines the lane_planner class.
Vehicle parameters specifying vehicle&#39;s handling performance.
Definition: control/motion_common/include/motion_common/config.hpp:87
autoware_auto_msgs::msg::Route Route
Definition: parking_planner_node.hpp:60
This file defines the trajectory_planner_node_base_node class.
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24