@@ -377,6 +377,33 @@ void StartPlannerModuleManager::updateModuleParams(
377
377
parameters, ns + " collision_check_margin_from_front_object" ,
378
378
p->collision_check_margin_from_front_object );
379
379
updateParam<double >(parameters, ns + " th_moving_object_velocity" , p->th_moving_object_velocity );
380
+ const std::string obj_types_ns = ns + " object_types_to_check_for_path_generation." ;
381
+ {
382
+ updateParam<bool >(
383
+ parameters, obj_types_ns + " check_car" ,
384
+ p->object_types_to_check_for_path_generation .check_car );
385
+ updateParam<bool >(
386
+ parameters, obj_types_ns + " check_truck" ,
387
+ p->object_types_to_check_for_path_generation .check_truck );
388
+ updateParam<bool >(
389
+ parameters, obj_types_ns + " check_bus" ,
390
+ p->object_types_to_check_for_path_generation .check_bus );
391
+ updateParam<bool >(
392
+ parameters, obj_types_ns + " check_trailer" ,
393
+ p->object_types_to_check_for_path_generation .check_trailer );
394
+ updateParam<bool >(
395
+ parameters, obj_types_ns + " check_unknown" ,
396
+ p->object_types_to_check_for_path_generation .check_unknown );
397
+ updateParam<bool >(
398
+ parameters, obj_types_ns + " check_bicycle" ,
399
+ p->object_types_to_check_for_path_generation .check_bicycle );
400
+ updateParam<bool >(
401
+ parameters, obj_types_ns + " check_motorcycle" ,
402
+ p->object_types_to_check_for_path_generation .check_motorcycle );
403
+ updateParam<bool >(
404
+ parameters, obj_types_ns + " check_pedestrian" ,
405
+ p->object_types_to_check_for_path_generation .check_pedestrian );
406
+ }
380
407
updateParam<double >(parameters, ns + " center_line_path_interval" , p->center_line_path_interval );
381
408
updateParam<bool >(parameters, ns + " enable_shift_pull_out" , p->enable_shift_pull_out );
382
409
updateParam<double >(
0 commit comments