Autoware.Auto
behavior_planner.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 BEHAVIOR_PLANNER__BEHAVIOR_PLANNER_HPP_
20 #define BEHAVIOR_PLANNER__BEHAVIOR_PLANNER_HPP_
21 
24 
25 // Autoware packages
26 #include <common/types.hpp>
27 #include <autoware_auto_msgs/msg/route.hpp>
28 #include <autoware_auto_msgs/msg/trajectory.hpp>
29 #include <autoware_auto_msgs/msg/vehicle_state_command.hpp>
30 #include <autoware_auto_msgs/msg/vehicle_kinematic_state.hpp>
31 
32 // lanelet headers
33 #include <lanelet2_core/LaneletMap.h>
34 
35 // others
36 #include <iostream>
37 #include <vector>
38 
39 namespace autoware
40 {
43 {
44 
45 // TODO(mitsudome-r): extract this into common library to be used
46 // both in behavior planner and global planner
47 namespace PrimitiveType
48 {
49 constexpr const char ParkingSpot[] = "parking_spot";
50 constexpr const char DrivableArea[] = "drivable_area";
51 constexpr const char Lane[] = "lane";
52 } // namespace PrimitiveType
53 
54 
56 using autoware_auto_msgs::msg::MapPrimitive;
59 using autoware_auto_msgs::msg::VehicleStateCommand;
60 
64 
66 {
70 };
71 
74 enum class ParkingDirection
75 {
76  HEAD_IN,
77  TOE_IN
78 };
79 
81 {
84 };
85 
88 class BEHAVIOR_PLANNER_PUBLIC BehaviorPlanner
89 {
90 public:
91  explicit BehaviorPlanner(const PlannerConfig & config);
92 
93  void set_route(const Route & route, const lanelet::LaneletMapPtr & lanelet_map_ptr);
94  void clear_route();
95  void set_next_subroute();
96 
97  bool8_t is_route_ready();
98 
99  bool8_t needs_new_trajectory(const State & state);
100  TrajectoryPoint get_sub_goal();
101  bool8_t has_arrived_goal(const State & state);
102  bool8_t has_arrived_subroute_goal(const State & state);
103 
104  bool8_t is_vehicle_stopped(const State & state);
105 
106  RouteWithType get_current_subroute(const State & ego_state);
107  PlannerType get_planner_type();
108  uchar8_t get_desired_gear(const State & state);
109  std::vector<RouteWithType> get_subroutes();
110 
111  // relay to trajectory_manager
112  bool8_t is_trajectory_ready();
113  void set_trajectory(const Trajectory & trajectory);
114  Trajectory get_trajectory(const State & state);
115  size_t get_remaining_length(const State & state);
116 
117 private:
118  RouteWithType get_current_subroute();
119 
124  ParkingDirection get_parking_direction(
125  const TrajectoryPoint & parking_point,
126  const TrajectoryPoint & closest_lane_point);
127  std::vector<RouteWithType> m_subroutes;
128  std::size_t m_current_subroute;
129 
130  // parameters
131  PlannerConfig m_config;
132 
133  // TODO(mitsudome-r): remove the manager once splitting of trajectory gets unnecessary
134  TrajectoryManager m_trajectory_manager;
135 
136  bool8_t m_is_trajectory_complete;
137 };
138 } // namespace behavior_planner
139 } // namespace autoware
140 
141 #endif // BEHAVIOR_PLANNER__BEHAVIOR_PLANNER_HPP_
autoware::behavior_planner::State
autoware_auto_msgs::msg::VehicleKinematicState State
Definition: behavior_planner.hpp:58
autoware::behavior_planner::PlannerType
PlannerType
Definition: behavior_planner.hpp:65
autoware::behavior_planner::PrimitiveType::DrivableArea
constexpr const char DrivableArea[]
Definition: behavior_planner.hpp:50
motion::motion_testing_nodes::TrajectoryPoint
autoware_auto_msgs::msg::TrajectoryPoint TrajectoryPoint
Definition: motion_testing_publisher.hpp:36
autoware::trajectory_spoofer::VehicleKinematicState
autoware_auto_msgs::msg::VehicleKinematicState VehicleKinematicState
Definition: trajectory_spoofer.hpp:44
types.hpp
This file includes common type definition.
behavior_planner
Definition: behavior_planner.launch.py:1
autoware::behavior_planner::UNKNOWN
@ UNKNOWN
Definition: behavior_planner.hpp:69
autoware::behavior_planner::RouteWithType::planner_type
PlannerType planner_type
Definition: behavior_planner.hpp:83
autoware::motion::planning::parking_planner_nodes::Route
autoware_auto_msgs::msg::Route Route
Definition: parking_planner_node.hpp:60
autoware::behavior_planner::ParkingDirection::HEAD_IN
@ HEAD_IN
Front of the vehicle is facing away from the entrance.
autoware::behavior_planner::TrajectoryManager
Class that splits trajectory at gear changing points and publish them separately.
Definition: trajectory_manager.hpp:60
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:39
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::behavior_planner::BehaviorPlanner
Class that contains core functions of the behavior planner.
Definition: behavior_planner.hpp:88
autoware::common::types::uchar8_t
unsigned char uchar8_t
Definition: types.hpp:41
autoware::behavior_planner::RouteWithType::route
Route route
Definition: behavior_planner.hpp:82
autoware::behavior_planner::LANE
@ LANE
Definition: behavior_planner.hpp:67
autoware::behavior_planner::PlannerConfig
Definition: trajectory_manager.hpp:45
trajectory_manager.hpp
This file defines the behavior_planner class.
autoware::behavior_planner::ParkingDirection
ParkingDirection
Enum representing the direction that a vehicle will park in a parking spot relative to the spot's ent...
Definition: behavior_planner.hpp:74
autoware::behavior_planner::PrimitiveType::ParkingSpot
constexpr const char ParkingSpot[]
Definition: behavior_planner.hpp:49
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:45
autoware::behavior_planner::RouteWithType
Definition: behavior_planner.hpp:80
autoware::behavior_planner::PARKING
@ PARKING
Definition: behavior_planner.hpp:68
visibility_control.hpp
autoware::behavior_planner::ParkingDirection::TOE_IN
@ TOE_IN
Rear of the vehicle is facing away from the entrance.
motion::motion_common::Trajectory
autoware_auto_msgs::msg::Trajectory Trajectory
Definition: motion_common.hpp:37
autoware::behavior_planner::PrimitiveType::Lane
constexpr const char Lane[]
Definition: behavior_planner.hpp:51