Autoware.Auto
autoware::motion::control::pure_pursuit::Config Class Reference

A configuration class for the PurePursuit class. More...

#include <config.hpp>

Public Member Functions

 Config (const float32_t minimum_lookahead_distance, const float32_t maximum_lookahead_distance, const float32_t speed_to_lookahead_ratio, const bool8_t is_interpolate_lookahead_point, const bool8_t is_delay_compensation, const float32_t emergency_stop_distance, const float32_t speed_thres_traveling_direction, const float32_t distance_front_rear_wheel)
 Constructor. More...
 
float32_t get_minimum_lookahead_distance () const noexcept
 Gets the minimum lookahead distance for the pure pursuit. More...
 
float32_t get_maximum_lookahead_distance () const noexcept
 Gets the maximum lookahead distance for the pure pursuit. More...
 
float32_t get_speed_to_lookahead_ratio () const noexcept
 Gets the maximum lookahead distance for the pure pursuit. More...
 
bool8_t get_is_interpolate_lookahead_point () const noexcept
 Gets the boolean whether using the interpolation to get the target point. More...
 
bool8_t get_is_delay_compensation () const noexcept
 Gets the boolean whether using the delay compensation to estimate the current point. More...
 
float32_t get_emergency_stop_distance () const noexcept
 Gets the emergency target distance for the emergency stop. More...
 
float32_t get_speed_thres_traveling_direction () const noexcept
 Gets the speed threshold for determining the traveling direction. More...
 
float32_t get_distance_front_rear_wheel () const noexcept
 Gets the distance between front and rear wheels. More...
 

Detailed Description

A configuration class for the PurePursuit class.

Constructor & Destructor Documentation

◆ Config()

autoware::motion::control::pure_pursuit::Config::Config ( const float32_t  minimum_lookahead_distance,
const float32_t  maximum_lookahead_distance,
const float32_t  speed_to_lookahead_ratio,
const bool8_t  is_interpolate_lookahead_point,
const bool8_t  is_delay_compensation,
const float32_t  emergency_stop_distance,
const float32_t  speed_thres_traveling_direction,
const float32_t  distance_front_rear_wheel 
)

Constructor.

Parameters
[in]minimum_lookahead_distanceThe minimum lookahead distance (meter) for the pure pursuit
[in]maximum_lookahead_distanceThe maximum lookahead distance (meter) for the pure pursuit
[in]speed_to_lookahead_ratioThe conversion ratio from the speed to the lookahead distance. The ratio is equal to the duration (s)
[in]is_interpolate_lookahead_pointThe boolean whether using the interpolation for determining the target position
[in]is_delay_compensationThe boolean whethre using the delay compensation for estimating the current vehicle position at the current timestamp
[in]emergency_stop_distanceThe emergency stop distance for the emergency stop
[in]speed_thres_traveling_directionThe speed threshold for determining the traveling direction
[in]distance_front_rear_wheelThe distance between front and rear wheels

Member Function Documentation

◆ get_distance_front_rear_wheel()

float32_t autoware::motion::control::pure_pursuit::Config::get_distance_front_rear_wheel ( ) const
noexcept

Gets the distance between front and rear wheels.

Returns
Fixed value

◆ get_emergency_stop_distance()

float32_t autoware::motion::control::pure_pursuit::Config::get_emergency_stop_distance ( ) const
noexcept

Gets the emergency target distance for the emergency stop.

Returns
Fixed value

◆ get_is_delay_compensation()

bool8_t autoware::motion::control::pure_pursuit::Config::get_is_delay_compensation ( ) const
noexcept

Gets the boolean whether using the delay compensation to estimate the current point.

Returns
Fixed value

◆ get_is_interpolate_lookahead_point()

bool8_t autoware::motion::control::pure_pursuit::Config::get_is_interpolate_lookahead_point ( ) const
noexcept

Gets the boolean whether using the interpolation to get the target point.

Returns
Fixed value

◆ get_maximum_lookahead_distance()

float32_t autoware::motion::control::pure_pursuit::Config::get_maximum_lookahead_distance ( ) const
noexcept

Gets the maximum lookahead distance for the pure pursuit.

Returns
Fixed value

◆ get_minimum_lookahead_distance()

float32_t autoware::motion::control::pure_pursuit::Config::get_minimum_lookahead_distance ( ) const
noexcept

Gets the minimum lookahead distance for the pure pursuit.

Returns
Fixed value

◆ get_speed_thres_traveling_direction()

float32_t autoware::motion::control::pure_pursuit::Config::get_speed_thres_traveling_direction ( ) const
noexcept

Gets the speed threshold for determining the traveling direction.

Returns
Fixed value

◆ get_speed_to_lookahead_ratio()

float32_t autoware::motion::control::pure_pursuit::Config::get_speed_to_lookahead_ratio ( ) const
noexcept

Gets the maximum lookahead distance for the pure pursuit.

Returns
Fixed value

The documentation for this class was generated from the following files: