diff --git a/aichallenge/workspace/src/aichallenge_submit/booars_launch/config/planning/costmap_generator.param.yaml b/aichallenge/workspace/src/aichallenge_submit/booars_launch/config/planning/costmap_generator.param.yaml index 283e0a7f..62292907 100644 --- a/aichallenge/workspace/src/aichallenge_submit/booars_launch/config/planning/costmap_generator.param.yaml +++ b/aichallenge/workspace/src/aichallenge_submit/booars_launch/config/planning/costmap_generator.param.yaml @@ -13,7 +13,7 @@ type: "cached_lanelet" map_topic: "/map/vector_map" costmap_topic: "~/debug/cached_costmap" - inflation_radius: 1.4 # [m] + inflation_radius: 1.8 # [m] cached_costmap: min_x: 89607.0 # [m] max_x: 89687.0 # [m] diff --git a/aichallenge/workspace/src/aichallenge_submit/booars_launch/config/planning/mppi_controller.param.yaml b/aichallenge/workspace/src/aichallenge_submit/booars_launch/config/planning/mppi_controller.param.yaml index 35ba01cc..50506a60 100644 --- a/aichallenge/workspace/src/aichallenge_submit/booars_launch/config/planning/mppi_controller.param.yaml +++ b/aichallenge/workspace/src/aichallenge_submit/booars_launch/config/planning/mppi_controller.param.yaml @@ -2,20 +2,20 @@ ros__parameters: # mppi horizon : 25 - num_samples : 4000 - u_min : [-4.0, -0.35] # accel(m/s2), steer angle(rad) - u_max : [3.0, 0.35] - sigmas : [2.0, 0.35] # sample range + num_samples : 5000 + u_min : [-4.0, -0.25] # accel(m/s2), steer angle(rad) + u_max : [2.0, 0.25] + sigmas : [2.0, 0.25] # sample range lambda : 1.0 - auto_lambda : false + auto_lambda : true # reference path DL : 0.1 lookahead_distance : 0.1 - reference_path_interval : 0.8 + reference_path_interval : 0.83 # cost weights - Qc : 10.0 - Ql : 1.0 - Qv : 4.0 + Qc : 20.0 + Ql : 5.0 + Qv : 0.5 Qo : 1000.0 Qin : 0.01 Qdin : 0.0 diff --git a/aichallenge/workspace/src/aichallenge_submit/booars_launch/launch/components/control.launch.xml b/aichallenge/workspace/src/aichallenge_submit/booars_launch/launch/components/control.launch.xml index 44181f68..7c0c285a 100644 --- a/aichallenge/workspace/src/aichallenge_submit/booars_launch/launch/components/control.launch.xml +++ b/aichallenge/workspace/src/aichallenge_submit/booars_launch/launch/components/control.launch.xml @@ -12,8 +12,8 @@