Autoware.Auto
control/pure_pursuit/include/pure_pursuit/config.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 #ifndef PURE_PURSUIT__CONFIG_HPP_
17 #define PURE_PURSUIT__CONFIG_HPP_
18 
20 #include <common/types.hpp>
21 
24 
25 namespace autoware
26 {
27 namespace motion
28 {
29 namespace control
30 {
31 namespace pure_pursuit
32 {
34 class PURE_PURSUIT_PUBLIC Config
35 {
36 public:
52  Config(
53  const float32_t minimum_lookahead_distance,
54  const float32_t maximum_lookahead_distance,
55  const float32_t speed_to_lookahead_ratio,
56  const bool8_t is_interpolate_lookahead_point,
57  const bool8_t is_delay_compensation,
58  const float32_t emergency_stop_distance,
59  const float32_t speed_thres_traveling_direction,
60  const float32_t distance_front_rear_wheel);
63  float32_t get_minimum_lookahead_distance() const noexcept;
66  float32_t get_maximum_lookahead_distance() const noexcept;
69  float32_t get_speed_to_lookahead_ratio() const noexcept;
72  bool8_t get_is_interpolate_lookahead_point() const noexcept;
75  bool8_t get_is_delay_compensation() const noexcept;
78  float32_t get_emergency_stop_distance() const noexcept;
81  float32_t get_speed_thres_traveling_direction() const noexcept;
84  float32_t get_distance_front_rear_wheel() const noexcept;
85 
86 private:
87  float32_t m_minimum_lookahead_distance;
88  float32_t m_maximum_lookahead_distance;
89  float32_t m_speed_to_lookahead_ratio;
90  bool8_t m_is_interpolate_lookahead_point;
91  bool8_t m_is_delay_compensation;
92  float32_t m_emergency_stop_distance;
93  float32_t m_speed_thres_traveling_direction;
94  float32_t m_distance_front_rear_wheel;
95 }; // class Config
96 } // namespace pure_pursuit
97 } // namespace control
98 } // namespace motion
99 } // namespace autoware
100 
101 #endif // PURE_PURSUIT__CONFIG_HPP_
types.hpp
This file includes common type definition.
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
visibility_control.hpp
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:45
motion
Definition: controller_base.hpp:30