diff --git a/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/data_association_matrix.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/data_association_matrix.param.yaml
new file mode 100644
index 0000000000..104d790d18
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/data_association_matrix.param.yaml
@@ -0,0 +1,66 @@
+/**:
+ ros__parameters:
+ can_assign_matrix:
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN <-Measurement
+ [1, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN <-Tracker
+ 0, 1, 1, 1, 1, 0, 0, 0, #CAR
+ 0, 1, 1, 1, 1, 0, 0, 0, #TRUCK
+ 0, 1, 1, 1, 1, 0, 0, 0, #BUS
+ 0, 1, 1, 1, 1, 0, 0, 0, #TRAILER
+ 0, 0, 0, 0, 0, 1, 1, 1, #MOTORBIKE
+ 0, 0, 0, 0, 0, 1, 1, 1, #BICYCLE
+ 0, 0, 0, 0, 0, 1, 1, 1] #PEDESTRIAN
+
+ max_dist_matrix:
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [4.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, #UNKNOWN
+ 4.0, 4.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #CAR
+ 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRUCK
+ 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #BUS
+ 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRAILER
+ 3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #MOTORBIKE
+ 3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #BICYCLE
+ 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0] #PEDESTRIAN
+ max_area_matrix:
+ # NOTE: The size of truck is 12 m length x 3 m width.
+ # NOTE: The size of trailer is 20 m length x 3 m width.
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [100.00, 100.00, 100.00, 100.00, 100.00, 100.00, 100.00, 100.00, #UNKNOWN
+ 12.10, 12.10, 36.00, 60.00, 60.00, 10000.00, 10000.00, 10000.00, #CAR
+ 36.00, 12.10, 36.00, 60.00, 60.00, 10000.00, 10000.00, 10000.00, #TRUCK
+ 60.00, 12.10, 36.00, 60.00, 60.00, 10000.00, 10000.00, 10000.00, #BUS
+ 60.00, 12.10, 36.00, 60.00, 60.00, 10000.00, 10000.00, 10000.00, #TRAILER
+ 2.50, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #MOTORBIKE
+ 2.50, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #BICYCLE
+ 2.00, 10000.00, 10000.00, 10000.00, 10000.00, 1.50, 1.50, 1.00] #PEDESTRIAN
+ min_area_matrix:
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN
+ 3.600, 3.600, 6.000, 10.000, 10.000, 0.000, 0.000, 0.000, #CAR
+ 6.000, 3.600, 6.000, 10.000, 10.000, 0.000, 0.000, 0.000, #TRUCK
+ 10.000, 3.600, 6.000, 10.000, 10.000, 0.000, 0.000, 0.000, #BUS
+ 10.000, 3.600, 6.000, 10.000, 10.000, 0.000, 0.000, 0.000, #TRAILER
+ 0.001, 0.000, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, #MOTORBIKE
+ 0.001, 0.000, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, #BICYCLE
+ 0.001, 0.000, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100] #PEDESTRIAN
+ max_rad_matrix: # If value is greater than pi, it will be ignored.
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER MOTORBIKE, BICYCLE, PEDESTRIAN
+ [3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #UNKNOWN
+ 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #CAR
+ 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRUCK
+ 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #BUS
+ 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRAILER
+ 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE
+ 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE
+ 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #PEDESTRIAN
+
+ min_iou_matrix: # If value is negative, it will be ignored.
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [0.0001, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN
+ 0.1, -0.1, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, #CAR
+ 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRUCK
+ 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #BUS
+ 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRAILER
+ 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #MOTORBIKE
+ 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #BICYCLE
+ 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.0001] #PEDESTRIAN
diff --git a/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/default_tracker.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/default_tracker.param.yaml
new file mode 100644
index 0000000000..757125202d
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/default_tracker.param.yaml
@@ -0,0 +1,9 @@
+/**:
+ ros__parameters:
+ car_tracker: "linear_motion_tracker"
+ truck_tracker: "linear_motion_tracker"
+ bus_tracker: "linear_motion_tracker"
+ trailer_tracker: "linear_motion_tracker"
+ pedestrian_tracker: "linear_motion_tracker"
+ bicycle_tracker: "linear_motion_tracker"
+ motorcycle_tracker: "linear_motion_tracker"
diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml
index f08de01837..73dcd49b87 100644
--- a/autoware_launch/launch/components/tier4_perception_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml
@@ -59,6 +59,14 @@
name="object_recognition_tracking_multi_object_tracker_data_association_matrix_param_path"
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml"
/>
+
+