Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
|
Struct containing the algorithm configuration values for the PurePursuitWrapperConfig. More...
#include <pure_pursuit_wrapper_config.hpp>
Public Attributes | |
double | vehicle_response_lag = 0.2 |
double | minimum_lookahead_distance = 6.0 |
double | maximum_lookahead_distance = 100.0 |
double | speed_to_lookahead_ratio = 2.0 |
bool | is_interpolate_lookahead_point = true |
bool | is_delay_compensation = true |
double | emergency_stop_distance = 0.1 |
double | speed_thres_traveling_direction = 0.3 |
double | dist_front_rear_wheels = 3.5 |
double | dt = 0.1 |
double | integrator_max_pp = 0.0 |
double | integrator_min_pp = 0.0 |
double | Ki_pp = 0.0 |
bool | is_integrator_enabled = false |
Friends | |
std::ostream & | operator<< (std::ostream &output, const PurePursuitWrapperConfig &c) |
Struct containing the algorithm configuration values for the PurePursuitWrapperConfig.
Definition at line 25 of file pure_pursuit_wrapper_config.hpp.
|
friend |
Definition at line 44 of file pure_pursuit_wrapper_config.hpp.
double pure_pursuit_wrapper::PurePursuitWrapperConfig::dist_front_rear_wheels = 3.5 |
double pure_pursuit_wrapper::PurePursuitWrapperConfig::dt = 0.1 |
Definition at line 38 of file pure_pursuit_wrapper_config.hpp.
Referenced by pure_pursuit_wrapper::PurePursuitWrapperNode::PurePursuitWrapperNode(), and pure_pursuit_wrapper::PurePursuitWrapperNode::on_configure_plugin().
double pure_pursuit_wrapper::PurePursuitWrapperConfig::emergency_stop_distance = 0.1 |
double pure_pursuit_wrapper::PurePursuitWrapperConfig::integrator_max_pp = 0.0 |
double pure_pursuit_wrapper::PurePursuitWrapperConfig::integrator_min_pp = 0.0 |
bool pure_pursuit_wrapper::PurePursuitWrapperConfig::is_delay_compensation = true |
bool pure_pursuit_wrapper::PurePursuitWrapperConfig::is_integrator_enabled = false |
bool pure_pursuit_wrapper::PurePursuitWrapperConfig::is_interpolate_lookahead_point = true |
double pure_pursuit_wrapper::PurePursuitWrapperConfig::Ki_pp = 0.0 |
double pure_pursuit_wrapper::PurePursuitWrapperConfig::maximum_lookahead_distance = 100.0 |
double pure_pursuit_wrapper::PurePursuitWrapperConfig::minimum_lookahead_distance = 6.0 |
double pure_pursuit_wrapper::PurePursuitWrapperConfig::speed_thres_traveling_direction = 0.3 |
double pure_pursuit_wrapper::PurePursuitWrapperConfig::speed_to_lookahead_ratio = 2.0 |
double pure_pursuit_wrapper::PurePursuitWrapperConfig::vehicle_response_lag = 0.2 |
Definition at line 27 of file pure_pursuit_wrapper_config.hpp.
Referenced by pure_pursuit_wrapper::PurePursuitWrapperNode::PurePursuitWrapperNode(), pure_pursuit_wrapper::PurePursuitWrapperNode::generate_command(), pure_pursuit_wrapper::PurePursuitWrapperNode::on_configure_plugin(), and pure_pursuit_wrapper::PurePursuitWrapperNode::parameter_update_callback().