Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
parameters.hpp
Go to the documentation of this file.
1#pragma once
2#include <yaml-cpp/yaml.h>
3
4#include <string>
5
8#include "rclcpp/rclcpp.hpp"
9
12
13 std::string control_solver_; // control solver to be used, options: "decoupled"
14 std::string lateral_controller_; // lateral controller to be used, options: "pure_pursuit"
15 std::string longitudinal_controller_; // longitudinal controller to be used, options: "pid"
16 bool using_simulated_slam_; // true: use simulated slam, false: use real slam (must run the slam node)
17 bool using_simulated_velocities_; // true: use simulated velocities, false: use real velocities (must run the velocity_estimation node)
18 bool use_simulated_planning_; // true: use simulated planning (must run mocker node), false: use real planning (must run the planning node)
19 double pure_pursuit_lookahead_gain_; // lookahead distance gain for pure pursuit, to be multiplied by the current speed
20 double pure_pursuit_lookahead_minimum_; // minimum lookahead distance for pure pursuit
21 double pure_pursuit_lpf_alpha_; // low-pass filter smoothing factor (0 < alpha < 1), smaller values mean more smoothing
22 double pure_pursuit_lpf_initial_value_; // initial value for low-pass filter
23 double first_last_max_dist_; // maximum distance between first and last point to consider for closing the path
24 double pid_kp_; // proportional gain for PID controller
25 double pid_ki_; // integral gain for PID controller
26 double pid_kd_; // derivative gain for PID controller
27 double pid_tau_; // Derivative low pass filter time constant
28 double pid_t_; // Sample time for PID controller
29 double pid_lim_min_; // minimum output limit for PID controller (maximum braking)
30 double pid_lim_max_; // maximum output limit for PID controller (maximum throttle)
31 double pid_anti_windup_; // anti-windup parameter for PID controller, gain of integrator impact when saturated
32 double pid_max_positive_error_; // maximum positive error for PID controller (restricts acceleration)
33 double pid_max_negative_error_; // maximum negative error for PID controller (restricts braking)
34 std::string map_frame_id_; // frame id to publish visualization markers (can be "map", ...), for example closest point and lookahead point
35 uint command_time_interval_; // time interval (in ms) between command publications
36
37
38
40 ControlParameters() = default;
42 std::string load_config();
43};
std::string longitudinal_controller_
double pure_pursuit_lpf_initial_value_
double pure_pursuit_lookahead_gain_
std::string load_config()
double pure_pursuit_lookahead_minimum_
ControlParameters & operator=(const ControlParameters &other)
common_lib::car_parameters::CarParameters car_parameters_
std::string control_solver_
double pid_max_positive_error_
ControlParameters()=default
bool using_simulated_velocities_
std::string map_frame_id_
std::string lateral_controller_
double pid_max_negative_error_
double first_last_max_dist_
double pure_pursuit_lpf_alpha_