16 #ifndef PURE_PURSUIT__CONFIG_HPP_
17 #define PURE_PURSUIT__CONFIG_HPP_
31 namespace pure_pursuit
55 const float32_t minimum_lookahead_distance,
56 const float32_t maximum_lookahead_distance,
58 const bool8_t is_interpolate_lookahead_point,
59 const bool8_t is_delay_compensation,
61 const float32_t speed_thres_traveling_direction,
63 const float32_t distance_front_rear_wheel);
66 float32_t get_minimum_lookahead_distance()
const noexcept;
69 float32_t get_maximum_lookahead_distance()
const noexcept;
72 float32_t get_speed_to_lookahead_ratio()
const noexcept;
75 bool8_t get_is_interpolate_lookahead_point()
const noexcept;
78 bool8_t get_is_delay_compensation()
const noexcept;
81 float32_t get_emergency_stop_distance()
const noexcept;
84 float32_t get_speed_thres_traveling_direction()
const noexcept;
87 float32_t get_distance_front_rear_wheel()
const noexcept;
90 float32_t get_max_acceleration()
const noexcept;
96 bool8_t m_is_interpolate_lookahead_point;
97 bool8_t m_is_delay_compensation;
99 float32_t m_speed_thres_traveling_direction;
108 #endif // PURE_PURSUIT__CONFIG_HPP_