Autoware.Auto
lane_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 LANE_PLANNER__LANE_PLANNER_HPP_
20 #define LANE_PLANNER__LANE_PLANNER_HPP_
21 
23 
24 #include <autoware_auto_msgs/msg/vehicle_kinematic_state.hpp>
25 #include <autoware_auto_msgs/msg/trajectory.hpp>
26 #include <autoware_auto_msgs/msg/route.hpp>
27 #include <common/types.hpp>
28 #include <motion_common/config.hpp>
29 
31 
32 #include <lanelet2_core/LaneletMap.h>
33 #include <lanelet2_core/primitives/Point.h>
34 
35 #include <iostream>
36 #include <vector>
37 
38 namespace autoware
39 {
41 namespace lane_planner
42 {
45 
47 using TrajectoryPoints = std::vector<TrajectoryPoint>;
51 using Heading = decltype(decltype(State::state)::heading);
52 
55 
59 
60 using lanelet::LaneletMapConstPtr;
61 
62 // utility functions
63 LANE_PLANNER_PUBLIC float32_t distance2d(const TrajectoryPoint & p1, const TrajectoryPoint & p2);
64 
65 // calculate curvature by circle fitting to three points
66 LANE_PLANNER_PUBLIC float32_t calculate_curvature(
67  const TrajectoryPoint & p1, const TrajectoryPoint & p2,
68  const TrajectoryPoint & p3);
69 
70 struct LANE_PLANNER_PUBLIC LanePlannerConfig
71 {
73 };
74 
76 class LANE_PLANNER_PUBLIC LanePlanner
77 {
78 public:
79  explicit LanePlanner(
80  const VehicleConfig & vehicle_param,
81  const TrajectorySmootherConfig & config,
82  const LanePlannerConfig & planner_config);
83 
84  Trajectory plan_trajectory(
85  const autoware_auto_msgs::msg::Route & route,
86  const LaneletMapConstPtr & map);
87 
88 private:
89  VehicleConfig m_vehicle_param;
90  LanePlannerConfig m_planner_config;
91 
92  TrajectorySmoother m_trajectory_smoother;
93 
94  // trajectory planning sub functions
95  TrajectoryPoints generate_base_trajectory(const Route & route, const LaneletMapConstPtr & map);
96  void set_angle(TrajectoryPoints * trajectory_points);
97  void set_steering_angle(TrajectoryPoints * trajectory_points);
98  void set_time_from_start(TrajectoryPoints * trajectory_points);
99  void modify_velocity(Trajectory * trajectory);
100 
101  Trajectory create_trajectory_message(
102  const std_msgs::msg::Header & header,
103  const TrajectoryPoints & trajectory_points);
104 }; // class LanePlanner
105 
106 } // namespace lane_planner
107 } // namespace autoware
108 
109 #endif // LANE_PLANNER__LANE_PLANNER_HPP_
autoware::lane_planner::LanePlannerConfig
Definition: lane_planner.hpp:70
motion::motion_common::VehicleConfig
Vehicle parameters specifying vehicle's handling performance.
Definition: control/motion_common/include/motion_common/config.hpp:87
motion::motion_common::to_angle
MOTION_COMMON_PUBLIC Real to_angle(Heading heading) noexcept
Converts 2D quaternion to simple heading representation.
Definition: motion_common.cpp:145
autoware::lane_planner::LanePlannerConfig::trajectory_resolution
float32_t trajectory_resolution
Definition: lane_planner.hpp:72
autoware::lane_planner::LanePlanner
A class for recording trajectories and replaying them as plans.
Definition: lane_planner.hpp:76
visibility_control.hpp
autoware::trajectory_spoofer::VehicleKinematicState
autoware_auto_msgs::msg::VehicleKinematicState VehicleKinematicState
Definition: trajectory_spoofer.hpp:44
autoware::lane_planner::calculate_curvature
LANE_PLANNER_PUBLIC float32_t calculate_curvature(const TrajectoryPoint &p1, const TrajectoryPoint &p2, const TrajectoryPoint &p3)
Definition: lane_planner.cpp:37
types.hpp
This file includes common type definition.
motion::planning::trajectory_smoother::TrajectorySmoother
Smooth over the trajectory by passing it through a gaussian filter.
Definition: trajectory_smoother.hpp:47
autoware::lane_planner::State
autoware_auto_msgs::msg::VehicleKinematicState State
Definition: lane_planner.hpp:48
autoware::lane_planner::TrajectoryPoint
autoware_auto_msgs::msg::TrajectoryPoint TrajectoryPoint
Definition: lane_planner.hpp:46
autoware::motion::planning::parking_planner_nodes::Route
autoware_auto_msgs::msg::Route Route
Definition: parking_planner_node.hpp:60
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:33
autoware::lane_planner::Heading
decltype(decltype(State::state)::heading) Heading
Definition: lane_planner.hpp:51
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
config.hpp
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:36
trajectory_smoother.hpp
This file defines the trajectory_smoother class.
autoware::lane_planner::distance2d
LANE_PLANNER_PUBLIC float32_t distance2d(const TrajectoryPoint &p1, const TrajectoryPoint &p2)
Definition: lane_planner.cpp:30
motion::planning::trajectory_smoother::TrajectorySmootherConfig
Definition: trajectory_smoother.hpp:39
autoware::common::types::float64_t
double float64_t
Definition: types.hpp:37
motion::motion_common::Trajectory
autoware_auto_msgs::msg::Trajectory Trajectory
Definition: motion_common.hpp:37
autoware::lane_planner::TrajectoryPoints
std::vector< TrajectoryPoint > TrajectoryPoints
Definition: lane_planner.hpp:47