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_vehicle_msgs/msg/vehicle_kinematic_state.hpp>
25 #include <autoware_auto_planning_msgs/msg/trajectory.hpp>
26 #include <autoware_auto_planning_msgs/msg/had_map_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 
54 
58 
59 using lanelet::LaneletMapConstPtr;
60 
61 // utility functions
62 LANE_PLANNER_PUBLIC float32_t distance2d(const TrajectoryPoint & p1, const TrajectoryPoint & p2);
63 
64 // calculate curvature by circle fitting to three points
65 LANE_PLANNER_PUBLIC float32_t calculate_curvature(
66  const TrajectoryPoint & p1, const TrajectoryPoint & p2,
67  const TrajectoryPoint & p3);
68 
69 struct LANE_PLANNER_PUBLIC LanePlannerConfig
70 {
72 };
73 
75 class LANE_PLANNER_PUBLIC LanePlanner
76 {
77 public:
78  explicit LanePlanner(
79  const VehicleConfig & vehicle_param,
80  const TrajectorySmootherConfig & config,
81  const LanePlannerConfig & planner_config);
82 
83  Trajectory plan_trajectory(
85  const LaneletMapConstPtr & map);
86 
87 private:
88  VehicleConfig m_vehicle_param;
89  LanePlannerConfig m_planner_config;
90 
91  TrajectorySmoother m_trajectory_smoother;
92 
93  // trajectory planning sub functions
94  TrajectoryPoints generate_base_trajectory(
95  const HADMapRoute & had_map_route,
96  const LaneletMapConstPtr & map);
97  void set_angle(TrajectoryPoints * trajectory_points);
98  void set_steering_angle(TrajectoryPoints * trajectory_points);
99  void set_time_from_start(TrajectoryPoints * trajectory_points);
100  void modify_velocity(Trajectory * trajectory);
101 
102  Trajectory create_trajectory_message(
103  const std_msgs::msg::Header & header,
104  const TrajectoryPoints & trajectory_points);
105 }; // class LanePlanner
106 
107 } // namespace lane_planner
108 } // namespace autoware
109 
110 #endif // LANE_PLANNER__LANE_PLANNER_HPP_
autoware::lane_planner::LanePlannerConfig
Definition: lane_planner.hpp:69
motion::motion_common::VehicleConfig
Vehicle parameters specifying vehicle's handling performance.
Definition: control/motion_common/include/motion_common/config.hpp:86
autoware::lane_planner::LanePlannerConfig::trajectory_resolution
float32_t trajectory_resolution
Definition: lane_planner.hpp:71
autoware::lane_planner::LanePlanner
A class for recording trajectories and replaying them as plans.
Definition: lane_planner.hpp:75
visibility_control.hpp
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:39
autoware::lane_planner::TrajectoryPoint
autoware_auto_planning_msgs::msg::TrajectoryPoint TrajectoryPoint
Definition: lane_planner.hpp:46
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_vehicle_msgs::msg::VehicleKinematicState State
Definition: lane_planner.hpp:48
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
config.hpp
autoware::planning::costmap_generator::HADMapRoute
autoware_auto_planning_msgs::msg::HADMapRoute HADMapRoute
Definition: costmap_generator_node.hpp:81
motion::motion_common::to_angle
MOTION_COMMON_PUBLIC Double to_angle(Orientation orientation) noexcept
Converts 3D quaternion to simple heading representation.
Definition: motion_common.cpp:106
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:45
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:32
motion::planning::trajectory_smoother::TrajectorySmootherConfig
Definition: trajectory_smoother.hpp:39
motion::motion_common::Trajectory
autoware_auto_planning_msgs::msg::Trajectory Trajectory
Definition: motion_common.hpp:41
autoware::common::types::float64_t
double float64_t
Definition: types.hpp:47
autoware::trajectory_spoofer::VehicleKinematicState
autoware_auto_vehicle_msgs::msg::VehicleKinematicState VehicleKinematicState
Definition: trajectory_spoofer.hpp:42
autoware::lane_planner::TrajectoryPoints
std::vector< TrajectoryPoint > TrajectoryPoints
Definition: lane_planner.hpp:47