Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
planning_config.hpp
Go to the documentation of this file.
1#ifndef SRC_PLANNING_INCLUDE_CONFIG_PLANNING_CONFIG_HPP_
2#define SRC_PLANNING_INCLUDE_CONFIG_PLANNING_CONFIG_HPP_
3
4#include <string>
5
7#include "skidpad_config.hpp"
9#include "velocity_config.hpp"
10
12 /*---------------------- Midpoint Generator (mg_) ----------------------*/
16
17 /*---------------------- Path Calculation (pc_) ------------------------*/
31
32 /*---------------------- Skidpad (skidpad_) ----------------------------*/
35
36 /*---------------------- Path Smoothing (smoothing_) -------------------*/
49
50 /*---------------------- Velocity Planning (vp_) -----------------------*/
58
59 /*---------------------- Planning (planning_) ----------------------*/
64
69
74
79
84
88 std::string planning_adapter_;
89 std::string map_frame_id_;
90};
91
102 std::string adapter_;
103
104 PlanningConfig() = default;
105
106 explicit PlanningConfig(const PlanningParameters &params)
108 // Midpoint Generator Config
109 MidpointGeneratorConfig(params.mg_minimum_cone_distance_,
110 params.mg_maximum_cone_distance_,
111 params.mg_sliding_window_radius_),
112 // Path Calculation parameters
113 params.pc_use_sliding_window_, params.pc_angle_gain_, params.pc_distance_gain_,
114 params.pc_angle_exponent_, params.pc_distance_exponent_, params.pc_max_cost_,
115 params.pc_minimum_point_distance_, params.pc_lookback_points_, params.pc_search_depth_,
116 params.pc_max_points_, params.pc_reset_interval_, params.pc_use_reset_path_,
117 params.pc_close_cost_),
118 smoothing_(params.smoothing_spline_precision_, params.smoothing_spline_order_,
119 params.smoothing_spline_coeffs_ratio_, params.smoothing_min_path_point_distance_,
120 params.smoothing_use_path_smoothing_, params.smoothing_use_optimization_,
121 params.smoothing_car_width_, params.smoothing_safety_margin_,
122 params.smoothing_curvature_weight_, params.smoothing_safety_weight_,
123 params.smoothing_max_iterations_, params.smoothing_tolerance_),
124 velocity_planning_(params.vp_minimum_velocity_, params.vp_desired_velocity_,
125 params.vp_braking_acceleration_, params.vp_acceleration_,
126 params.vp_lateral_acceleration_, params.vp_longitudinal_acceleration_,
127 params.vp_use_velocity_planning_),
128 skidpad_(params.skidpad_minimum_cones_, params.skidpad_tolerance_),
129 publishing_visualization_msgs_(params.planning_publishing_visualization_msgs_),
130 using_simulated_se_(params.planning_using_simulated_se_),
131 using_full_map_(params.planning_using_full_map_),
132 braking_distance_acceleration_(params.planning_braking_distance_acceleration_),
133 braking_distance_autocross_(params.planning_braking_distance_autocross_),
134 adapter_(params.planning_adapter_) {}
135};
136
137#endif // SRC_PLANNING_INCLUDE_CONFIG_PLANNING_CONFIG_HPP_
Configuration parameters for the Midpoint Generator class.
Configuration parameters for the Path Smoothing class.
PlanningConfig(const PlanningParameters &params)
bool publishing_visualization_msgs_
double braking_distance_acceleration_
PathCalculationConfig path_calculation_
PlanningConfig()=default
PathSmoothingConfig smoothing_
VelocityPlanningConfig velocity_planning_
SkidpadConfig skidpad_
double braking_distance_autocross_
double planning_braking_distance_acceleration_
Distance to start braking during acceleration mode.
double planning_braking_distance_autocross_
Distance to start braking during autocross/trackdrive mode.
bool planning_using_full_map_
Flag to enable/disable using planning with the full map.
std::string planning_adapter_
The adapter planning is currently using like Pacsim, Vehicle...
bool planning_using_simulated_se_
Flag to enable/disable the use of simulated State Estimation.
bool planning_publishing_visualization_msgs_
Flag to enable/disable publishing of visualization messages.
float smoothing_min_path_point_distance_
Configuration parameters for the Skidpad class.
Configuration parameters for the Velocity Planning class.