16 #ifndef PURE_PURSUIT__CONFIG_HPP_ 17 #define PURE_PURSUIT__CONFIG_HPP_ 31 namespace pure_pursuit
53 const float32_t minimum_lookahead_distance,
54 const float32_t maximum_lookahead_distance,
56 const bool8_t is_interpolate_lookahead_point,
57 const bool8_t is_delay_compensation,
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;
90 bool8_t m_is_interpolate_lookahead_point;
91 bool8_t m_is_delay_compensation;
93 float32_t m_speed_thres_traveling_direction;
101 #endif // PURE_PURSUIT__CONFIG_HPP_
float float32_t
Definition: types.hpp:36
bool bool8_t
Definition: types.hpp:33
This file includes common type definition.
A configuration class for the PurePursuit class.
Definition: control/pure_pursuit/include/pure_pursuit/config.hpp:34
Definition: controller_base.hpp:30
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24