74 optional
double xy_grid_resolution = 1 [
default = 0.2];
76 optional
double phi_grid_resolution = 2 [
default = 0.05];
78 optional uint64 next_node_num = 3 [
default = 10];
80 optional
double step_size = 4 [
default = 0.5];
82 optional
double traj_forward_penalty = 5 [
default = 0.0];
84 optional
double traj_back_penalty = 6 [
default = 0.0];
86 optional
double traj_gear_switch_penalty = 7 [
default = 10.0];
88 optional
double traj_steer_penalty = 8 [
default = 100.0];
90 optional
double traj_steer_change_penalty = 9 [
default = 10.0];
92 optional
double traj_short_length_penalty = 10 [
default = 10.0];
94 optional
double grid_a_star_xy_resolution = 11 [
default = 0.1];
96 optional
double node_radius = 12 [
default = 0.5];
99 optional
double traj_kappa_contraint_ratio = 14 [
default = 0.7];
101 optional int32 max_explored_num = 15 [
default = 10000];
103 optional int32 desired_explored_num= 16 [
default = 10000];
106 optional
double traj_expected_shortest_length = 17 [
default = 1.0];
108 optional
double astar_max_search_time = 18 [
default = 5.0];
110 optional
double esdf_range = 19 [
default = 2.0];
112 optional
double soft_boundary_penalty = 20 [
default = 2.0];
114 optional
bool use_esdf = 21 [
default =
true];
137 optional
double weight_steer = 1;
138 optional
double weight_a = 2;
139 optional
double weight_steer_rate = 3;
140 optional
double weight_a_rate = 4;
141 optional
double weight_x = 5;
142 optional
double weight_y = 6;
143 optional
double weight_phi = 7;
144 optional
double weight_v = 8;
145 optional
double weight_steer_stitching = 9;
146 optional
double weight_a_stitching = 10;
147 optional
double weight_first_order_time = 11;
148 optional
double weight_second_order_time = 12;
150 optional
double min_safety_distance = 13 [
default = 0.0];
152 optional
double max_speed_forward = 14 [
default = 3.0];
154 optional
double max_speed_reverse = 15 [
default = 2.0];
156 optional
double max_acceleration_forward = 16 [
default = 2.0];
158 optional
double max_acceleration_reverse = 17 [
default = 2.0];
160 optional
double min_time_sample_scaling = 18 [
default = 0.1];
162 optional
double max_time_sample_scaling = 19 [
default = 10.0];
164 optional
bool use_fix_time = 20 [
default =
false];
168 optional
bool enable_constraint_check = 22;
170 optional
bool enable_hand_derivative = 23;
172 optional
bool enable_derivative_check = 24;
174 optional
bool enable_initial_final_check = 25 [
default =
false];
177 optional
bool enable_jacobian_ad = 27 [
default =
false];
179 optional
bool enable_check_initial_state = 28 [
default =
false];
181 optional
double weight_end_state = 29 [
default = 0.0];
183 optional
double weight_slack = 30 [
default = 0.0];
188 optional int32 ipopt_print_level = 1;
191 optional int32 mumps_mem_percent = 2;
193 optional
double mumps_pivtol = 3;
195 optional int32 ipopt_max_iter = 4;
197 optional
double ipopt_tol = 5;
199 optional
double ipopt_acceptable_constr_viol_tol = 6;
203 optional
double ipopt_min_hessian_perturbation = 7;
207 optional
double ipopt_jacobian_regularization_value = 8;
209 optional
string ipopt_print_timing_statistics = 9;
212 optional
string ipopt_alpha_for_y = 10;
215 optional
string ipopt_recalc_y = 11;
217 optional
double ipopt_mu_init = 12 [
default = 0.1];
239 optional
double interpolated_delta_s = 1 [
default = 0.1];
241 optional int32 reanchoring_trails_num = 2 [
default = 50];
243 optional
double reanchoring_pos_stddev = 3 [
default = 0.25];
245 optional
double reanchoring_length_stddev = 4 [
default = 1.0];
247 optional
bool estimate_bound = 5 [
default =
false];
249 optional
double default_bound = 6 [
default = 2.0];
251 optional
double vehicle_shortest_dimension = 7 [
default = 1.04];
256 optional
double collision_decrease_ratio = 9 [
default = 0.9];
259 optional
double max_forward_v = 10 [
default = 2.0];
261 optional
double max_reverse_v = 11 [
default = 2.0];
263 optional
double max_forward_acc = 12 [
default = 3.0];
265 optional
double max_reverse_acc = 13 [
default = 2.0];
267 optional
double max_acc_jerk = 14 [
default = 4.0];
269 optional
double delta_t = 15 [
default = 0.2];
302 optional int32 ipopt_print_level = 1;
304 optional int32 mumps_mem_percent = 2;
306 optional
double mumps_pivtol = 3;
308 optional int32 ipopt_max_iter = 4;
310 optional
double ipopt_tol = 5;
312 optional
double ipopt_acceptable_constr_viol_tol = 6;
316 optional
double ipopt_min_hessian_perturbation = 7;
320 optional
double ipopt_jacobian_regularization_value = 8;
322 optional
string ipopt_print_timing_statistics = 9;
325 optional
string ipopt_alpha_for_y = 10;
328 optional
string ipopt_recalc_y = 11;
330 optional
double ipopt_mu_init = 12 [
default = 0.1];