Autoware.Auto
pure_pursuit.hpp
Go to the documentation of this file.
1 // Copyright 2019 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 //
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
16 
17 #ifndef PURE_PURSUIT__PURE_PURSUIT_HPP_
18 #define PURE_PURSUIT__PURE_PURSUIT_HPP_
19 
20 #include <autoware_auto_msgs/msg/trajectory.hpp>
21 #include <autoware_auto_msgs/msg/trajectory_point.hpp>
22 #include <autoware_auto_msgs/msg/vehicle_kinematic_state.hpp>
23 #include <autoware_auto_msgs/msg/vehicle_control_command.hpp>
25 #include <utility>
26 #include "pure_pursuit/config.hpp"
27 
28 namespace autoware
29 {
30 namespace motion
31 {
32 namespace control
33 {
35 namespace pure_pursuit
36 {
40 using ControllerDiagnostic = autoware_auto_msgs::msg::ControlDiagnostic;
42 
44 class PURE_PURSUIT_PUBLIC PurePursuit
46 {
47 public:
50  explicit PurePursuit(const Config & cfg);
51 
52 protected:
58  VehicleControlCommand compute_command_impl(const TrajectoryPointStamped & state) override;
59 
60 private:
64  PURE_PURSUIT_LOCAL void compute_errors(const TrajectoryPoint & current_point);
68  PURE_PURSUIT_LOCAL void compute_lookahead_distance(const float32_t current_velocity);
75  PURE_PURSUIT_LOCAL bool8_t in_traveling_direction(
76  const TrajectoryPoint & current_point,
77  const TrajectoryPoint & point) const;
84  PURE_PURSUIT_LOCAL void compute_interpolate_target_point(
85  const TrajectoryPoint & current_point,
86  const TrajectoryPoint & target_point,
87  const uint32_t idx);
91  PURE_PURSUIT_LOCAL bool8_t compute_target_point(const TrajectoryPoint & current_point);
96  PURE_PURSUIT_LOCAL static float32_t compute_points_distance_squared(
97  const TrajectoryPoint & point1,
98  const TrajectoryPoint & point2);
103  PURE_PURSUIT_LOCAL std::pair<float32_t, float32_t> compute_relative_xy_offset(
104  const TrajectoryPoint & current,
105  const TrajectoryPoint & target) const;
109  PURE_PURSUIT_LOCAL float32_t compute_steering_rad(const TrajectoryPoint & current_point);
114  PURE_PURSUIT_LOCAL float32_t compute_command_accel_mps(
115  const TrajectoryPoint & current_point,
116  const bool8_t is_emergency) const;
117 
118  float32_t m_lookahead_distance;
119  TrajectoryPoint m_target_point;
120  VehicleControlCommand m_command;
121  Config m_config;
122 
123  bool8_t m_is_traj_update;
124  uint32_t m_reference_idx;
125  uint32_t m_iterations;
126 }; // class PurePursuit
127 } // namespace pure_pursuit
128 } // namespace control
129 } // namespace motion
130 } // namespace autoware
131 
132 #endif // PURE_PURSUIT__PURE_PURSUIT_HPP_
config.hpp
autoware::motion::control::pure_pursuit::VehicleControlCommand
autoware_auto_msgs::msg::VehicleControlCommand VehicleControlCommand
Definition: pure_pursuit.hpp:41
autoware::trajectory_spoofer::VehicleKinematicState
autoware_auto_msgs::msg::VehicleKinematicState VehicleKinematicState
Definition: trajectory_spoofer.hpp:44
autoware::motion::control::pure_pursuit::ControllerDiagnostic
autoware_auto_msgs::msg::ControlDiagnostic ControllerDiagnostic
Definition: pure_pursuit.hpp:40
autoware::motion::control::pure_pursuit::TrajectoryPoint
autoware_auto_msgs::msg::TrajectoryPoint TrajectoryPoint
Definition: pure_pursuit.hpp:38
autoware::motion::control::pure_pursuit::Trajectory
autoware_auto_msgs::msg::Trajectory Trajectory
Definition: pure_pursuit.hpp:37
autoware::motion::control::pure_pursuit::PurePursuit
Given a trajectory and the current state, compute the control command.
Definition: pure_pursuit.hpp:44
controller_base.hpp
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:33
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::motion::control::pure_pursuit::Config
A configuration class for the PurePursuit class.
Definition: control/pure_pursuit/include/pure_pursuit/config.hpp:34
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:36
motion::control::controller_common::ControllerBase
Definition: controller_base.hpp:76
motion
Definition: controller_base.hpp:30
autoware::motion::control::pure_pursuit::TrajectoryPointStamped
autoware_auto_msgs::msg::VehicleKinematicState TrajectoryPointStamped
Definition: pure_pursuit.hpp:39