diff --git a/aip_x1_launch/config/concatenate_and_time_sync_node.param.yaml b/aip_x1_launch/config/concatenate_and_time_sync_node.param.yaml index 374a65fa..fcc00d60 100644 --- a/aip_x1_launch/config/concatenate_and_time_sync_node.param.yaml +++ b/aip_x1_launch/config/concatenate_and_time_sync_node.param.yaml @@ -1,7 +1,5 @@ /**: ros__parameters: - # ignore the lidar_timestamp_offsets and lidar_timestamp_noise_window if 'use_naive_approach' is true - use_naive_approach: false debug_mode: false has_static_tf_only: false rosbag_length: 10.0 @@ -18,5 +16,7 @@ "/sensing/lidar/top/pointcloud_before_sync", # 0.055 ] output_frame: base_link - lidar_timestamp_offsets: [0.0, 0.03] - lidar_timestamp_noise_window: [0.01, 0.01] + matching_strategy: + type: advanced + lidar_timestamp_offsets: [0.0, 0.03] + lidar_timestamp_noise_window: [0.01, 0.01] diff --git a/aip_x2_launch/config/concatenate_and_time_sync_node.param.yaml b/aip_x2_launch/config/concatenate_and_time_sync_node.param.yaml index fe37a3d9..fac6393b 100644 --- a/aip_x2_launch/config/concatenate_and_time_sync_node.param.yaml +++ b/aip_x2_launch/config/concatenate_and_time_sync_node.param.yaml @@ -1,7 +1,5 @@ /**: ros__parameters: - # ignore the lidar_timestamp_offsets and lidar_timestamp_noise_window if 'use_naive_approach' is true - use_naive_approach: false debug_mode: false has_static_tf_only: false rosbag_length: 10.0 @@ -24,5 +22,7 @@ "/sensing/lidar/right_lower/pointcloud_before_sync", # 0.00 ] output_frame: base_link - lidar_timestamp_offsets: [0.0, 0.005, 0.006, 0.006, 0.031, 0.03, 0.046, 0.056] - lidar_timestamp_noise_window: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] + matching_strategy: + type: advanced + lidar_timestamp_offsets: [0.0, 0.005, 0.006, 0.006, 0.031, 0.03, 0.046, 0.056] + lidar_timestamp_noise_window: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] diff --git a/aip_xx1_gen2_launch/config/concatenate_and_time_sync_node.param.yaml b/aip_xx1_gen2_launch/config/concatenate_and_time_sync_node.param.yaml index e889deef..9e5ffa7e 100644 --- a/aip_xx1_gen2_launch/config/concatenate_and_time_sync_node.param.yaml +++ b/aip_xx1_gen2_launch/config/concatenate_and_time_sync_node.param.yaml @@ -1,7 +1,5 @@ /**: ros__parameters: - # ignore the lidar_timestamp_offsets and lidar_timestamp_noise_window if 'use_naive_approach' is true - use_naive_approach: false debug_mode: false has_static_tf_only: false rosbag_length: 10.0 @@ -21,5 +19,7 @@ "/sensing/lidar/side_right/pointcloud_before_sync", # 0.99 ] output_frame: base_link - lidar_timestamp_offsets: [0.0, 0.0, 0.0, 0.0, 0.0] - lidar_timestamp_noise_window: [0.01, 0.01, 0.01, 0.01, 0.01] + matching_strategy: + type: advanced + lidar_timestamp_offsets: [0.0, 0.0, 0.0, 0.0, 0.0] + lidar_timestamp_noise_window: [0.01, 0.01, 0.01, 0.01, 0.01] \ No newline at end of file diff --git a/aip_xx1_launch/config/concatenate_and_time_sync_node.param.yaml b/aip_xx1_launch/config/concatenate_and_time_sync_node.param.yaml index 54745186..453c5408 100644 --- a/aip_xx1_launch/config/concatenate_and_time_sync_node.param.yaml +++ b/aip_xx1_launch/config/concatenate_and_time_sync_node.param.yaml @@ -1,7 +1,5 @@ /**: ros__parameters: - # ignore the lidar_timestamp_offsets and lidar_timestamp_noise_window if 'use_naive_approach' is true - use_naive_approach: false debug_mode: false has_static_tf_only: false rosbag_length: 10.0 @@ -20,5 +18,7 @@ "/sensing/lidar/rear/pointcloud_before_sync", ] output_frame: base_link - lidar_timestamp_offsets: [0.0, 0.02, 0.02, 0.02] - lidar_timestamp_noise_window: [0.02, 0.02, 0.02, 0.02] + matching_strategy: + type: advanced + lidar_timestamp_offsets: [0.0, 0.02, 0.02, 0.02] + lidar_timestamp_noise_window: [0.02, 0.02, 0.02, 0.02]