diff --git a/.cspell.json b/.cspell.json
index 66c0f12b..df7e9be3 100644
--- a/.cspell.json
+++ b/.cspell.json
@@ -137,6 +137,7 @@
"tempature",
"rsample",
"coeffs",
- "softplus"
+ "softplus",
+ "mpss"
]
}
diff --git a/.gitignore b/.gitignore
new file mode 100644
index 00000000..600d2d33
--- /dev/null
+++ b/.gitignore
@@ -0,0 +1 @@
+.vscode
\ No newline at end of file
diff --git a/aichallenge/.gitignore b/aichallenge/.gitignore
new file mode 100644
index 00000000..71c36e20
--- /dev/null
+++ b/aichallenge/.gitignore
@@ -0,0 +1,2 @@
+capture
+result-details.json
\ No newline at end of file
diff --git a/aichallenge/workspace/.gitignore b/aichallenge/workspace/.gitignore
index ab2524be..fca9e03b 100644
--- a/aichallenge/workspace/.gitignore
+++ b/aichallenge/workspace/.gitignore
@@ -3,4 +3,5 @@
/log
.vscode
-*.code-workspace
\ No newline at end of file
+*.code-workspace
+result-details.json
diff --git a/aichallenge/workspace/src/aichallenge_submit/aichallenge_submit_launch/launch/aichallenge_submit.launch.xml b/aichallenge/workspace/src/aichallenge_submit/aichallenge_submit_launch/launch/aichallenge_submit.launch.xml
index da639962..ec2952a0 100644
--- a/aichallenge/workspace/src/aichallenge_submit/aichallenge_submit_launch/launch/aichallenge_submit.launch.xml
+++ b/aichallenge/workspace/src/aichallenge_submit/aichallenge_submit_launch/launch/aichallenge_submit.launch.xml
@@ -22,6 +22,6 @@
-
+
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 f670c1e7..283e0a7f 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
@@ -4,7 +4,7 @@
map_frame_id: "map"
costmap_center_frame_id: "base_link"
costmap_width: 50.0 # [m]
- costmap_resolution: 0.2 # [m/cell]
+ costmap_resolution: 0.1 # [m/cell]
multi_layered_costmap:
layers:
- "cached_lanelet_layer"
@@ -13,7 +13,7 @@
type: "cached_lanelet"
map_topic: "/map/vector_map"
costmap_topic: "~/debug/cached_costmap"
- inflation_radius: 1.8 # [m]
+ inflation_radius: 1.4 # [m]
cached_costmap:
min_x: 89607.0 # [m]
max_x: 89687.0 # [m]
@@ -23,4 +23,4 @@
predicted_object_layer:
type: "predicted_object"
predicted_objects_topic: "/perception/object_recognition/objects"
- distance_threshold: 1.3
+ distance_threshold: 1.2
diff --git a/aichallenge/workspace/src/aichallenge_submit/booars_launch/config/planning/goal_pose.param.yaml b/aichallenge/workspace/src/aichallenge_submit/booars_launch/config/planning/goal_pose.param.yaml
new file mode 100644
index 00000000..7f21479c
--- /dev/null
+++ b/aichallenge/workspace/src/aichallenge_submit/booars_launch/config/planning/goal_pose.param.yaml
@@ -0,0 +1,32 @@
+/**:
+ ros__parameters:
+ goal.position.x: 89653.7
+ goal.position.y: 43122.5
+ goal.position.z: 0.0
+ goal.orientation.x: 0.0
+ goal.orientation.y: 0.0
+ goal.orientation.z: -0.971732
+ goal.orientation.w: 0.236088
+
+ half_goal.position.x: 89657.0
+ half_goal.position.y: 43175.0
+ half_goal.position.z: -28.0
+ half_goal.orientation.x: 0.0
+ half_goal.orientation.y: 0.0
+ half_goal.orientation.z: -0.9
+ half_goal.orientation.w: 0.25
+
+ pit_goal.position.x: 89626.3671875
+ pit_goal.position.y: 43134.921875
+ pit_goal.position.z: 42.10000228881836
+ pit_goal.orientation.x: 0.0
+ pit_goal.orientation.y: 0.0
+ pit_goal.orientation.z: -0.8788172006607056
+ pit_goal.orientation.w: -0.47715866565704346
+ # ゴールまでの距離がこの値以下になると次のゴールを配信する
+ goal_range: 10.0
+ # ピットインを有効化するか
+ enable_pit: true
+ # このしきい値以下になるとピットイン
+ # pit_in_threshold: 100
+ pit_in_threshold: 700
\ No newline at end of file
diff --git a/aichallenge/workspace/src/aichallenge_submit/booars_launch/config/planning/mission_planner.param.yaml b/aichallenge/workspace/src/aichallenge_submit/booars_launch/config/planning/mission_planner.param.yaml
new file mode 100644
index 00000000..a0aa4f74
--- /dev/null
+++ b/aichallenge/workspace/src/aichallenge_submit/booars_launch/config/planning/mission_planner.param.yaml
@@ -0,0 +1,13 @@
+/**:
+ ros__parameters:
+ map_frame: map
+ arrival_check_angle_deg: 180.0
+ arrival_check_distance: 30.0
+ arrival_check_duration: 1.0
+ goal_angle_threshold_deg: 90.0
+ enable_correct_goal_pose: false
+ reroute_time_threshold: 10.0
+ minimum_reroute_length: 30.0
+ consider_no_drivable_lanes: false # This flag is for considering no_drivable_lanes in planning or not.
+ check_footprint_inside_lanes: false
+ allow_reroute_in_autonomous_mode: true
\ No newline at end of file
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 ca77d864..35ba01cc 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,10 +2,10 @@
ros__parameters:
# mppi
horizon : 25
- num_samples : 3000
- u_min : [-2.0, -0.35] # accel(m/s2), steer angle(rad)
- u_max : [2.0, 0.35]
- sigmas : [0.5, 0.25] # sample range
+ 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
lambda : 1.0
auto_lambda : false
# reference path
@@ -13,14 +13,14 @@
lookahead_distance : 0.1
reference_path_interval : 0.8
# cost weights
- Qc : 20.0
+ Qc : 10.0
Ql : 1.0
- Qv : 2.0
- Qo : 10000.0
+ Qv : 4.0
+ Qo : 1000.0
Qin : 0.01
- Qdin : 0.5
+ Qdin : 0.0
# model param
delta_t : 0.1
- vehicle_L : 1.0
- V_MAX : 8.0
+ vehicle_L : 1.08
+ V_MAX : 8.33
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 350d33c5..d5d98a9c 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,11 +12,11 @@
-
+
-
-
+
+
diff --git a/aichallenge/workspace/src/aichallenge_submit/booars_launch/launch/components/planning.launch.xml b/aichallenge/workspace/src/aichallenge_submit/booars_launch/launch/components/planning.launch.xml
index c1deb358..a1f3cb0c 100644
--- a/aichallenge/workspace/src/aichallenge_submit/booars_launch/launch/components/planning.launch.xml
+++ b/aichallenge/workspace/src/aichallenge_submit/booars_launch/launch/components/planning.launch.xml
@@ -14,7 +14,7 @@
-
+
@@ -98,6 +98,14 @@
+
+
+
+
+
+
+
+
diff --git a/aichallenge/workspace/src/aichallenge_submit/booars_launch/map/lanelet2_map_opt.osm b/aichallenge/workspace/src/aichallenge_submit/booars_launch/map/lanelet2_map_opt.osm
index 28d60946..3754ea01 100644
--- a/aichallenge/workspace/src/aichallenge_submit/booars_launch/map/lanelet2_map_opt.osm
+++ b/aichallenge/workspace/src/aichallenge_submit/booars_launch/map/lanelet2_map_opt.osm
@@ -1,4850 +1,4042 @@
-
-
-
+
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
-
-
+
+
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
+
-
-
+
-
-
+
-
-
-
-
+
+
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
-
-
+
+
+
-
-
-
-
+
+
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
-
-
+
+
+
-
-
-
-
+
+
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+
-
-
+