From 606ec8981b27f54ab051d8c8e619d005beb39794 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Sat, 3 Feb 2024 22:19:58 +0900 Subject: [PATCH 01/41] update for xx1 gen2 Signed-off-by: Yukihiro Saito --- .../config/sensor_kit_calibration.yaml | 181 ++++++++++-------- .../config/sensors_calibration.yaml | 79 +++++--- aip_xx1_description/urdf/radar.xacro | 31 --- aip_xx1_description/urdf/sensor_kit.xacro | 130 ++++++++----- aip_xx1_description/urdf/sensors.xacro | 105 +++++++--- 5 files changed, 312 insertions(+), 214 deletions(-) delete mode 100644 aip_xx1_description/urdf/radar.xacro diff --git a/aip_xx1_description/config/sensor_kit_calibration.yaml b/aip_xx1_description/config/sensor_kit_calibration.yaml index ab417b52..14c61651 100644 --- a/aip_xx1_description/config/sensor_kit_calibration.yaml +++ b/aip_xx1_description/config/sensor_kit_calibration.yaml @@ -1,92 +1,113 @@ sensor_kit_base_link: camera0/camera_link: - x: 0.10731 - y: 0.56343 - z: -0.27697 - roll: -0.025 - pitch: 0.315 - yaw: 1.035 + x: 0.372 # Design Value + y: 0.0 # Design Value + z: -0.207 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 0.0 # Design Value camera1/camera_link: - x: -0.10731 - y: -0.56343 - z: -0.27697 - roll: -0.025 - pitch: 0.32 - yaw: -2.12 + x: 0.372 # Design Value + y: 0.045 # Design Value + z: -0.207 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 0.0 # Design Value camera2/camera_link: - x: 0.10731 - y: -0.56343 - z: -0.27697 - roll: -0.00 - pitch: 0.335 - yaw: -1.04 + x: 0.372 # Design Value + y: -0.045 # Design Value + z: -0.207 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 0.0 # Design Value camera3/camera_link: - x: -0.10731 - y: 0.56343 - z: -0.27697 - roll: 0.0 - pitch: 0.325 - yaw: 2.0943951 + x: 0.133 # Design Value + y: 0.498 # Design Value + z: -0.246 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 0.872665 # Design Value camera4/camera_link: - x: 0.07356 - y: 0.0 - z: -0.0525 - roll: 0.0 - pitch: -0.03 - yaw: -0.005 + x: 0.133 # Design Value + y: -0.498 # Design Value + z: -0.246 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: -0.872665 # Design Value camera5/camera_link: - x: -0.07356 - y: 0.0 - z: -0.0525 - roll: 0.0 - pitch: -0.01 - yaw: 3.125 + x: 0.095 # Design Value + y: 0.524 # Design Value + z: -0.246 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 1.0472 # Design Value camera6/camera_link: - x: 0.05 - y: 0.0175 - z: -0.1 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 + x: 0.095 # Design Value + y: -0.524 # Design Value + z: -0.246 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: -1.0472 # Design Value camera7/camera_link: - x: 0.05 - y: -0.0175 - z: -0.1 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 - velodyne_top_base_link: - x: 0.0 - y: 0.0 - z: 0.0 - roll: 0.0 - pitch: 0.0 - yaw: 1.575 - velodyne_left_base_link: - x: 0.0 - y: 0.56362 - z: -0.30555 - roll: -0.02 - pitch: 0.71 - yaw: 1.575 - velodyne_right_base_link: - x: 0.0 - y: -0.56362 - z: -0.30555 - roll: -0.01 - pitch: 0.71 - yaw: -1.580 + x: -0.345 # Design Value + y: 0.244 # Design Value + z: -0.174 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 2.70526 # Design Value + camera8/camera_link: + x: -0.345 # Design Value + y: -0.244 # Design Value + z: -0.174 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: -2.70526 # Design Value + camera9/camera_link: + x: -0.362 # Design Value + y: 0.202 # Design Value + z: -0.174 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 2.79253 # Design Value + camera10/camera_link: + x: -0.362 # Design Value + y: -0.202 # Design Value + z: -0.174 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: -2.79253 # Design Value + hesai_top_base_link: + x: 0.0 # Design Value + y: 0.0 # Design Value + z: 0.0 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: -0.349066 # Design Value + hesai_left_base_link: + x: 0.0 # Design Value + y: 0.564 # Design Value + z: -0.300 # Design Value + roll: 0.0 # Design Value + pitch: 0.872665 # Design Value + yaw: 1.5708 # Design Value + hesai_right_base_link: + x: 0.0 # Design Value + y: -0.564 # Design Value + z: -0.300 # Design Value + roll: 0.0 # Design Value + pitch: 0.872665 # Design Value + yaw: -1.5708 # Design Value gnss_link: - x: -0.1 - y: 0.0 - z: -0.2 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 + x: -0.279 # Design Value + y: 0.0 # Design Value + z: -0.160 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 0.0 # Design Value tamagawa/imu_link: - x: 0.0 - y: 0.0 - z: 0.0 + x: -0.129 # Design Value + y: 0.0 # Design Value + z: -0.160 # Design Value roll: 3.14159265359 - pitch: 0.0 - yaw: 3.14159265359 + pitch: 0.0 # Design Value + yaw: 3.14159265359 # Design Value diff --git a/aip_xx1_description/config/sensors_calibration.yaml b/aip_xx1_description/config/sensors_calibration.yaml index e8c4b75e..4ae5a152 100644 --- a/aip_xx1_description/config/sensors_calibration.yaml +++ b/aip_xx1_description/config/sensors_calibration.yaml @@ -1,32 +1,25 @@ base_link: - ars408_front_center: - x: 3.8 - y: 0.0 - z: 0.5 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 sensor_kit_base_link: x: 0.9 y: 0.0 z: 2.0 - roll: -0.001 - pitch: 0.015 - yaw: -0.0364 - livox_front_right_base_link: - x: 3.290 - y: -0.65485 - z: 0.3216 roll: 0.0 pitch: 0.0 - yaw: -0.872664444 - livox_front_left_base_link: - x: 3.290 - y: 0.65485 - z: 0.3016 - roll: -0.021 - pitch: 0.05 - yaw: 0.872664444 + yaw: 0.0 + hesai_front_right_base_link: + x: 3.373 # Design Value + y: -0.740 # Design Value + z: 0.5482 + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: -0.872665 # Design Value + hesai_front_left_base_link: + x: 3.373 # Design Value + y: 0.740 # Design Value + z: 0.5482 + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 0.872665 # Design Value velodyne_rear_base_link: x: -0.358 y: 0.0 @@ -34,3 +27,45 @@ base_link: roll: -0.02 pitch: 0.7281317 yaw: 3.141592 + ars548_front_center_base_link: + x: 3.520 # Design Value + y: 0.0 # Design Value + z: 0.6352 + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 0.0 # Design Value + ars548_front_right_base_link: + x: 3.384 # Design Value + y: -0.7775 # Design Value + z: 0.410 + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: -1.22173 # Design Value + ars548_front_left_base_link: + x: 3.384 # Design Value + y: 0.7775 # Design Value + z: 0.410 + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 1.22173 # Design Value + ars548_back_center_base_link: + x: -0.858 # Design Value + y: 0.0 # Design Value + z: 0.520 + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 3.141592 # Design Value + ars548_back_right_base_link: + x: -0.782 # Design Value + y: -0.761 # Design Value + z: 0.520 + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: -2.0944 # Design Value + ars548_back_left_base_link: + x: -0.782 # Design Value + y: 0.761 # Design Value + z: 0.520 + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 2.0944 # Design Value diff --git a/aip_xx1_description/urdf/radar.xacro b/aip_xx1_description/urdf/radar.xacro deleted file mode 100644 index 8b0f8d4b..00000000 --- a/aip_xx1_description/urdf/radar.xacro +++ /dev/null @@ -1,31 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/aip_xx1_description/urdf/sensor_kit.xacro b/aip_xx1_description/urdf/sensor_kit.xacro index ef36763f..647d70d7 100644 --- a/aip_xx1_description/urdf/sensor_kit.xacro +++ b/aip_xx1_description/urdf/sensor_kit.xacro @@ -1,9 +1,8 @@ - + - @@ -25,57 +24,37 @@ - - - - - - - - - + + + + + + + - + - - + - - - + + + + + + + - From 33adae636a6b330212b77bf9b48f66fe3c980a3b Mon Sep 17 00:00:00 2001 From: Yuki Takagi Date: Thu, 15 Feb 2024 13:59:06 +0900 Subject: [PATCH 02/41] set network configs Signed-off-by: Yuki Takagi --- aip_xx1_launch/launch/lidar.launch.xml | 51 ++++++++++++-------------- 1 file changed, 24 insertions(+), 27 deletions(-) diff --git a/aip_xx1_launch/launch/lidar.launch.xml b/aip_xx1_launch/launch/lidar.launch.xml index 0adfe218..26845221 100644 --- a/aip_xx1_launch/launch/lidar.launch.xml +++ b/aip_xx1_launch/launch/lidar.launch.xml @@ -27,11 +27,11 @@ - - + + - + @@ -44,11 +44,11 @@ - - + + - + @@ -61,11 +61,11 @@ - - - - - + + + + + @@ -77,25 +77,22 @@ - + From 845912cd1b044f61ded463140eb346d15c5ee779 Mon Sep 17 00:00:00 2001 From: Yuki Takagi Date: Thu, 15 Feb 2024 14:17:09 +0900 Subject: [PATCH 03/41] use angle param add OT128 launch Signed-off-by: Yuki Takagi --- common_sensor_launch/launch/hesai_XT32.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/common_sensor_launch/launch/hesai_XT32.launch.xml b/common_sensor_launch/launch/hesai_XT32.launch.xml index 56587f72..c47f05fd 100644 --- a/common_sensor_launch/launch/hesai_XT32.launch.xml +++ b/common_sensor_launch/launch/hesai_XT32.launch.xml @@ -25,8 +25,8 @@ - - + + From fd65737cc20e2a7398343dc2a31d6ce6ecb1911b Mon Sep 17 00:00:00 2001 From: Yuki Takagi Date: Thu, 15 Feb 2024 14:32:29 +0900 Subject: [PATCH 04/41] set lidar horizontal FOV angle Signed-off-by: Yuki Takagi --- aip_xx1_launch/launch/lidar.launch.xml | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/aip_xx1_launch/launch/lidar.launch.xml b/aip_xx1_launch/launch/lidar.launch.xml index 26845221..89acee3a 100644 --- a/aip_xx1_launch/launch/lidar.launch.xml +++ b/aip_xx1_launch/launch/lidar.launch.xml @@ -35,8 +35,8 @@ - - + + @@ -52,8 +52,8 @@ - - + + @@ -69,8 +69,8 @@ - - + + @@ -78,7 +78,7 @@ - + @@ -86,8 +86,8 @@ - - + + From 79efd42229c0037a940f25756ee65ce12274ac5d Mon Sep 17 00:00:00 2001 From: Yuki Takagi Date: Thu, 15 Feb 2024 15:05:04 +0900 Subject: [PATCH 05/41] update settings Signed-off-by: Yuki Takagi --- .../config/sensors_calibration.yaml | 14 ++++----- aip_xx1_launch/launch/lidar.launch.xml | 30 +++++++++---------- 2 files changed, 22 insertions(+), 22 deletions(-) diff --git a/aip_xx1_description/config/sensors_calibration.yaml b/aip_xx1_description/config/sensors_calibration.yaml index 4ae5a152..95a93435 100644 --- a/aip_xx1_description/config/sensors_calibration.yaml +++ b/aip_xx1_description/config/sensors_calibration.yaml @@ -6,21 +6,21 @@ base_link: roll: 0.0 pitch: 0.0 yaw: 0.0 - hesai_front_right_base_link: + hesai_front_left_base_link: x: 3.373 # Design Value - y: -0.740 # Design Value + y: 0.740 # Design Value z: 0.5482 roll: 0.0 # Design Value pitch: 0.0 # Design Value - yaw: -0.872665 # Design Value - hesai_front_left_base_link: + yaw: 0.872665 # Design Value + hesai_front_right_base_link: x: 3.373 # Design Value - y: 0.740 # Design Value + y: -0.740 # Design Value z: 0.5482 roll: 0.0 # Design Value pitch: 0.0 # Design Value - yaw: 0.872665 # Design Value - velodyne_rear_base_link: + yaw: -0.872665 # Design Value + velodyne_rear_base_link: #unused x: -0.358 y: 0.0 z: 1.631 diff --git a/aip_xx1_launch/launch/lidar.launch.xml b/aip_xx1_launch/launch/lidar.launch.xml index 89acee3a..be1772f8 100644 --- a/aip_xx1_launch/launch/lidar.launch.xml +++ b/aip_xx1_launch/launch/lidar.launch.xml @@ -14,12 +14,12 @@ - - + + - + @@ -29,12 +29,12 @@ - - + + - + @@ -46,12 +46,12 @@ - - + + - + @@ -63,12 +63,12 @@ - - + + - + @@ -80,12 +80,12 @@ - - + + - + From 06c054790935202f45e3928a73110b2b8953530d Mon Sep 17 00:00:00 2001 From: Yuki Takagi Date: Thu, 15 Feb 2024 15:21:00 +0900 Subject: [PATCH 06/41] update Signed-off-by: Yuki Takagi --- aip_xx1_launch/launch/lidar.launch.xml | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/aip_xx1_launch/launch/lidar.launch.xml b/aip_xx1_launch/launch/lidar.launch.xml index be1772f8..8f8b111a 100644 --- a/aip_xx1_launch/launch/lidar.launch.xml +++ b/aip_xx1_launch/launch/lidar.launch.xml @@ -14,7 +14,6 @@ - @@ -29,7 +28,7 @@ - + @@ -46,7 +45,7 @@ - + @@ -63,7 +62,7 @@ - + @@ -80,7 +79,7 @@ - + From 2e0edd280fca2932374f6904745151d12736f382 Mon Sep 17 00:00:00 2001 From: Yuki Takagi Date: Thu, 15 Feb 2024 17:18:28 +0900 Subject: [PATCH 07/41] add OT128 launch Signed-off-by: Yuki Takagi --- .../launch/hesai_OT128.launch.xml | 36 +++++++++++++++++++ 1 file changed, 36 insertions(+) create mode 100644 common_sensor_launch/launch/hesai_OT128.launch.xml diff --git a/common_sensor_launch/launch/hesai_OT128.launch.xml b/common_sensor_launch/launch/hesai_OT128.launch.xml new file mode 100644 index 00000000..492b56f3 --- /dev/null +++ b/common_sensor_launch/launch/hesai_OT128.launch.xml @@ -0,0 +1,36 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From 106edb705f69f3b2584ebec810ffe0db3a73d624 Mon Sep 17 00:00:00 2001 From: "yuki.takagi@car_8" Date: Thu, 22 Feb 2024 17:45:31 +0900 Subject: [PATCH 08/41] add ptp param Signed-off-by: yuki.takagi@car_8 --- common_sensor_launch/launch/hesai_OT128.launch.xml | 2 ++ common_sensor_launch/launch/nebula_node_container.launch.py | 5 +++++ 2 files changed, 7 insertions(+) diff --git a/common_sensor_launch/launch/hesai_OT128.launch.xml b/common_sensor_launch/launch/hesai_OT128.launch.xml index 492b56f3..ccfaced0 100644 --- a/common_sensor_launch/launch/hesai_OT128.launch.xml +++ b/common_sensor_launch/launch/hesai_OT128.launch.xml @@ -32,5 +32,7 @@ + + diff --git a/common_sensor_launch/launch/nebula_node_container.launch.py b/common_sensor_launch/launch/nebula_node_container.launch.py index c14c1390..f4054af4 100644 --- a/common_sensor_launch/launch/nebula_node_container.launch.py +++ b/common_sensor_launch/launch/nebula_node_container.launch.py @@ -234,6 +234,8 @@ def create_parameter_dict(*args): "packet_mtu_size", "dual_return_distance_threshold", "setup_sensor", + "ptp_profile", + "ptp_transport_type", ), } ], @@ -283,6 +285,9 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg("use_multithread", "False", "use multithread") add_launch_arg("use_intra_process", "False", "use ROS 2 component container communication") add_launch_arg("container_name", "nebula_node_container") + add_launch_arg("ptp_profile", "1588v2") + add_launch_arg("ptp_transport_type", "L2") + set_container_executable = SetLaunchConfiguration( "container_executable", From dec266855ea7b653579e85da2042a18c896748fe Mon Sep 17 00:00:00 2001 From: "yuki.takagi@car_8" Date: Wed, 28 Feb 2024 13:21:18 +0900 Subject: [PATCH 09/41] complete to write lidar settings Signed-off-by: yuki.takagi@car_8 --- .../config/sensors_calibration.yaml | 14 +++++----- aip_xx1_description/urdf/sensors.xacro | 8 +++--- aip_xx1_launch/launch/lidar.launch.xml | 26 +++++++++---------- aip_xx1_launch/launch/sensing.launch.xml | 12 ++++----- .../launch/hesai_XT32.launch.xml | 2 ++ 5 files changed, 32 insertions(+), 30 deletions(-) diff --git a/aip_xx1_description/config/sensors_calibration.yaml b/aip_xx1_description/config/sensors_calibration.yaml index 95a93435..f55dad76 100644 --- a/aip_xx1_description/config/sensors_calibration.yaml +++ b/aip_xx1_description/config/sensors_calibration.yaml @@ -20,13 +20,13 @@ base_link: roll: 0.0 # Design Value pitch: 0.0 # Design Value yaw: -0.872665 # Design Value - velodyne_rear_base_link: #unused - x: -0.358 - y: 0.0 - z: 1.631 - roll: -0.02 - pitch: 0.7281317 - yaw: 3.141592 + # velodyne_rear_base_link: #unused + # x: -0.358 + # y: 0.0 + # z: 1.631 + # roll: -0.02 + # pitch: 0.7281317 + # yaw: 3.141592 ars548_front_center_base_link: x: 3.520 # Design Value y: 0.0 # Design Value diff --git a/aip_xx1_description/urdf/sensors.xacro b/aip_xx1_description/urdf/sensors.xacro index 4bff759f..4ab453ba 100644 --- a/aip_xx1_description/urdf/sensors.xacro +++ b/aip_xx1_description/urdf/sensors.xacro @@ -16,7 +16,7 @@ yaw="${calibration['base_link']['sensor_kit_base_link']['yaw']}" /> - + - + diff --git a/aip_xx1_launch/launch/lidar.launch.xml b/aip_xx1_launch/launch/lidar.launch.xml index 8f8b111a..1fd2efb8 100644 --- a/aip_xx1_launch/launch/lidar.launch.xml +++ b/aip_xx1_launch/launch/lidar.launch.xml @@ -13,7 +13,7 @@ - + @@ -27,13 +27,13 @@ - + - + - + @@ -47,10 +47,10 @@ - + - + @@ -61,13 +61,13 @@ - + - - + + - + @@ -80,11 +80,11 @@ - - + + - + diff --git a/aip_xx1_launch/launch/sensing.launch.xml b/aip_xx1_launch/launch/sensing.launch.xml index ba6b935c..db7c3dfb 100644 --- a/aip_xx1_launch/launch/sensing.launch.xml +++ b/aip_xx1_launch/launch/sensing.launch.xml @@ -23,19 +23,19 @@ --> - + - + - + diff --git a/common_sensor_launch/launch/hesai_XT32.launch.xml b/common_sensor_launch/launch/hesai_XT32.launch.xml index c47f05fd..7ec89fb8 100644 --- a/common_sensor_launch/launch/hesai_XT32.launch.xml +++ b/common_sensor_launch/launch/hesai_XT32.launch.xml @@ -12,6 +12,7 @@ + @@ -27,6 +28,7 @@ + From 168aac29cebe214c224e1bedd8468446f875da09 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Wed, 28 Feb 2024 05:07:12 +0000 Subject: [PATCH 10/41] ci(pre-commit): autofix --- common_sensor_launch/launch/nebula_node_container.launch.py | 1 - 1 file changed, 1 deletion(-) diff --git a/common_sensor_launch/launch/nebula_node_container.launch.py b/common_sensor_launch/launch/nebula_node_container.launch.py index f4054af4..abb72290 100644 --- a/common_sensor_launch/launch/nebula_node_container.launch.py +++ b/common_sensor_launch/launch/nebula_node_container.launch.py @@ -288,7 +288,6 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg("ptp_profile", "1588v2") add_launch_arg("ptp_transport_type", "L2") - set_container_executable = SetLaunchConfiguration( "container_executable", "component_container", From 78d388ba73c751688b7b09c7e326abaf3ecbaef9 Mon Sep 17 00:00:00 2001 From: Kenzo Lobos-Tsunekawa Date: Wed, 21 Feb 2024 18:17:45 +0900 Subject: [PATCH 11/41] chore: generalized radar names Signed-off-by: Kenzo Lobos-Tsunekawa --- .../config/sensors_calibration.yaml | 12 +-- aip_xx1_description/urdf/sensors.xacro | 84 +++++++++---------- 2 files changed, 48 insertions(+), 48 deletions(-) diff --git a/aip_xx1_description/config/sensors_calibration.yaml b/aip_xx1_description/config/sensors_calibration.yaml index f55dad76..5121000a 100644 --- a/aip_xx1_description/config/sensors_calibration.yaml +++ b/aip_xx1_description/config/sensors_calibration.yaml @@ -27,42 +27,42 @@ base_link: # roll: -0.02 # pitch: 0.7281317 # yaw: 3.141592 - ars548_front_center_base_link: + front_center/radar_link: x: 3.520 # Design Value y: 0.0 # Design Value z: 0.6352 roll: 0.0 # Design Value pitch: 0.0 # Design Value yaw: 0.0 # Design Value - ars548_front_right_base_link: + front_right/radar_link: x: 3.384 # Design Value y: -0.7775 # Design Value z: 0.410 roll: 0.0 # Design Value pitch: 0.0 # Design Value yaw: -1.22173 # Design Value - ars548_front_left_base_link: + front_left/radar_link: x: 3.384 # Design Value y: 0.7775 # Design Value z: 0.410 roll: 0.0 # Design Value pitch: 0.0 # Design Value yaw: 1.22173 # Design Value - ars548_back_center_base_link: + rear_center/radar_link: x: -0.858 # Design Value y: 0.0 # Design Value z: 0.520 roll: 0.0 # Design Value pitch: 0.0 # Design Value yaw: 3.141592 # Design Value - ars548_back_right_base_link: + rear_right/radar_link: x: -0.782 # Design Value y: -0.761 # Design Value z: 0.520 roll: 0.0 # Design Value pitch: 0.0 # Design Value yaw: -2.0944 # Design Value - ars548_back_left_base_link: + rear_left/radar_link: x: -0.782 # Design Value y: 0.761 # Design Value z: 0.520 diff --git a/aip_xx1_description/urdf/sensors.xacro b/aip_xx1_description/urdf/sensors.xacro index 4ab453ba..b92bb19b 100644 --- a/aip_xx1_description/urdf/sensors.xacro +++ b/aip_xx1_description/urdf/sensors.xacro @@ -59,63 +59,63 @@ From 1bd6ef936fcf0326dc266aa2459de8336e6bd07f Mon Sep 17 00:00:00 2001 From: "yuki.takagi@car_8" Date: Wed, 28 Feb 2024 15:05:20 +0900 Subject: [PATCH 12/41] feat(aip_xx1_description): update side lidar name Signed-off-by: yuki.takagi@car_8 --- aip_xx1_description/urdf/sensor_kit.xacro | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/aip_xx1_description/urdf/sensor_kit.xacro b/aip_xx1_description/urdf/sensor_kit.xacro index 647d70d7..73472fc9 100644 --- a/aip_xx1_description/urdf/sensor_kit.xacro +++ b/aip_xx1_description/urdf/sensor_kit.xacro @@ -35,7 +35,7 @@ yaw="${calibration['sensor_kit_base_link']['hesai_top_base_link']['yaw']}" /> Date: Wed, 28 Feb 2024 15:07:43 +0900 Subject: [PATCH 13/41] feat(aip_xx1_launch): enable imu in adm ecus Signed-off-by: yuki.takagi@car_8 --- aip_xx1_launch/launch/imu.launch.xml | 22 ++++++++++++++-------- aip_xx1_launch/launch/sensing.launch.xml | 4 ++-- 2 files changed, 16 insertions(+), 10 deletions(-) diff --git a/aip_xx1_launch/launch/imu.launch.xml b/aip_xx1_launch/launch/imu.launch.xml index b764d598..22f42d39 100644 --- a/aip_xx1_launch/launch/imu.launch.xml +++ b/aip_xx1_launch/launch/imu.launch.xml @@ -1,22 +1,28 @@ - - - + + + + + - - - - + + + + + + + + - + diff --git a/aip_xx1_launch/launch/sensing.launch.xml b/aip_xx1_launch/launch/sensing.launch.xml index db7c3dfb..a4468878 100644 --- a/aip_xx1_launch/launch/sensing.launch.xml +++ b/aip_xx1_launch/launch/sensing.launch.xml @@ -23,9 +23,9 @@ --> - + - + - Date: Tue, 5 Mar 2024 17:29:10 +0900 Subject: [PATCH 20/41] fix bug Signed-off-by: Yukihiro Saito --- aip_xx1_description/urdf/sensor_kit.xacro | 1 + 1 file changed, 1 insertion(+) diff --git a/aip_xx1_description/urdf/sensor_kit.xacro b/aip_xx1_description/urdf/sensor_kit.xacro index 3f99c698..8830a4d3 100644 --- a/aip_xx1_description/urdf/sensor_kit.xacro +++ b/aip_xx1_description/urdf/sensor_kit.xacro @@ -2,6 +2,7 @@ + From 3a32bfdccf5d14eaee53836e59ea2f576e81d00b Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Tue, 5 Mar 2024 20:16:13 +0900 Subject: [PATCH 21/41] change max_range --- aip_xx1_launch/launch/lidar.launch.xml | 9 +++++---- common_sensor_launch/launch/hesai_XT32.launch.xml | 1 - 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/aip_xx1_launch/launch/lidar.launch.xml b/aip_xx1_launch/launch/lidar.launch.xml index 1fd2efb8..7f77ad2d 100644 --- a/aip_xx1_launch/launch/lidar.launch.xml +++ b/aip_xx1_launch/launch/lidar.launch.xml @@ -14,6 +14,7 @@ + @@ -28,7 +29,7 @@ - + @@ -45,7 +46,7 @@ - + @@ -62,7 +63,7 @@ - + @@ -79,7 +80,7 @@ - + diff --git a/common_sensor_launch/launch/hesai_XT32.launch.xml b/common_sensor_launch/launch/hesai_XT32.launch.xml index 7ec89fb8..1a77c267 100644 --- a/common_sensor_launch/launch/hesai_XT32.launch.xml +++ b/common_sensor_launch/launch/hesai_XT32.launch.xml @@ -12,7 +12,6 @@ - From c714228111dc628e41ba501838f15471a08f8e16 Mon Sep 17 00:00:00 2001 From: j4tfwm6z Date: Mon, 11 Mar 2024 14:26:33 +0900 Subject: [PATCH 22/41] feat: added the radars to the aip launcher and description Signed-off-by: j4tfwm6z --- .../config/sensors_calibration.yaml | 12 +- aip_xx1_description/urdf/sensors.xacro | 4 +- aip_xx1_launch/launch/radar.launch.xml | 142 ++++++++++++++++-- 3 files changed, 141 insertions(+), 17 deletions(-) diff --git a/aip_xx1_description/config/sensors_calibration.yaml b/aip_xx1_description/config/sensors_calibration.yaml index 9d4bbed6..a57d3ea9 100644 --- a/aip_xx1_description/config/sensors_calibration.yaml +++ b/aip_xx1_description/config/sensors_calibration.yaml @@ -27,42 +27,42 @@ base_link: # roll: -0.02 # pitch: 0.7281317 # yaw: 3.141592 - ars548_front_center_base_link: + front_center/radar_link: x: 3.520 # Design Value y: 0.0 # Design Value z: 0.6352 roll: 0.0 # Design Value pitch: 0.0 # Design Value yaw: 0.0 # Design Value - ars548_front_right_base_link: + front_right/radar_link: x: 3.384 # Design Value y: -0.7775 # Design Value z: 0.410 roll: 0.0 # Design Value pitch: 0.0 # Design Value yaw: -1.22173 # Design Value - ars548_front_left_base_link: + front_left/radar_link: x: 3.384 # Design Value y: 0.7775 # Design Value z: 0.410 roll: 0.0 # Design Value pitch: 0.0 # Design Value yaw: 1.22173 # Design Value - ars548_back_center_base_link: + rear_center/radar_link: x: -0.858 # Design Value y: 0.0 # Design Value z: 0.520 roll: 0.0 # Design Value pitch: 0.0 # Design Value yaw: 3.141592 # Design Value - ars548_back_right_base_link: + rear_right/radar_link: x: -0.782 # Design Value y: -0.761 # Design Value z: 0.520 roll: 0.0 # Design Value pitch: 0.0 # Design Value yaw: -2.0944 # Design Value - ars548_back_left_base_link: + rear_left/radar_link: x: -0.782 # Design Value y: 0.761 # Design Value z: 0.520 diff --git a/aip_xx1_description/urdf/sensors.xacro b/aip_xx1_description/urdf/sensors.xacro index b92bb19b..f6899f14 100644 --- a/aip_xx1_description/urdf/sensors.xacro +++ b/aip_xx1_description/urdf/sensors.xacro @@ -57,7 +57,7 @@ /> - + /> diff --git a/aip_xx1_launch/launch/radar.launch.xml b/aip_xx1_launch/launch/radar.launch.xml index 44d24722..6b842d4f 100644 --- a/aip_xx1_launch/launch/radar.launch.xml +++ b/aip_xx1_launch/launch/radar.launch.xml @@ -1,23 +1,147 @@ - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - + + + + + + + + + + + - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From 27676f056c35de5e521b36dbfae2a23f9c4f9347 Mon Sep 17 00:00:00 2001 From: j4tfwm6z Date: Mon, 11 Mar 2024 14:42:13 +0900 Subject: [PATCH 23/41] add nebula argments --- common_sensor_launch/launch/hesai_OT128.launch.xml | 1 + common_sensor_launch/launch/hesai_XT32.launch.xml | 4 ++++ 2 files changed, 5 insertions(+) diff --git a/common_sensor_launch/launch/hesai_OT128.launch.xml b/common_sensor_launch/launch/hesai_OT128.launch.xml index ccfaced0..63b755a1 100644 --- a/common_sensor_launch/launch/hesai_OT128.launch.xml +++ b/common_sensor_launch/launch/hesai_OT128.launch.xml @@ -34,5 +34,6 @@ + diff --git a/common_sensor_launch/launch/hesai_XT32.launch.xml b/common_sensor_launch/launch/hesai_XT32.launch.xml index 1a77c267..b446e499 100644 --- a/common_sensor_launch/launch/hesai_XT32.launch.xml +++ b/common_sensor_launch/launch/hesai_XT32.launch.xml @@ -32,6 +32,10 @@ + + + + From f2a74e1d43e756e7b57332a1072ef459d20a851b Mon Sep 17 00:00:00 2001 From: Kenzo Lobos-Tsunekawa Date: Tue, 12 Mar 2024 19:09:10 +0900 Subject: [PATCH 24/41] fix: fixed naming and enabled the radars Signed-off-by: Kenzo Lobos-Tsunekawa --- aip_xx1_description/urdf/sensors.xacro | 12 ++++++------ aip_xx1_launch/launch/sensing.launch.xml | 4 ++-- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/aip_xx1_description/urdf/sensors.xacro b/aip_xx1_description/urdf/sensors.xacro index f6899f14..64dbf6bb 100644 --- a/aip_xx1_description/urdf/sensors.xacro +++ b/aip_xx1_description/urdf/sensors.xacro @@ -59,7 +59,7 @@ - + From d6f66402767ca5ffafd139489d5b54432bc171f5 Mon Sep 17 00:00:00 2001 From: j4tfwm6z Date: Mon, 11 Mar 2024 14:23:34 +0900 Subject: [PATCH 25/41] fix pointcloud preprocess for multi_lidar_ogm --- .../launch/pointcloud_preprocessor.launch.py | 19 ++++---- .../launch/nebula_node_container.launch.py | 47 ++++++++++++++++++- 2 files changed, 56 insertions(+), 10 deletions(-) diff --git a/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py b/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py index ea35c49d..ed7b3bf5 100644 --- a/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py +++ b/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py @@ -38,22 +38,23 @@ def launch_setup(context, *args, **kwargs): parameters=[ { "input_topics": [ - "/sensing/lidar/top/pointcloud", - "/sensing/lidar/side_left/pointcloud", - "/sensing/lidar/side_right/pointcloud", - "/sensing/lidar/front_left/pointcloud", - "/sensing/lidar/front_right/pointcloud", + "/sensing/lidar/top/pointcloud_before_sync", + # "/sensing/lidar/side_left/pointcloud_before_sync", + # "/sensing/lidar/side_right/pointcloud_before_sync", + # "/sensing/lidar/front_left/pointcloud_before_sync", + # "/sensing/lidar/front_right/pointcloud_before_sync", ], "output_frame": LaunchConfiguration("base_frame"), "input_offset": [ 0.035, - 0.025, - 0.025, - 0.025, - 0.025, + # 0.025, + # 0.025, + # 0.025, + # 0.025, ], # each sensor will wait 60, 70, 70, 70ms "timeout_sec": 0.095, # set shorter than 100ms "input_twist_topic_type": "twist", + "publish_synchronized_pointcloud": True, } ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], diff --git a/common_sensor_launch/launch/nebula_node_container.launch.py b/common_sensor_launch/launch/nebula_node_container.launch.py index abb72290..9047cf18 100644 --- a/common_sensor_launch/launch/nebula_node_container.launch.py +++ b/common_sensor_launch/launch/nebula_node_container.launch.py @@ -115,6 +115,8 @@ def create_parameter_dict(*args): "cloud_min_angle", "cloud_max_angle", "dual_return_distance_threshold", + "setup_sensor", + "retry_hw", ), }, ], @@ -126,6 +128,36 @@ def create_parameter_dict(*args): ) ) + nodes.append( + ComposableNode( + package="nebula_ros", + plugin=sensor_make + "HwMonitorRosWrapper", + name=sensor_make.lower() + "_hw_monitor_ros_wrapper_node", + parameters=[ + { + "sensor_model": sensor_model, + **create_parameter_dict( + "return_mode", + "frame_id", + "scan_phase", + "sensor_ip", + "host_ip", + "data_port", + "gnss_port", + "packet_mtu_size", + "rotation_speed", + "cloud_min_angle", + "cloud_max_angle", + "diag_span", + "dual_return_distance_threshold", + "delay_monitor_ms", + ), + }, + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + ) + cropbox_parameters = create_parameter_dict("input_frame", "output_frame") cropbox_parameters["negative"] = True @@ -188,6 +220,13 @@ def create_parameter_dict(*args): ) ) + # Ring Outlier Filter is the last component in the pipeline, so control the output frame here + if LaunchConfiguration("output_as_sensor_frame").perform(context): + ring_outlier_filter_parameters = {"output_frame": LaunchConfiguration("frame_id")} + else: + ring_outlier_filter_parameters = { + "output_frame": "" + } # keep the output frame as the input frame nodes.append( ComposableNode( package="pointcloud_preprocessor", @@ -195,8 +234,9 @@ def create_parameter_dict(*args): name="ring_outlier_filter", remappings=[ ("input", "rectified/pointcloud_ex"), - ("output", "pointcloud"), + ("output", "pointcloud_before_sync"), ], + parameters=[ring_outlier_filter_parameters], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) ) @@ -236,6 +276,7 @@ def create_parameter_dict(*args): "setup_sensor", "ptp_profile", "ptp_transport_type", + "retry_hw", ), } ], @@ -263,6 +304,7 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg("config_file", "", description="sensor configuration file") add_launch_arg("launch_driver", "True", "do launch driver") add_launch_arg("setup_sensor", "True", "configure sensor") + add_launch_arg("retry_hw", "false", "retry hw") add_launch_arg("sensor_ip", "192.168.1.201", "device ip address") add_launch_arg("host_ip", "255.255.255.255", "host ip address") add_launch_arg("scan_phase", "0.0") @@ -287,6 +329,9 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg("container_name", "nebula_node_container") add_launch_arg("ptp_profile", "1588v2") add_launch_arg("ptp_transport_type", "L2") + add_launch_arg("output_as_sensor_frame", "True", "output final pointcloud in sensor frame") + add_launch_arg("diag_span", "1000", "") + add_launch_arg("delay_monitor_ms", "2000", "") set_container_executable = SetLaunchConfiguration( "container_executable", From c93ee98294e500e09b9fa45aa89443dc9b2b1d73 Mon Sep 17 00:00:00 2001 From: j4tfwm6z Date: Tue, 12 Mar 2024 19:42:07 +0900 Subject: [PATCH 26/41] feat: enable radar launch and concatenation for all lidars Signed-off-by: j4tfwm6z --- .../launch/pointcloud_preprocessor.launch.py | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py b/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py index ed7b3bf5..4aa9736c 100644 --- a/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py +++ b/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py @@ -39,18 +39,18 @@ def launch_setup(context, *args, **kwargs): { "input_topics": [ "/sensing/lidar/top/pointcloud_before_sync", - # "/sensing/lidar/side_left/pointcloud_before_sync", - # "/sensing/lidar/side_right/pointcloud_before_sync", - # "/sensing/lidar/front_left/pointcloud_before_sync", - # "/sensing/lidar/front_right/pointcloud_before_sync", + "/sensing/lidar/side_left/pointcloud_before_sync", + "/sensing/lidar/side_right/pointcloud_before_sync", + "/sensing/lidar/front_left/pointcloud_before_sync", + "/sensing/lidar/front_right/pointcloud_before_sync", ], "output_frame": LaunchConfiguration("base_frame"), "input_offset": [ 0.035, - # 0.025, - # 0.025, - # 0.025, - # 0.025, + 0.025, + 0.025, + 0.025, + 0.025, ], # each sensor will wait 60, 70, 70, 70ms "timeout_sec": 0.095, # set shorter than 100ms "input_twist_topic_type": "twist", From 3d101db6f785d71c003dfee8796845578e0a332b Mon Sep 17 00:00:00 2001 From: j4tfwm6z Date: Tue, 12 Mar 2024 20:03:13 +0900 Subject: [PATCH 27/41] fix(hesai_xt32): update ptp_transport_type from l2 to udp for xt32 Signed-off-by: j4tfwm6z --- common_sensor_launch/launch/hesai_XT32.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common_sensor_launch/launch/hesai_XT32.launch.xml b/common_sensor_launch/launch/hesai_XT32.launch.xml index b446e499..a1a50dbc 100644 --- a/common_sensor_launch/launch/hesai_XT32.launch.xml +++ b/common_sensor_launch/launch/hesai_XT32.launch.xml @@ -33,7 +33,7 @@ - + From ca1192013f2b50d43e1d7cd36405921e3171ac05 Mon Sep 17 00:00:00 2001 From: Kenzo Lobos-Tsunekawa Date: Thu, 14 Mar 2024 19:25:15 +0900 Subject: [PATCH 28/41] feat: added an option to select the frame of the radar objects Signed-off-by: Kenzo Lobos-Tsunekawa --- aip_xx1_launch/launch/radar.launch.xml | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/aip_xx1_launch/launch/radar.launch.xml b/aip_xx1_launch/launch/radar.launch.xml index 6b842d4f..4005c41b 100644 --- a/aip_xx1_launch/launch/radar.launch.xml +++ b/aip_xx1_launch/launch/radar.launch.xml @@ -22,6 +22,7 @@ + @@ -44,6 +45,7 @@ + @@ -66,6 +68,7 @@ + @@ -88,6 +91,7 @@ + @@ -110,6 +114,7 @@ + @@ -132,6 +137,7 @@ + From 56f77a5ecb02a1838ace59733e8b07a5de4e7f26 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 15 Mar 2024 11:54:32 +0900 Subject: [PATCH 29/41] feat: add ptp_switch_type to support latest nebula at 2024/03/15 (#222) Signed-off-by: j4tfwm6z Co-authored-by: j4tfwm6z --- aip_xx1_launch/launch/sensing.launch.xml | 4 ++-- common_sensor_launch/launch/hesai_OT128.launch.xml | 2 ++ common_sensor_launch/launch/hesai_XT32.launch.xml | 1 + common_sensor_launch/launch/nebula_node_container.launch.py | 4 ++++ 4 files changed, 9 insertions(+), 2 deletions(-) diff --git a/aip_xx1_launch/launch/sensing.launch.xml b/aip_xx1_launch/launch/sensing.launch.xml index ba6b935c..e8aa4186 100644 --- a/aip_xx1_launch/launch/sensing.launch.xml +++ b/aip_xx1_launch/launch/sensing.launch.xml @@ -33,9 +33,9 @@ - + diff --git a/common_sensor_launch/launch/hesai_OT128.launch.xml b/common_sensor_launch/launch/hesai_OT128.launch.xml index 63b755a1..7d4713fd 100644 --- a/common_sensor_launch/launch/hesai_OT128.launch.xml +++ b/common_sensor_launch/launch/hesai_OT128.launch.xml @@ -34,6 +34,8 @@ + + diff --git a/common_sensor_launch/launch/hesai_XT32.launch.xml b/common_sensor_launch/launch/hesai_XT32.launch.xml index a1a50dbc..c6ea9b64 100644 --- a/common_sensor_launch/launch/hesai_XT32.launch.xml +++ b/common_sensor_launch/launch/hesai_XT32.launch.xml @@ -33,6 +33,7 @@ + diff --git a/common_sensor_launch/launch/nebula_node_container.launch.py b/common_sensor_launch/launch/nebula_node_container.launch.py index 9047cf18..7b6ee0c2 100644 --- a/common_sensor_launch/launch/nebula_node_container.launch.py +++ b/common_sensor_launch/launch/nebula_node_container.launch.py @@ -276,6 +276,8 @@ def create_parameter_dict(*args): "setup_sensor", "ptp_profile", "ptp_transport_type", + "ptp_switch_type", + "ptp_domain", "retry_hw", ), } @@ -329,6 +331,8 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg("container_name", "nebula_node_container") add_launch_arg("ptp_profile", "1588v2") add_launch_arg("ptp_transport_type", "L2") + add_launch_arg("ptp_switch_type", "TSN") + add_launch_arg("ptp_domain", "0") add_launch_arg("output_as_sensor_frame", "True", "output final pointcloud in sensor frame") add_launch_arg("diag_span", "1000", "") add_launch_arg("delay_monitor_ms", "2000", "") From 8ee46d4f3fd8cfaeec007be075f90bd1b857e3ee Mon Sep 17 00:00:00 2001 From: yoshiri Date: Thu, 21 Mar 2024 13:06:05 +0900 Subject: [PATCH 30/41] feat: add radar feature Signed-off-by: yoshiri --- .../radar_simple_object_merger.param.yaml | 6 ++ aip_xx1_launch/launch/radar.launch.xml | 73 +++++++++++++++++-- 2 files changed, 73 insertions(+), 6 deletions(-) create mode 100644 aip_xx1_launch/config/radar_simple_object_merger.param.yaml diff --git a/aip_xx1_launch/config/radar_simple_object_merger.param.yaml b/aip_xx1_launch/config/radar_simple_object_merger.param.yaml new file mode 100644 index 00000000..a817e0b7 --- /dev/null +++ b/aip_xx1_launch/config/radar_simple_object_merger.param.yaml @@ -0,0 +1,6 @@ +/**: + ros__parameters: + update_rate_hz: 20.0 + new_frame_id: "base_link" + timeout_threshold: 1.0 + input_topics: ["/sensing/radar/front_center/detected_objects", "/sensing/radar/front_left/detected_objects", "/sensing/radar/rear_left/detected_objects", "/sensing/radar/rear_center/detected_objects", "/sensing/radar/rear_right/detected_objects", "/sensing/radar/front_right/detected_objects"] diff --git a/aip_xx1_launch/launch/radar.launch.xml b/aip_xx1_launch/launch/radar.launch.xml index 4005c41b..aba667d9 100644 --- a/aip_xx1_launch/launch/radar.launch.xml +++ b/aip_xx1_launch/launch/radar.launch.xml @@ -4,6 +4,7 @@ + @@ -14,7 +15,7 @@ - + @@ -33,11 +34,20 @@ + + + + + + + + + - + @@ -56,11 +66,20 @@ + + + + + + + + + - + @@ -79,11 +98,20 @@ + + + + + + + + + - + @@ -102,11 +130,20 @@ + + + + + + + + + - + @@ -125,11 +162,20 @@ + + + + + + + + + - + @@ -148,6 +194,21 @@ + + + + + + + + + + + + + + + From 0680405725118bd8835e3528cce6c173cc0216aa Mon Sep 17 00:00:00 2001 From: kminoda Date: Thu, 21 Mar 2024 20:14:39 +0900 Subject: [PATCH 31/41] fix: revert commenting out of radar.launch.xml Signed-off-by: kminoda --- aip_xx1_launch/launch/sensing.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/aip_xx1_launch/launch/sensing.launch.xml b/aip_xx1_launch/launch/sensing.launch.xml index e8aa4186..ba6b935c 100644 --- a/aip_xx1_launch/launch/sensing.launch.xml +++ b/aip_xx1_launch/launch/sensing.launch.xml @@ -33,9 +33,9 @@ - + From 53e0b0f70f6b0b00b8b1cb382f94f328031c7c82 Mon Sep 17 00:00:00 2001 From: Yuxuan Liu Date: Mon, 17 Jun 2024 16:40:43 +0900 Subject: [PATCH 32/41] add new folders Signed-off-by: Yuxuan Liu --- aip_xx1_gen2_launch/CMakeLists.txt | 16 ++ .../sensor_kit.param.yaml | 109 +++++++++ .../sensor_kit.param.yaml | 30 +++ .../radar_simple_object_merger.param.yaml | 6 + .../data/traffic_light_camera.yaml | 20 ++ aip_xx1_gen2_launch/launch/camera.launch.xml | 19 ++ aip_xx1_gen2_launch/launch/gnss.launch.xml | 41 ++++ aip_xx1_gen2_launch/launch/imu.launch.xml | 39 ++++ aip_xx1_gen2_launch/launch/lidar.launch.xml | 106 +++++++++ .../launch/pointcloud_preprocessor.launch.py | 118 ++++++++++ aip_xx1_gen2_launch/launch/radar.launch.xml | 214 ++++++++++++++++++ aip_xx1_gen2_launch/launch/sensing.launch.xml | 49 ++++ aip_xx1_gen2_launch/package.xml | 32 +++ aip_xx1_launch/launch/imu.launch.xml | 24 +- aip_xx1_launch/launch/lidar.launch.xml | 112 +++++---- .../launch/pointcloud_preprocessor.launch.py | 33 +-- aip_xx1_launch/launch/radar.launch.xml | 211 +---------------- 17 files changed, 892 insertions(+), 287 deletions(-) create mode 100644 aip_xx1_gen2_launch/CMakeLists.txt create mode 100644 aip_xx1_gen2_launch/config/diagnostic_aggregator/sensor_kit.param.yaml create mode 100644 aip_xx1_gen2_launch/config/dummy_diag_publisher/sensor_kit.param.yaml create mode 100644 aip_xx1_gen2_launch/config/radar_simple_object_merger.param.yaml create mode 100644 aip_xx1_gen2_launch/data/traffic_light_camera.yaml create mode 100644 aip_xx1_gen2_launch/launch/camera.launch.xml create mode 100644 aip_xx1_gen2_launch/launch/gnss.launch.xml create mode 100644 aip_xx1_gen2_launch/launch/imu.launch.xml create mode 100644 aip_xx1_gen2_launch/launch/lidar.launch.xml create mode 100644 aip_xx1_gen2_launch/launch/pointcloud_preprocessor.launch.py create mode 100644 aip_xx1_gen2_launch/launch/radar.launch.xml create mode 100644 aip_xx1_gen2_launch/launch/sensing.launch.xml create mode 100644 aip_xx1_gen2_launch/package.xml diff --git a/aip_xx1_gen2_launch/CMakeLists.txt b/aip_xx1_gen2_launch/CMakeLists.txt new file mode 100644 index 00000000..7f8d9f60 --- /dev/null +++ b/aip_xx1_gen2_launch/CMakeLists.txt @@ -0,0 +1,16 @@ +cmake_minimum_required(VERSION 3.5) +project(aip_xx1_gen2_launch) + +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_auto_package(INSTALL_TO_SHARE + launch + data + config +) diff --git a/aip_xx1_gen2_launch/config/diagnostic_aggregator/sensor_kit.param.yaml b/aip_xx1_gen2_launch/config/diagnostic_aggregator/sensor_kit.param.yaml new file mode 100644 index 00000000..ab32e0fe --- /dev/null +++ b/aip_xx1_gen2_launch/config/diagnostic_aggregator/sensor_kit.param.yaml @@ -0,0 +1,109 @@ +/**: + ros__parameters: + sensing: + type: diagnostic_aggregator/AnalyzerGroup + path: sensing + analyzers: + node_alive_monitoring: + type: diagnostic_aggregator/AnalyzerGroup + path: node_alive_monitoring + analyzers: + topic_status: + type: diagnostic_aggregator/GenericAnalyzer + path: topic_status + contains: [": sensing_topic_status"] + timeout: 1.0 + + lidar: + type: diagnostic_aggregator/AnalyzerGroup + path: lidar + analyzers: + velodyne: + type: diagnostic_aggregator/AnalyzerGroup + path: velodyne + analyzers: + health_monitoring: + type: diagnostic_aggregator/AnalyzerGroup + path: health_monitoring + analyzers: + connection: + type: diagnostic_aggregator/GenericAnalyzer + path: connection + contains: [": velodyne_connection"] + timeout: 3.0 + + temperature: + type: diagnostic_aggregator/GenericAnalyzer + path: temperature + contains: [": velodyne_temperature"] + timeout: 3.0 + + rpm: + type: diagnostic_aggregator/GenericAnalyzer + path: rpm + contains: [": velodyne_rpm"] + timeout: 3.0 + + gnss: + type: diagnostic_aggregator/AnalyzerGroup + path: gnss + analyzers: + health_monitoring: + type: diagnostic_aggregator/AnalyzerGroup + path: health_monitoring + analyzers: + connection: + type: diagnostic_aggregator/GenericAnalyzer + path: connection + contains: [": gnss_connection"] + timeout: 3.0 + + data: + type: diagnostic_aggregator/GenericAnalyzer + path: data + contains: [": gnss_data"] + timeout: 3.0 + + antenna: + type: diagnostic_aggregator/GenericAnalyzer + path: antenna + contains: [": gnss_antenna"] + timeout: 3.0 + + tx_usage: + type: diagnostic_aggregator/GenericAnalyzer + path: tx_usage + contains: [": gnss_tx_usage"] + timeout: 3.0 + + spoofing: + type: diagnostic_aggregator/GenericAnalyzer + path: spoofing + contains: [": gnss_spoofing"] + timeout: 3.0 + + jamming: + type: diagnostic_aggregator/GenericAnalyzer + path: jamming + contains: [": gnss_jamming"] + timeout: 3.0 + + fix_topic_status: + type: diagnostic_aggregator/GenericAnalyzer + path: fix_topic_status + contains: [": fix topic status"] + timeout: 3.0 + + imu: + type: diagnostic_aggregator/AnalyzerGroup + path: imu + analyzers: + bias_monitoring: + type: diagnostic_aggregator/AnalyzerGroup + path: bias_monitoring + analyzers: + gyro_bias_validator: + type: diagnostic_aggregator/GenericAnalyzer + path: gyro_bias_validator + contains: [": gyro_bias_validator"] + timeout: 1.0 diff --git a/aip_xx1_gen2_launch/config/dummy_diag_publisher/sensor_kit.param.yaml b/aip_xx1_gen2_launch/config/dummy_diag_publisher/sensor_kit.param.yaml new file mode 100644 index 00000000..80cc7944 --- /dev/null +++ b/aip_xx1_gen2_launch/config/dummy_diag_publisher/sensor_kit.param.yaml @@ -0,0 +1,30 @@ +# Description: +# name: diag name +# is_active: Force update or not +# status: diag status set by dummy diag publisher "OK, Warn, Error, Stale" +# +# Note: +# +# default values are: +# is_active: "true" +# status: "OK" +--- +/**: + ros__parameters: + required_diags: + # gnss + gnss_connection: default + gnss_data: default + gnss_antenna: default + gnss_tx_usage: default + gnss_spoofing: default + gnss_jamming: default + fix topic status: default + + # velodyne + velodyne_connection: default + velodyne_temperature: default + velodyne_rpm: default + + # imu + gyro_bias_estimator: default diff --git a/aip_xx1_gen2_launch/config/radar_simple_object_merger.param.yaml b/aip_xx1_gen2_launch/config/radar_simple_object_merger.param.yaml new file mode 100644 index 00000000..a817e0b7 --- /dev/null +++ b/aip_xx1_gen2_launch/config/radar_simple_object_merger.param.yaml @@ -0,0 +1,6 @@ +/**: + ros__parameters: + update_rate_hz: 20.0 + new_frame_id: "base_link" + timeout_threshold: 1.0 + input_topics: ["/sensing/radar/front_center/detected_objects", "/sensing/radar/front_left/detected_objects", "/sensing/radar/rear_left/detected_objects", "/sensing/radar/rear_center/detected_objects", "/sensing/radar/rear_right/detected_objects", "/sensing/radar/front_right/detected_objects"] diff --git a/aip_xx1_gen2_launch/data/traffic_light_camera.yaml b/aip_xx1_gen2_launch/data/traffic_light_camera.yaml new file mode 100644 index 00000000..458ad17c --- /dev/null +++ b/aip_xx1_gen2_launch/data/traffic_light_camera.yaml @@ -0,0 +1,20 @@ +image_width: 1920 +image_height: 1080 +camera_name: traffic_light/camera +camera_matrix: + rows: 3 + cols: 3 + data: [2410.755261, 0.000000, 922.621401, 0.000000, 2403.573140, 534.752500, 0.000000, 0.000000, 1.000000] +distortion_model: plumb_bob +distortion_coefficients: + rows: 1 + cols: 5 + data: [-0.126600, 0.152594, 0.002432, -0.001244, 0.000000] +rectification_matrix: + rows: 3 + cols: 3 + data: [1.000000, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000, 0.000000, 0.000000, 1.000000] +projection_matrix: + rows: 3 + cols: 4 + data: [2370.254883, 0.000000, 920.136018, 0.000000, 0.000000, 2388.885254, 535.599668, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000] diff --git a/aip_xx1_gen2_launch/launch/camera.launch.xml b/aip_xx1_gen2_launch/launch/camera.launch.xml new file mode 100644 index 00000000..041c70c8 --- /dev/null +++ b/aip_xx1_gen2_launch/launch/camera.launch.xml @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + diff --git a/aip_xx1_gen2_launch/launch/gnss.launch.xml b/aip_xx1_gen2_launch/launch/gnss.launch.xml new file mode 100644 index 00000000..37ad6bde --- /dev/null +++ b/aip_xx1_gen2_launch/launch/gnss.launch.xml @@ -0,0 +1,41 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/aip_xx1_gen2_launch/launch/imu.launch.xml b/aip_xx1_gen2_launch/launch/imu.launch.xml new file mode 100644 index 00000000..7f1f0337 --- /dev/null +++ b/aip_xx1_gen2_launch/launch/imu.launch.xml @@ -0,0 +1,39 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/aip_xx1_gen2_launch/launch/lidar.launch.xml b/aip_xx1_gen2_launch/launch/lidar.launch.xml new file mode 100644 index 00000000..7f77ad2d --- /dev/null +++ b/aip_xx1_gen2_launch/launch/lidar.launch.xml @@ -0,0 +1,106 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/aip_xx1_gen2_launch/launch/pointcloud_preprocessor.launch.py b/aip_xx1_gen2_launch/launch/pointcloud_preprocessor.launch.py new file mode 100644 index 00000000..4aa9736c --- /dev/null +++ b/aip_xx1_gen2_launch/launch/pointcloud_preprocessor.launch.py @@ -0,0 +1,118 @@ +# Copyright 2020 Tier IV, Inc. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + + +import launch +from launch.actions import DeclareLaunchArgument +from launch.actions import OpaqueFunction +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import LoadComposableNodes +from launch_ros.descriptions import ComposableNode + + +def launch_setup(context, *args, **kwargs): + # set concat filter as a component + concat_component = ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", + name="concatenate_data", + remappings=[ + ("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"), + ("output", "concatenated/pointcloud"), + ], + parameters=[ + { + "input_topics": [ + "/sensing/lidar/top/pointcloud_before_sync", + "/sensing/lidar/side_left/pointcloud_before_sync", + "/sensing/lidar/side_right/pointcloud_before_sync", + "/sensing/lidar/front_left/pointcloud_before_sync", + "/sensing/lidar/front_right/pointcloud_before_sync", + ], + "output_frame": LaunchConfiguration("base_frame"), + "input_offset": [ + 0.035, + 0.025, + 0.025, + 0.025, + 0.025, + ], # each sensor will wait 60, 70, 70, 70ms + "timeout_sec": 0.095, # set shorter than 100ms + "input_twist_topic_type": "twist", + "publish_synchronized_pointcloud": True, + } + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + # set container to run all required components in the same process + container = ComposableNodeContainer( + name=LaunchConfiguration("individual_container_name"), + namespace="", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), + condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), + output="screen", + ) + + target_container = ( + container + if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context) + else LaunchConfiguration("pointcloud_container_name") + ) + + # load concat or passthrough filter + concat_loader = LoadComposableNodes( + composable_node_descriptions=[concat_component], + target_container=target_container, + condition=IfCondition(LaunchConfiguration("use_concat_filter")), + ) + + return [container, concat_loader] + + +def generate_launch_description(): + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None): + launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + + add_launch_arg("base_frame", "base_link") + add_launch_arg("use_multithread", "False") + add_launch_arg("use_intra_process", "False") + add_launch_arg("use_pointcloud_container", "False") + add_launch_arg("pointcloud_container_name", "pointcloud_container") + add_launch_arg("individual_container_name", "concatenate_container") + + set_container_executable = SetLaunchConfiguration( + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), + ) + + set_container_mt_executable = SetLaunchConfiguration( + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), + ) + + return launch.LaunchDescription( + launch_arguments + + [set_container_executable, set_container_mt_executable] + + [OpaqueFunction(function=launch_setup)] + ) diff --git a/aip_xx1_gen2_launch/launch/radar.launch.xml b/aip_xx1_gen2_launch/launch/radar.launch.xml new file mode 100644 index 00000000..aba667d9 --- /dev/null +++ b/aip_xx1_gen2_launch/launch/radar.launch.xml @@ -0,0 +1,214 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/aip_xx1_gen2_launch/launch/sensing.launch.xml b/aip_xx1_gen2_launch/launch/sensing.launch.xml new file mode 100644 index 00000000..ba6b935c --- /dev/null +++ b/aip_xx1_gen2_launch/launch/sensing.launch.xml @@ -0,0 +1,49 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/aip_xx1_gen2_launch/package.xml b/aip_xx1_gen2_launch/package.xml new file mode 100644 index 00000000..8f2f9df9 --- /dev/null +++ b/aip_xx1_gen2_launch/package.xml @@ -0,0 +1,32 @@ + + + + aip_xx1_gen2_launch + 0.1.0 + The aip_xx1_gen2_launch package + + Hiroki OTA + Apache License 2.0 + + ament_cmake_auto + + common_sensor_launch + glog_component + gnss_poser + imu_corrector + pacmod3 + pointcloud_preprocessor + ros2_socketcan + tamagawa_imu_driver + topic_tools + ublox_gps + usb_cam + vehicle_velocity_converter + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/aip_xx1_launch/launch/imu.launch.xml b/aip_xx1_launch/launch/imu.launch.xml index 7f1f0337..f0509930 100644 --- a/aip_xx1_launch/launch/imu.launch.xml +++ b/aip_xx1_launch/launch/imu.launch.xml @@ -1,23 +1,17 @@ + + + - - - - - - - - - - - - - + + + + @@ -29,11 +23,13 @@ + + - + \ No newline at end of file diff --git a/aip_xx1_launch/launch/lidar.launch.xml b/aip_xx1_launch/launch/lidar.launch.xml index 7f77ad2d..1b5bef3c 100644 --- a/aip_xx1_launch/launch/lidar.launch.xml +++ b/aip_xx1_launch/launch/lidar.launch.xml @@ -5,102 +5,124 @@ - + - - - + + + - + + + + + + - - - - - + + + + + - - - + + + + + + + + - - - - - + + + + + - - - + + + + + + + + - - - - - + + + + + - - - + + + + + + + + - - - - - - - - - - - - - - + + - - + \ No newline at end of file diff --git a/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py b/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py index 4aa9736c..a5d67206 100644 --- a/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py +++ b/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py @@ -20,7 +20,6 @@ from launch.conditions import IfCondition from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode @@ -39,10 +38,9 @@ def launch_setup(context, *args, **kwargs): { "input_topics": [ "/sensing/lidar/top/pointcloud_before_sync", - "/sensing/lidar/side_left/pointcloud_before_sync", - "/sensing/lidar/side_right/pointcloud_before_sync", - "/sensing/lidar/front_left/pointcloud_before_sync", - "/sensing/lidar/front_right/pointcloud_before_sync", + "/sensing/lidar/left/pointcloud_before_sync", + "/sensing/lidar/right/pointcloud_before_sync", + "/sensing/lidar/rear/pointcloud_before_sync", ], "output_frame": LaunchConfiguration("base_frame"), "input_offset": [ @@ -50,7 +48,6 @@ def launch_setup(context, *args, **kwargs): 0.025, 0.025, 0.025, - 0.025, ], # each sensor will wait 60, 70, 70, 70ms "timeout_sec": 0.095, # set shorter than 100ms "input_twist_topic_type": "twist", @@ -60,30 +57,14 @@ def launch_setup(context, *args, **kwargs): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) - # set container to run all required components in the same process - container = ComposableNodeContainer( - name=LaunchConfiguration("individual_container_name"), - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), - output="screen", - ) - - target_container = ( - container - if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context) - else LaunchConfiguration("pointcloud_container_name") - ) - # load concat or passthrough filter concat_loader = LoadComposableNodes( composable_node_descriptions=[concat_component], - target_container=target_container, + target_container=LaunchConfiguration("pointcloud_container_name"), condition=IfCondition(LaunchConfiguration("use_concat_filter")), ) - return [container, concat_loader] + return [concat_loader] def generate_launch_description(): @@ -95,9 +76,7 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("base_frame", "base_link") add_launch_arg("use_multithread", "False") add_launch_arg("use_intra_process", "False") - add_launch_arg("use_pointcloud_container", "False") add_launch_arg("pointcloud_container_name", "pointcloud_container") - add_launch_arg("individual_container_name", "concatenate_container") set_container_executable = SetLaunchConfiguration( "container_executable", @@ -115,4 +94,4 @@ def add_launch_arg(name: str, default_value=None): launch_arguments + [set_container_executable, set_container_mt_executable] + [OpaqueFunction(function=launch_setup)] - ) + ) \ No newline at end of file diff --git a/aip_xx1_launch/launch/radar.launch.xml b/aip_xx1_launch/launch/radar.launch.xml index aba667d9..f8ede59f 100644 --- a/aip_xx1_launch/launch/radar.launch.xml +++ b/aip_xx1_launch/launch/radar.launch.xml @@ -1,214 +1,23 @@ - - - - - - + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + - - - - - - - + \ No newline at end of file From 2e95c3c1d06b721bead30cc14d250eae51c5457e Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 17 Jun 2024 07:42:31 +0000 Subject: [PATCH 33/41] ci(pre-commit): autofix --- aip_xx1_gen2_launch/launch/radar.launch.xml | 12 ++++++------ aip_xx1_launch/launch/imu.launch.xml | 2 +- aip_xx1_launch/launch/lidar.launch.xml | 2 +- .../launch/pointcloud_preprocessor.launch.py | 2 +- aip_xx1_launch/launch/radar.launch.xml | 2 +- 5 files changed, 10 insertions(+), 10 deletions(-) diff --git a/aip_xx1_gen2_launch/launch/radar.launch.xml b/aip_xx1_gen2_launch/launch/radar.launch.xml index aba667d9..1f9b16e6 100644 --- a/aip_xx1_gen2_launch/launch/radar.launch.xml +++ b/aip_xx1_gen2_launch/launch/radar.launch.xml @@ -34,7 +34,7 @@ - + @@ -106,7 +106,7 @@ - + @@ -138,7 +138,7 @@ - + @@ -170,7 +170,7 @@ - + @@ -201,12 +201,12 @@ - + - + diff --git a/aip_xx1_launch/launch/imu.launch.xml b/aip_xx1_launch/launch/imu.launch.xml index f0509930..85b620d7 100644 --- a/aip_xx1_launch/launch/imu.launch.xml +++ b/aip_xx1_launch/launch/imu.launch.xml @@ -32,4 +32,4 @@ - \ No newline at end of file + diff --git a/aip_xx1_launch/launch/lidar.launch.xml b/aip_xx1_launch/launch/lidar.launch.xml index 1b5bef3c..279bf9f2 100644 --- a/aip_xx1_launch/launch/lidar.launch.xml +++ b/aip_xx1_launch/launch/lidar.launch.xml @@ -125,4 +125,4 @@ - \ No newline at end of file + diff --git a/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py b/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py index a5d67206..726171f9 100644 --- a/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py +++ b/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py @@ -94,4 +94,4 @@ def add_launch_arg(name: str, default_value=None): launch_arguments + [set_container_executable, set_container_mt_executable] + [OpaqueFunction(function=launch_setup)] - ) \ No newline at end of file + ) diff --git a/aip_xx1_launch/launch/radar.launch.xml b/aip_xx1_launch/launch/radar.launch.xml index f8ede59f..44d24722 100644 --- a/aip_xx1_launch/launch/radar.launch.xml +++ b/aip_xx1_launch/launch/radar.launch.xml @@ -20,4 +20,4 @@ - \ No newline at end of file + From a6185441cd38b113f1bc661f69eb14c9aac5f895 Mon Sep 17 00:00:00 2001 From: Yuxuan Liu Date: Mon, 17 Jun 2024 16:44:39 +0900 Subject: [PATCH 34/41] add folders for description Signed-off-by: Yuxuan Liu --- .../config/sensor_kit_calibration.yaml | 181 ++++++------- .../config/sensors_calibration.yaml | 93 ++----- aip_xx1_description/urdf/sensor_kit.xacro | 133 ++++----- aip_xx1_description/urdf/sensors.xacro | 111 +++----- aip_xx1_gen2_description/CMakeLists.txt | 11 + .../config/sensor_kit_calibration.yaml | 113 ++++++++ .../config/sensors_calibration.yaml | 71 +++++ aip_xx1_gen2_description/package.xml | 17 ++ .../urdf/sensor_kit.xacro | 253 ++++++++++++++++++ aip_xx1_gen2_description/urdf/sensors.xacro | 121 +++++++++ .../radar_simple_object_merger.param.yaml | 6 - 11 files changed, 780 insertions(+), 330 deletions(-) create mode 100644 aip_xx1_gen2_description/CMakeLists.txt create mode 100644 aip_xx1_gen2_description/config/sensor_kit_calibration.yaml create mode 100644 aip_xx1_gen2_description/config/sensors_calibration.yaml create mode 100644 aip_xx1_gen2_description/package.xml create mode 100644 aip_xx1_gen2_description/urdf/sensor_kit.xacro create mode 100644 aip_xx1_gen2_description/urdf/sensors.xacro delete mode 100644 aip_xx1_launch/config/radar_simple_object_merger.param.yaml diff --git a/aip_xx1_description/config/sensor_kit_calibration.yaml b/aip_xx1_description/config/sensor_kit_calibration.yaml index 88288533..b3c920c6 100644 --- a/aip_xx1_description/config/sensor_kit_calibration.yaml +++ b/aip_xx1_description/config/sensor_kit_calibration.yaml @@ -1,113 +1,92 @@ sensor_kit_base_link: camera0/camera_link: - x: 0.372 # Design Value - y: 0.0 # Design Value - z: -0.207 # Design Value - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: 0.0 # Design Value + x: 0.10731 + y: 0.56343 + z: -0.27697 + roll: -0.025 + pitch: 0.315 + yaw: 1.035 camera1/camera_link: - x: 0.372 # Design Value - y: 0.045 # Design Value - z: -0.207 # Design Value - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: 0.0 # Design Value + x: -0.10731 + y: -0.56343 + z: -0.27697 + roll: -0.025 + pitch: 0.32 + yaw: -2.12 camera2/camera_link: - x: 0.372 # Design Value - y: -0.045 # Design Value - z: -0.207 # Design Value - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: 0.0 # Design Value + x: 0.10731 + y: -0.56343 + z: -0.27697 + roll: -0.00 + pitch: 0.335 + yaw: -1.04 camera3/camera_link: - x: 0.133 # Design Value - y: 0.498 # Design Value - z: -0.246 # Design Value - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: 0.872665 # Design Value + x: -0.10731 + y: 0.56343 + z: -0.27697 + roll: 0.0 + pitch: 0.325 + yaw: 2.0943951 camera4/camera_link: - x: 0.133 # Design Value - y: -0.498 # Design Value - z: -0.246 # Design Value - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: -0.872665 # Design Value + x: 0.07356 + y: 0.0 + z: -0.0525 + roll: 0.0 + pitch: -0.03 + yaw: -0.005 camera5/camera_link: - x: 0.095 # Design Value - y: 0.524 # Design Value - z: -0.246 # Design Value - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: 1.0472 # Design Value + x: -0.07356 + y: 0.0 + z: -0.0525 + roll: 0.0 + pitch: -0.01 + yaw: 3.125 camera6/camera_link: - x: 0.095 # Design Value - y: -0.524 # Design Value - z: -0.246 # Design Value - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: -1.0472 # Design Value + x: 0.05 + y: 0.0175 + z: -0.1 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 camera7/camera_link: - x: -0.345 # Design Value - y: 0.244 # Design Value - z: -0.174 # Design Value - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: 2.70526 # Design Value - camera8/camera_link: - x: -0.345 # Design Value - y: -0.244 # Design Value - z: -0.174 # Design Value - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: -2.70526 # Design Value - camera9/camera_link: - x: -0.362 # Design Value - y: 0.202 # Design Value - z: -0.174 # Design Value - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: 2.79253 # Design Value - camera10/camera_link: - x: -0.362 # Design Value - y: -0.202 # Design Value - z: -0.174 # Design Value - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: -2.79253 # Design Value - hesai_top_base_link: - x: 0.0 # Design Value - y: 0.0 # Design Value - z: 0.0 # Design Value - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: 4.36332298038 # Design Value - hesai_left_base_link: - x: 0.0 # Design Value - y: 0.564 # Design Value - z: -0.300 # Design Value - roll: 0.872665 # Design Value - pitch: 0.0 # Design Value - yaw: 3.14159265359 # Design Value - hesai_right_base_link: - x: 0.0 # Design Value - y: -0.564 # Design Value - z: -0.300 # Design Value - roll: 0.69813132679 # Design Value - pitch: 0.0 # Design Value - yaw: 0.0 # Design Value + x: 0.05 + y: -0.0175 + z: -0.1 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 + velodyne_top_base_link: + x: 0.0 + y: 0.0 + z: 0.0 + roll: 0.0 + pitch: 0.0 + yaw: 1.575 + velodyne_left_base_link: + x: 0.0 + y: 0.56362 + z: -0.30555 + roll: -0.02 + pitch: 0.71 + yaw: 1.575 + velodyne_right_base_link: + x: 0.0 + y: -0.56362 + z: -0.30555 + roll: -0.01 + pitch: 0.71 + yaw: -1.580 gnss_link: - x: -0.279 # Design Value - y: 0.0 # Design Value - z: -0.160 # Design Value - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: 0.0 # Design Value + x: -0.1 + y: 0.0 + z: -0.2 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 tamagawa/imu_link: - x: -0.129 # Design Value - y: 0.0 # Design Value - z: -0.160 # Design Value + x: 0.0 + y: 0.0 + z: 0.0 roll: 3.14159265359 - pitch: 0.0 # Design Value - yaw: 3.14159265359 # Design Value + pitch: 0.0 + yaw: 3.14159265359 \ No newline at end of file diff --git a/aip_xx1_description/config/sensors_calibration.yaml b/aip_xx1_description/config/sensors_calibration.yaml index a57d3ea9..c7389f7e 100644 --- a/aip_xx1_description/config/sensors_calibration.yaml +++ b/aip_xx1_description/config/sensors_calibration.yaml @@ -1,71 +1,36 @@ base_link: + ars408_front_center: + x: 3.8 + y: 0.0 + z: 0.5 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 sensor_kit_base_link: x: 0.9 y: 0.0 z: 2.0 + roll: -0.001 + pitch: 0.015 + yaw: -0.0364 + livox_front_right_base_link: + x: 3.290 + y: -0.65485 + z: 0.3216 roll: 0.0 pitch: 0.0 - yaw: 0.0 - hesai_front_left_base_link: - x: 3.373 # Design Value - y: 0.740 # Design Value - z: 0.5482 - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: 2.44346132679 # Design Value - hesai_front_right_base_link: - x: 3.373 # Design Value - y: -0.740 # Design Value - z: 0.5482 - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: 0.69813132679 # Design Value - # velodyne_rear_base_link: #unused - # x: -0.358 - # y: 0.0 - # z: 1.631 - # roll: -0.02 - # pitch: 0.7281317 - # yaw: 3.141592 - front_center/radar_link: - x: 3.520 # Design Value - y: 0.0 # Design Value - z: 0.6352 - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: 0.0 # Design Value - front_right/radar_link: - x: 3.384 # Design Value - y: -0.7775 # Design Value - z: 0.410 - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: -1.22173 # Design Value - front_left/radar_link: - x: 3.384 # Design Value - y: 0.7775 # Design Value - z: 0.410 - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: 1.22173 # Design Value - rear_center/radar_link: - x: -0.858 # Design Value - y: 0.0 # Design Value - z: 0.520 - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: 3.141592 # Design Value - rear_right/radar_link: - x: -0.782 # Design Value - y: -0.761 # Design Value - z: 0.520 - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: -2.0944 # Design Value - rear_left/radar_link: - x: -0.782 # Design Value - y: 0.761 # Design Value - z: 0.520 - roll: 0.0 # Design Value - pitch: 0.0 # Design Value - yaw: 2.0944 # Design Value + yaw: -0.872664444 + livox_front_left_base_link: + x: 3.290 + y: 0.65485 + z: 0.3016 + roll: -0.021 + pitch: 0.05 + yaw: 0.872664444 + velodyne_rear_base_link: + x: -0.358 + y: 0.0 + z: 1.631 + roll: -0.02 + pitch: 0.7281317 + yaw: 3.141592 \ No newline at end of file diff --git a/aip_xx1_description/urdf/sensor_kit.xacro b/aip_xx1_description/urdf/sensor_kit.xacro index 8830a4d3..e4a6c40d 100644 --- a/aip_xx1_description/urdf/sensor_kit.xacro +++ b/aip_xx1_description/urdf/sensor_kit.xacro @@ -1,9 +1,9 @@ - - + + @@ -25,37 +25,57 @@ - - - - + + + + + + + + + - - - - + \ No newline at end of file diff --git a/aip_xx1_description/urdf/sensors.xacro b/aip_xx1_description/urdf/sensors.xacro index 64dbf6bb..52299371 100644 --- a/aip_xx1_description/urdf/sensors.xacro +++ b/aip_xx1_description/urdf/sensors.xacro @@ -15,8 +15,8 @@ pitch="${calibration['base_link']['sensor_kit_base_link']['pitch']}" yaw="${calibration['base_link']['sensor_kit_base_link']['yaw']}" /> - - + - --> - - + + - - - + + - - - - - - + + \ No newline at end of file diff --git a/aip_xx1_gen2_description/CMakeLists.txt b/aip_xx1_gen2_description/CMakeLists.txt new file mode 100644 index 00000000..50723262 --- /dev/null +++ b/aip_xx1_gen2_description/CMakeLists.txt @@ -0,0 +1,11 @@ +cmake_minimum_required(VERSION 3.5) +project(aip_xx1_description) + +find_package(ament_cmake_auto REQUIRED) + +ament_auto_find_build_dependencies() + +ament_auto_package(INSTALL_TO_SHARE + urdf + config +) diff --git a/aip_xx1_gen2_description/config/sensor_kit_calibration.yaml b/aip_xx1_gen2_description/config/sensor_kit_calibration.yaml new file mode 100644 index 00000000..88288533 --- /dev/null +++ b/aip_xx1_gen2_description/config/sensor_kit_calibration.yaml @@ -0,0 +1,113 @@ +sensor_kit_base_link: + camera0/camera_link: + x: 0.372 # Design Value + y: 0.0 # Design Value + z: -0.207 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 0.0 # Design Value + camera1/camera_link: + x: 0.372 # Design Value + y: 0.045 # Design Value + z: -0.207 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 0.0 # Design Value + camera2/camera_link: + x: 0.372 # Design Value + y: -0.045 # Design Value + z: -0.207 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 0.0 # Design Value + camera3/camera_link: + x: 0.133 # Design Value + y: 0.498 # Design Value + z: -0.246 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 0.872665 # Design Value + camera4/camera_link: + x: 0.133 # Design Value + y: -0.498 # Design Value + z: -0.246 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: -0.872665 # Design Value + camera5/camera_link: + x: 0.095 # Design Value + y: 0.524 # Design Value + z: -0.246 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 1.0472 # Design Value + camera6/camera_link: + x: 0.095 # Design Value + y: -0.524 # Design Value + z: -0.246 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: -1.0472 # Design Value + camera7/camera_link: + x: -0.345 # Design Value + y: 0.244 # Design Value + z: -0.174 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 2.70526 # Design Value + camera8/camera_link: + x: -0.345 # Design Value + y: -0.244 # Design Value + z: -0.174 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: -2.70526 # Design Value + camera9/camera_link: + x: -0.362 # Design Value + y: 0.202 # Design Value + z: -0.174 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 2.79253 # Design Value + camera10/camera_link: + x: -0.362 # Design Value + y: -0.202 # Design Value + z: -0.174 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: -2.79253 # Design Value + hesai_top_base_link: + x: 0.0 # Design Value + y: 0.0 # Design Value + z: 0.0 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 4.36332298038 # Design Value + hesai_left_base_link: + x: 0.0 # Design Value + y: 0.564 # Design Value + z: -0.300 # Design Value + roll: 0.872665 # Design Value + pitch: 0.0 # Design Value + yaw: 3.14159265359 # Design Value + hesai_right_base_link: + x: 0.0 # Design Value + y: -0.564 # Design Value + z: -0.300 # Design Value + roll: 0.69813132679 # Design Value + pitch: 0.0 # Design Value + yaw: 0.0 # Design Value + gnss_link: + x: -0.279 # Design Value + y: 0.0 # Design Value + z: -0.160 # Design Value + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 0.0 # Design Value + tamagawa/imu_link: + x: -0.129 # Design Value + y: 0.0 # Design Value + z: -0.160 # Design Value + roll: 3.14159265359 + pitch: 0.0 # Design Value + yaw: 3.14159265359 # Design Value diff --git a/aip_xx1_gen2_description/config/sensors_calibration.yaml b/aip_xx1_gen2_description/config/sensors_calibration.yaml new file mode 100644 index 00000000..a57d3ea9 --- /dev/null +++ b/aip_xx1_gen2_description/config/sensors_calibration.yaml @@ -0,0 +1,71 @@ +base_link: + sensor_kit_base_link: + x: 0.9 + y: 0.0 + z: 2.0 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 + hesai_front_left_base_link: + x: 3.373 # Design Value + y: 0.740 # Design Value + z: 0.5482 + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 2.44346132679 # Design Value + hesai_front_right_base_link: + x: 3.373 # Design Value + y: -0.740 # Design Value + z: 0.5482 + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 0.69813132679 # Design Value + # velodyne_rear_base_link: #unused + # x: -0.358 + # y: 0.0 + # z: 1.631 + # roll: -0.02 + # pitch: 0.7281317 + # yaw: 3.141592 + front_center/radar_link: + x: 3.520 # Design Value + y: 0.0 # Design Value + z: 0.6352 + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 0.0 # Design Value + front_right/radar_link: + x: 3.384 # Design Value + y: -0.7775 # Design Value + z: 0.410 + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: -1.22173 # Design Value + front_left/radar_link: + x: 3.384 # Design Value + y: 0.7775 # Design Value + z: 0.410 + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 1.22173 # Design Value + rear_center/radar_link: + x: -0.858 # Design Value + y: 0.0 # Design Value + z: 0.520 + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 3.141592 # Design Value + rear_right/radar_link: + x: -0.782 # Design Value + y: -0.761 # Design Value + z: 0.520 + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: -2.0944 # Design Value + rear_left/radar_link: + x: -0.782 # Design Value + y: 0.761 # Design Value + z: 0.520 + roll: 0.0 # Design Value + pitch: 0.0 # Design Value + yaw: 2.0944 # Design Value diff --git a/aip_xx1_gen2_description/package.xml b/aip_xx1_gen2_description/package.xml new file mode 100644 index 00000000..b35b48e0 --- /dev/null +++ b/aip_xx1_gen2_description/package.xml @@ -0,0 +1,17 @@ + + + aip_xx1_description + 0.1.0 + The aip_xx1_description package + + Yukihiro Saito + Apache 2 + + ament_cmake_auto + + velodyne_description + + + ament_cmake + + diff --git a/aip_xx1_gen2_description/urdf/sensor_kit.xacro b/aip_xx1_gen2_description/urdf/sensor_kit.xacro new file mode 100644 index 00000000..8830a4d3 --- /dev/null +++ b/aip_xx1_gen2_description/urdf/sensor_kit.xacro @@ -0,0 +1,253 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/aip_xx1_gen2_description/urdf/sensors.xacro b/aip_xx1_gen2_description/urdf/sensors.xacro new file mode 100644 index 00000000..64dbf6bb --- /dev/null +++ b/aip_xx1_gen2_description/urdf/sensors.xacro @@ -0,0 +1,121 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/aip_xx1_launch/config/radar_simple_object_merger.param.yaml b/aip_xx1_launch/config/radar_simple_object_merger.param.yaml deleted file mode 100644 index a817e0b7..00000000 --- a/aip_xx1_launch/config/radar_simple_object_merger.param.yaml +++ /dev/null @@ -1,6 +0,0 @@ -/**: - ros__parameters: - update_rate_hz: 20.0 - new_frame_id: "base_link" - timeout_threshold: 1.0 - input_topics: ["/sensing/radar/front_center/detected_objects", "/sensing/radar/front_left/detected_objects", "/sensing/radar/rear_left/detected_objects", "/sensing/radar/rear_center/detected_objects", "/sensing/radar/rear_right/detected_objects", "/sensing/radar/front_right/detected_objects"] From aa5c2dc14a3dced2f96ddb5c2a48638f76282a8a Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 17 Jun 2024 07:44:51 +0000 Subject: [PATCH 35/41] ci(pre-commit): autofix --- aip_xx1_description/config/sensor_kit_calibration.yaml | 2 +- aip_xx1_description/config/sensors_calibration.yaml | 2 +- aip_xx1_description/urdf/sensor_kit.xacro | 2 +- aip_xx1_description/urdf/sensors.xacro | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/aip_xx1_description/config/sensor_kit_calibration.yaml b/aip_xx1_description/config/sensor_kit_calibration.yaml index b3c920c6..ab417b52 100644 --- a/aip_xx1_description/config/sensor_kit_calibration.yaml +++ b/aip_xx1_description/config/sensor_kit_calibration.yaml @@ -89,4 +89,4 @@ sensor_kit_base_link: z: 0.0 roll: 3.14159265359 pitch: 0.0 - yaw: 3.14159265359 \ No newline at end of file + yaw: 3.14159265359 diff --git a/aip_xx1_description/config/sensors_calibration.yaml b/aip_xx1_description/config/sensors_calibration.yaml index c7389f7e..e8c4b75e 100644 --- a/aip_xx1_description/config/sensors_calibration.yaml +++ b/aip_xx1_description/config/sensors_calibration.yaml @@ -33,4 +33,4 @@ base_link: z: 1.631 roll: -0.02 pitch: 0.7281317 - yaw: 3.141592 \ No newline at end of file + yaw: 3.141592 diff --git a/aip_xx1_description/urdf/sensor_kit.xacro b/aip_xx1_description/urdf/sensor_kit.xacro index e4a6c40d..ef36763f 100644 --- a/aip_xx1_description/urdf/sensor_kit.xacro +++ b/aip_xx1_description/urdf/sensor_kit.xacro @@ -225,4 +225,4 @@ /> - \ No newline at end of file + diff --git a/aip_xx1_description/urdf/sensors.xacro b/aip_xx1_description/urdf/sensors.xacro index 52299371..0484bdc3 100644 --- a/aip_xx1_description/urdf/sensors.xacro +++ b/aip_xx1_description/urdf/sensors.xacro @@ -69,4 +69,4 @@ yaw="${calibration['base_link']['ars408_front_center']['yaw']}" /> - \ No newline at end of file + From d0fbd1a6cb98492b9d5eb90afc29ae588b017f95 Mon Sep 17 00:00:00 2001 From: Yuxuan Liu Date: Mon, 17 Jun 2024 16:46:19 +0900 Subject: [PATCH 36/41] fix Spell-check Signed-off-by: Yuxuan Liu --- aip_xx1_gen2_launch/launch/radar.launch.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/aip_xx1_gen2_launch/launch/radar.launch.xml b/aip_xx1_gen2_launch/launch/radar.launch.xml index 1f9b16e6..198a2dfc 100644 --- a/aip_xx1_gen2_launch/launch/radar.launch.xml +++ b/aip_xx1_gen2_launch/launch/radar.launch.xml @@ -9,7 +9,6 @@ - From 573a281d139928aace6397ee008c6226b10f0b31 Mon Sep 17 00:00:00 2001 From: Yuxuan Liu Date: Mon, 17 Jun 2024 16:48:15 +0900 Subject: [PATCH 37/41] fix package name Signed-off-by: Yuxuan Liu --- aip_xx1_gen2_description/CMakeLists.txt | 2 +- aip_xx1_gen2_description/package.xml | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/aip_xx1_gen2_description/CMakeLists.txt b/aip_xx1_gen2_description/CMakeLists.txt index 50723262..549de0f8 100644 --- a/aip_xx1_gen2_description/CMakeLists.txt +++ b/aip_xx1_gen2_description/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(aip_xx1_description) +project(aip_xx1_gen2_description) find_package(ament_cmake_auto REQUIRED) diff --git a/aip_xx1_gen2_description/package.xml b/aip_xx1_gen2_description/package.xml index b35b48e0..9b010d72 100644 --- a/aip_xx1_gen2_description/package.xml +++ b/aip_xx1_gen2_description/package.xml @@ -1,8 +1,8 @@ - aip_xx1_description + aip_xx1_gen2_description 0.1.0 - The aip_xx1_description package + The aip_xx1_gen2_description package Yukihiro Saito Apache 2 From 9d07d76ed44bb486deb28ef15795cdda538565b7 Mon Sep 17 00:00:00 2001 From: N-Eiki Date: Tue, 18 Jun 2024 16:25:38 +0900 Subject: [PATCH 38/41] fix: recover radar.xacro to make gen1 operational Signed-off-by: N-Eiki --- aip_xx1_description/urdf/radar.xacro | 31 ++++++++++++++++++++++++++++ 1 file changed, 31 insertions(+) create mode 100644 aip_xx1_description/urdf/radar.xacro diff --git a/aip_xx1_description/urdf/radar.xacro b/aip_xx1_description/urdf/radar.xacro new file mode 100644 index 00000000..994c124b --- /dev/null +++ b/aip_xx1_description/urdf/radar.xacro @@ -0,0 +1,31 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file From b76f34f076d9d19466984970e4831a488a1f7c18 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 18 Jun 2024 07:26:44 +0000 Subject: [PATCH 39/41] ci(pre-commit): autofix --- aip_xx1_description/urdf/radar.xacro | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/aip_xx1_description/urdf/radar.xacro b/aip_xx1_description/urdf/radar.xacro index 994c124b..8b0f8d4b 100644 --- a/aip_xx1_description/urdf/radar.xacro +++ b/aip_xx1_description/urdf/radar.xacro @@ -28,4 +28,4 @@ - \ No newline at end of file + From 143346df61981653b70d41c311ca2d68fc45fa94 Mon Sep 17 00:00:00 2001 From: N-Eiki Date: Wed, 19 Jun 2024 14:22:16 +0900 Subject: [PATCH 40/41] update aip_xx1 for gen2 Signed-off-by: N-Eiki --- aip_xx1_gen2_description/CMakeLists.txt | 2 +- aip_xx1_gen2_description/package.xml | 4 +- aip_xx1_gen2_launch/CMakeLists.txt | 2 +- .../sensor_kit.param.yaml | 9 + .../config/gyro_bias_estimator.param.yaml | 6 + aip_xx1_gen2_launch/config/lidar_gen2.yaml | 69 +++++++ aip_xx1_gen2_launch/config/lidar_launch.yaml | 70 +++++++ aip_xx1_gen2_launch/launch/imu.launch.xml | 27 ++- aip_xx1_gen2_launch/launch/lidar.launch.py | 188 ++++++++++++++++++ aip_xx1_gen2_launch/launch/lidar.launch.xml | 23 ++- .../launch/pointcloud_preprocessor.launch.py | 56 ++---- aip_xx1_gen2_launch/launch/radar.launch.xml | 35 +++- aip_xx1_gen2_launch/launch/sensing.launch.xml | 4 +- aip_xx1_gen2_launch/package.xml | 4 +- 14 files changed, 440 insertions(+), 59 deletions(-) create mode 100644 aip_xx1_gen2_launch/config/gyro_bias_estimator.param.yaml create mode 100644 aip_xx1_gen2_launch/config/lidar_gen2.yaml create mode 100644 aip_xx1_gen2_launch/config/lidar_launch.yaml create mode 100644 aip_xx1_gen2_launch/launch/lidar.launch.py diff --git a/aip_xx1_gen2_description/CMakeLists.txt b/aip_xx1_gen2_description/CMakeLists.txt index 549de0f8..50723262 100644 --- a/aip_xx1_gen2_description/CMakeLists.txt +++ b/aip_xx1_gen2_description/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(aip_xx1_gen2_description) +project(aip_xx1_description) find_package(ament_cmake_auto REQUIRED) diff --git a/aip_xx1_gen2_description/package.xml b/aip_xx1_gen2_description/package.xml index 9b010d72..b35b48e0 100644 --- a/aip_xx1_gen2_description/package.xml +++ b/aip_xx1_gen2_description/package.xml @@ -1,8 +1,8 @@ - aip_xx1_gen2_description + aip_xx1_description 0.1.0 - The aip_xx1_gen2_description package + The aip_xx1_description package Yukihiro Saito Apache 2 diff --git a/aip_xx1_gen2_launch/CMakeLists.txt b/aip_xx1_gen2_launch/CMakeLists.txt index 7f8d9f60..babf05d8 100644 --- a/aip_xx1_gen2_launch/CMakeLists.txt +++ b/aip_xx1_gen2_launch/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(aip_xx1_gen2_launch) +project(aip_xx1_launch) find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() diff --git a/aip_xx1_gen2_launch/config/diagnostic_aggregator/sensor_kit.param.yaml b/aip_xx1_gen2_launch/config/diagnostic_aggregator/sensor_kit.param.yaml index ab32e0fe..56fc9dbd 100644 --- a/aip_xx1_gen2_launch/config/diagnostic_aggregator/sensor_kit.param.yaml +++ b/aip_xx1_gen2_launch/config/diagnostic_aggregator/sensor_kit.param.yaml @@ -18,6 +18,15 @@ type: diagnostic_aggregator/AnalyzerGroup path: lidar analyzers: + performance_monitoring: + type: diagnostic_aggregator/AnalyzerGroup + path: performance_monitoring + analyzers: + blockage: + type: diagnostic_aggregator/GenericAnalyzer + path: blockage + contains: [": blockage_validation"] + timeout: 1.0 velodyne: type: diagnostic_aggregator/AnalyzerGroup path: velodyne diff --git a/aip_xx1_gen2_launch/config/gyro_bias_estimator.param.yaml b/aip_xx1_gen2_launch/config/gyro_bias_estimator.param.yaml new file mode 100644 index 00000000..d552569f --- /dev/null +++ b/aip_xx1_gen2_launch/config/gyro_bias_estimator.param.yaml @@ -0,0 +1,6 @@ +/**: + ros__parameters: + gyro_bias_threshold: 0.008 # [rad/s] + timer_callback_interval_sec: 0.5 # [sec] + diagnostics_updater_interval_sec: 0.5 # [sec] + straight_motion_ang_vel_upper_limit: 0.015 # [rad/s] diff --git a/aip_xx1_gen2_launch/config/lidar_gen2.yaml b/aip_xx1_gen2_launch/config/lidar_gen2.yaml new file mode 100644 index 00000000..fcfefdd4 --- /dev/null +++ b/aip_xx1_gen2_launch/config/lidar_gen2.yaml @@ -0,0 +1,69 @@ +launches: + - sensor_type: hesai_OT128 + namespace: top + parameters: + max_range: 300.0 + sensor_frame: hesai_top + sensor_ip: 192.168.1.201 + data_port: 2368 + scan_phase: 160 + vertical_bins: 128 + - sensor_type: hesai_XT32 + namespace: front_left + parameters: + max_range: 300.0 + sensor_frame: hesai_front_left + sensor_ip: 192.168.1.21 + data_port: 2369 + scan_phase: 50.0 + cloud_min_angle: 50 + cloud_max_angle: 320 + vertical_bins: 16 + horizontal_ring_id: 0 + - sensor_type: hesai_XT32 + namespace: front_right + parameters: + max_range: 300.0 + sensor_frame: hesai_front_right + sensor_ip: 192.168.1.22 + data_port: 2370 + scan_phase: 310.0 + cloud_min_angle: 40 + cloud_max_angle: 310 + - sensor_type: hesai_XT32 + namespace: side_left + parameters: + max_range: 10.0 + sensor_frame: hesai_side_left + sensor_ip: 192.168.1.23 + data_port: 2371 + scan_phase: 90.0 + cloud_min_angle: 90 + cloud_max_angle: 270 + - sensor_type: hesai_XT32 + namespace: side_right + parameters: + max_range: 10.0 + sensor_frame: hesai_side_right + sensor_ip: 192.168.1.24 + data_port: 2372 + scan_phase: 270.0 + cloud_min_angle: 90 + cloud_max_angle: 270 + +preprocessor: + input_topics: + - /sensing/lidar/top/pointcloud_before_sync + - /sensing/lidar/side_left/pointcloud_before_sync + - /sensing/lidar/side_right/pointcloud_before_sync + - /sensing/lidar/front_left/pointcloud_before_sync + - /sensing/lidar/front_right/pointcloud_before_sync + input_offset: + - 0.035 + - 0.025 + - 0.025 + - 0.025 + - 0.025 + timeout_sec: 0.095 + input_twist_topic_type: twist + publish_synchronized_pointcloud: true diff --git a/aip_xx1_gen2_launch/config/lidar_launch.yaml b/aip_xx1_gen2_launch/config/lidar_launch.yaml new file mode 100644 index 00000000..c702f766 --- /dev/null +++ b/aip_xx1_gen2_launch/config/lidar_launch.yaml @@ -0,0 +1,70 @@ +launches: + - sensor_type: velodyne_VLS128 + namespace: top + parameters: + max_range: 250.0 + sensor_frame: velodyne_top + sensor_ip: 192.168.1.201 + data_port: 2368 + scan_phase: 300.0 + vertical_bins: 128 + horizontal_ring_id: 64 + horizontal_resolution: 0.4 + is_channel_order_top2down: false + - sensor_type: velodyne_VLP16 + namespace: left + parameters: + max_range: 5.0 + sensor_frame: velodyne_left + sensor_ip: 192.168.1.202 + data_port: 2369 + scan_phase: 180.0 + cloud_min_angle: 300 + cloud_max_angle: 60 + vertical_bins: 16 + horizontal_ring_id: 0 + horizontal_resolution: 0.4 + is_channel_order_top2down: false + - sensor_type: velodyne_VLP16 + namespace: right + parameters: + max_range: 5.0 + sensor_frame: velodyne_right + sensor_ip: 192.168.1.203 + data_port: 2370 + scan_phase: 180.0 + cloud_min_angle: 300 + cloud_max_angle: 60 + vertical_bins: 16 + horizontal_ring_id: 0 + horizontal_resolution: 0.4 + is_channel_order_top2down: false + - sensor_type: velodyne_VLP16 + namespace: rear + parameters: + max_range: 1.5 + sensor_frame: velodyne_rear + sensor_ip: 192.168.1.204 + data_port: 2371 + scan_phase: 180.0 + cloud_min_angle: 300 + cloud_max_angle: 60 + vertical_bins: 16 + horizontal_ring_id: 0 + horizontal_resolution: 0.4 + is_channel_order_top2down: false + +preprocessor: + input_topics: + - /sensing/lidar/top/pointcloud + - /sensing/lidar/left/pointcloud + - /sensing/lidar/right/pointcloud + - /sensing/lidar/rear/pointcloud + input_offset: + - 0.035 + - 0.025 + - 0.025 + - 0.025 + timeout_sec: 0.095 + input_twist_topic_type: twist + publish_synchronized_pointcloud: false diff --git a/aip_xx1_gen2_launch/launch/imu.launch.xml b/aip_xx1_gen2_launch/launch/imu.launch.xml index 7f1f0337..29795ae1 100644 --- a/aip_xx1_gen2_launch/launch/imu.launch.xml +++ b/aip_xx1_gen2_launch/launch/imu.launch.xml @@ -1,14 +1,27 @@ + + + + - - - - + + + + + + + + + - + + + + + @@ -21,6 +34,7 @@ + @@ -29,10 +43,13 @@ + + + diff --git a/aip_xx1_gen2_launch/launch/lidar.launch.py b/aip_xx1_gen2_launch/launch/lidar.launch.py new file mode 100644 index 00000000..594d2eb4 --- /dev/null +++ b/aip_xx1_gen2_launch/launch/lidar.launch.py @@ -0,0 +1,188 @@ +# Copyright 2024 Tier IV, Inc. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + + +from copy import deepcopy +import os +from typing import Any +from typing import List + +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import GroupAction +from launch.actions import IncludeLaunchDescription +from launch.actions import OpaqueFunction +from launch.launch_description_sources import AnyLaunchDescriptionSource +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import EnvironmentVariable +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import PushRosNamespace +import yaml + + +def join_list_of_arguments(arguments: List[Any]) -> str: + """Join a list of arguments into a string, used by Include Launch Description. + + Example: + join_list_of_arguments([1,2,3]) -> "[1, 2, 3]" + """ + return f"[{', '.join([str(arg) for arg in arguments])}]" + + +def generate_launch_dictionary(): + path_dictionary = { + "hesai_OT128": AnyLaunchDescriptionSource( + os.path.join( + get_package_share_directory("common_sensor_launch"), + "launch", + "hesai_OT128.launch.xml", + ) + ), + "hesai_XT32": AnyLaunchDescriptionSource( + os.path.join( + get_package_share_directory("common_sensor_launch"), + "launch", + "hesai_XT32.launch.xml", + ) + ), + "velodyne_VLS128": AnyLaunchDescriptionSource( + os.path.join( + get_package_share_directory("common_sensor_launch"), + "launch", + "velodyne_VLS128.launch.xml", + ) + ), + "velodyne_VLP16": AnyLaunchDescriptionSource( + os.path.join( + get_package_share_directory("common_sensor_launch"), + "launch", + "velodyne_VLP16.launch.xml", + ) + ), + "livox_horizon": AnyLaunchDescriptionSource( + os.path.join( + get_package_share_directory("common_sensor_launch"), + "launch", + "livox_horizon.launch.py", + ) + ), + } + return path_dictionary + + +def load_sub_launches_from_yaml(context, *args, **kwargs): + def load_yaml(yaml_file_path): + with open(LaunchConfiguration(yaml_file_path).perform(context), "r") as f: + return yaml.safe_load(f) + + config = load_yaml("config_file") + + path_dictionary = generate_launch_dictionary() + + base_parameters = {} + base_parameters["host_ip"] = LaunchConfiguration("host_ip") + base_parameters["vehicle_mirror_param_file"] = LaunchConfiguration( + "vehicle_mirror_param_file" + ).perform(context) + base_parameters["launch_driver"] = LaunchConfiguration("launch_driver").perform(context) + base_parameters["vehicle_id"] = LaunchConfiguration("vehicle_id").perform(context) + base_parameters["pointcloud_container_name"] = LaunchConfiguration( + "pointcloud_container_name" + ).perform(context) + base_parameters["enable_blockage_diag"] = LaunchConfiguration("enable_blockage_diag").perform( + context + ) + + sub_launch_actions = [] + for launch in config["launches"]: + launch_parameters = deepcopy(base_parameters) + launch_parameters.update(launch["parameters"]) # dict + launch_parameter_list_tuple = [(str(k), str(v)) for k, v in launch_parameters.items()] + sub_launch_action = GroupAction( + [ + PushRosNamespace(launch["namespace"]), + IncludeLaunchDescription( + deepcopy(path_dictionary[launch["sensor_type"]]), + launch_arguments=launch_parameter_list_tuple, + ), + ] + ) + sub_launch_actions.append(sub_launch_action) + + processor_dict = config["preprocessor"] + sub_launch_actions.append( + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join( + get_package_share_directory("aip_xx1_launch"), + "launch", + "pointcloud_preprocessor.launch.py", + ) + ), + launch_arguments=[ + ("base_frame", "base_link"), + ("use_multithread", "true"), + ("use_intra_process", "true"), + ("use_pointcloud_container", LaunchConfiguration("use_pointcloud_container")), + ("pointcloud_container_name", LaunchConfiguration("pointcloud_container_name")), + ("input_topics", join_list_of_arguments(processor_dict["input_topics"])), + ("input_offset", join_list_of_arguments(processor_dict["input_offset"])), + ("timeout_sec", str(processor_dict["timeout_sec"])), + ("input_twist_topic_type", str(processor_dict["input_twist_topic_type"])), + ( + "publish_synchronized_pointcloud", + str(processor_dict["publish_synchronized_pointcloud"]), + ), + ], + ) + ) + return [ + GroupAction([PushRosNamespace("lidar"), *sub_launch_actions]), + ] + + +def generate_launch_description(): + # Define launch arguments + launch_arguments = [] + config_file_arg = DeclareLaunchArgument( + "config_file", + default_value=os.path.join( + get_package_share_directory("aip_xx1_launch"), "config", "lidar_launch.yaml" + ), + description="Path to the configuration file", + ) + launch_arguments.append(config_file_arg) + + def add_launch_arg(name: str, default_value=None, **kwargs): + launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value, **kwargs)) + + add_launch_arg("launch_driver", "true") + add_launch_arg("host_ip", "192.168.1.10") + add_launch_arg("use_concat_filter", "true") + add_launch_arg( + "vehicle_id", + default_value=EnvironmentVariable("VEHICLE_ID", default_value="default"), + ) + add_launch_arg("vehicle_mirror_param_file") + add_launch_arg("use_pointcloud_container", "false", description="launch pointcloud container") + add_launch_arg("pointcloud_container_name", "pointcloud_container") + add_launch_arg("enable_blockage_diag", "false") + + # Create launch description with the config_file argument + ld = LaunchDescription(launch_arguments) + # Add sub-launch files dynamically based on the YAML configuration + ld.add_action(OpaqueFunction(function=load_sub_launches_from_yaml)) + + return ld diff --git a/aip_xx1_gen2_launch/launch/lidar.launch.xml b/aip_xx1_gen2_launch/launch/lidar.launch.xml index 7f77ad2d..b524b788 100644 --- a/aip_xx1_gen2_launch/launch/lidar.launch.xml +++ b/aip_xx1_gen2_launch/launch/lidar.launch.xml @@ -5,8 +5,8 @@ - + @@ -23,6 +23,11 @@ + + + + + @@ -40,6 +45,11 @@ + + + + + @@ -57,6 +67,11 @@ + + + + + @@ -74,6 +89,11 @@ + + + + + @@ -98,7 +118,6 @@ - diff --git a/aip_xx1_gen2_launch/launch/pointcloud_preprocessor.launch.py b/aip_xx1_gen2_launch/launch/pointcloud_preprocessor.launch.py index 4aa9736c..433b7f58 100644 --- a/aip_xx1_gen2_launch/launch/pointcloud_preprocessor.launch.py +++ b/aip_xx1_gen2_launch/launch/pointcloud_preprocessor.launch.py @@ -20,7 +20,6 @@ from launch.conditions import IfCondition from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode @@ -37,53 +36,29 @@ def launch_setup(context, *args, **kwargs): ], parameters=[ { - "input_topics": [ - "/sensing/lidar/top/pointcloud_before_sync", - "/sensing/lidar/side_left/pointcloud_before_sync", - "/sensing/lidar/side_right/pointcloud_before_sync", - "/sensing/lidar/front_left/pointcloud_before_sync", - "/sensing/lidar/front_right/pointcloud_before_sync", - ], + "input_topics": LaunchConfiguration("input_topics"), "output_frame": LaunchConfiguration("base_frame"), - "input_offset": [ - 0.035, - 0.025, - 0.025, - 0.025, - 0.025, - ], # each sensor will wait 60, 70, 70, 70ms - "timeout_sec": 0.095, # set shorter than 100ms - "input_twist_topic_type": "twist", - "publish_synchronized_pointcloud": True, + "input_offset": LaunchConfiguration( + "input_offset" + ), # each sensor will wait 60, 70, 70, 70ms + "timeout_sec": LaunchConfiguration("timeout_sec"), # set shorter than 100ms + "input_twist_topic_type": LaunchConfiguration("input_twist_topic_type"), + "publish_synchronized_pointcloud": LaunchConfiguration( + "publish_synchronized_pointcloud" + ), } ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) - # set container to run all required components in the same process - container = ComposableNodeContainer( - name=LaunchConfiguration("individual_container_name"), - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), - output="screen", - ) - - target_container = ( - container - if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context) - else LaunchConfiguration("pointcloud_container_name") - ) - # load concat or passthrough filter concat_loader = LoadComposableNodes( composable_node_descriptions=[concat_component], - target_container=target_container, + target_container=LaunchConfiguration("pointcloud_container_name"), condition=IfCondition(LaunchConfiguration("use_concat_filter")), ) - return [container, concat_loader] + return [concat_loader] def generate_launch_description(): @@ -95,9 +70,16 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("base_frame", "base_link") add_launch_arg("use_multithread", "False") add_launch_arg("use_intra_process", "False") - add_launch_arg("use_pointcloud_container", "False") add_launch_arg("pointcloud_container_name", "pointcloud_container") add_launch_arg("individual_container_name", "concatenate_container") + add_launch_arg( + "input_topics", + "[/sensing/lidar/top/pointcloud, /sensing/lidar/left/pointcloud, /sensing/lidar/right/pointcloud, /sensing/lidar/rear/pointcloud]", + ) + add_launch_arg("input_offset", "[0.035, 0.025, 0.025, 0.025]") + add_launch_arg("timeout_sec", "0.095") + add_launch_arg("input_twist_topic_type", "twist") + add_launch_arg("publish_synchronized_pointcloud", "False") set_container_executable = SetLaunchConfiguration( "container_executable", diff --git a/aip_xx1_gen2_launch/launch/radar.launch.xml b/aip_xx1_gen2_launch/launch/radar.launch.xml index 198a2dfc..41ac94b3 100644 --- a/aip_xx1_gen2_launch/launch/radar.launch.xml +++ b/aip_xx1_gen2_launch/launch/radar.launch.xml @@ -1,12 +1,34 @@ - + - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -210,4 +232,5 @@ + diff --git a/aip_xx1_gen2_launch/launch/sensing.launch.xml b/aip_xx1_gen2_launch/launch/sensing.launch.xml index ba6b935c..8213cba8 100644 --- a/aip_xx1_gen2_launch/launch/sensing.launch.xml +++ b/aip_xx1_gen2_launch/launch/sensing.launch.xml @@ -3,17 +3,15 @@ - - + - diff --git a/aip_xx1_gen2_launch/package.xml b/aip_xx1_gen2_launch/package.xml index 8f2f9df9..93246e4b 100644 --- a/aip_xx1_gen2_launch/package.xml +++ b/aip_xx1_gen2_launch/package.xml @@ -1,9 +1,9 @@ - aip_xx1_gen2_launch + aip_xx1_launch 0.1.0 - The aip_xx1_gen2_launch package + The aip_xx1_launch package Hiroki OTA Apache License 2.0 From bd25b0834b9cf8e456a51c0c72c92e2df5f0c290 Mon Sep 17 00:00:00 2001 From: N-Eiki Date: Wed, 19 Jun 2024 14:31:59 +0900 Subject: [PATCH 41/41] fix: packages name is aip_xx1_gen2_* but in these files written as aip_xx1_* Signed-off-by: N-Eiki --- aip_xx1_gen2_description/CMakeLists.txt | 2 +- aip_xx1_gen2_description/package.xml | 4 ++-- aip_xx1_gen2_description/urdf/sensor_kit.xacro | 2 +- aip_xx1_gen2_description/urdf/sensors.xacro | 2 +- aip_xx1_gen2_launch/CMakeLists.txt | 2 +- aip_xx1_gen2_launch/launch/imu.launch.xml | 2 +- aip_xx1_gen2_launch/launch/lidar.launch.py | 4 ++-- aip_xx1_gen2_launch/launch/lidar.launch.xml | 2 +- aip_xx1_gen2_launch/launch/radar.launch.xml | 2 +- aip_xx1_gen2_launch/launch/sensing.launch.xml | 10 +++++----- aip_xx1_gen2_launch/package.xml | 4 ++-- 11 files changed, 18 insertions(+), 18 deletions(-) diff --git a/aip_xx1_gen2_description/CMakeLists.txt b/aip_xx1_gen2_description/CMakeLists.txt index 50723262..549de0f8 100644 --- a/aip_xx1_gen2_description/CMakeLists.txt +++ b/aip_xx1_gen2_description/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(aip_xx1_description) +project(aip_xx1_gen2_description) find_package(ament_cmake_auto REQUIRED) diff --git a/aip_xx1_gen2_description/package.xml b/aip_xx1_gen2_description/package.xml index b35b48e0..9b010d72 100644 --- a/aip_xx1_gen2_description/package.xml +++ b/aip_xx1_gen2_description/package.xml @@ -1,8 +1,8 @@ - aip_xx1_description + aip_xx1_gen2_description 0.1.0 - The aip_xx1_description package + The aip_xx1_gen2_description package Yukihiro Saito Apache 2 diff --git a/aip_xx1_gen2_description/urdf/sensor_kit.xacro b/aip_xx1_gen2_description/urdf/sensor_kit.xacro index 8830a4d3..137b3589 100644 --- a/aip_xx1_gen2_description/urdf/sensor_kit.xacro +++ b/aip_xx1_gen2_description/urdf/sensor_kit.xacro @@ -9,7 +9,7 @@ - + diff --git a/aip_xx1_gen2_description/urdf/sensors.xacro b/aip_xx1_gen2_description/urdf/sensors.xacro index 64dbf6bb..81faabe8 100644 --- a/aip_xx1_gen2_description/urdf/sensors.xacro +++ b/aip_xx1_gen2_description/urdf/sensors.xacro @@ -1,7 +1,7 @@ - + diff --git a/aip_xx1_gen2_launch/CMakeLists.txt b/aip_xx1_gen2_launch/CMakeLists.txt index babf05d8..7f8d9f60 100644 --- a/aip_xx1_gen2_launch/CMakeLists.txt +++ b/aip_xx1_gen2_launch/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(aip_xx1_launch) +project(aip_xx1_gen2_launch) find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() diff --git a/aip_xx1_gen2_launch/launch/imu.launch.xml b/aip_xx1_gen2_launch/launch/imu.launch.xml index 29795ae1..04011706 100644 --- a/aip_xx1_gen2_launch/launch/imu.launch.xml +++ b/aip_xx1_gen2_launch/launch/imu.launch.xml @@ -44,7 +44,7 @@ - + diff --git a/aip_xx1_gen2_launch/launch/lidar.launch.py b/aip_xx1_gen2_launch/launch/lidar.launch.py index 594d2eb4..7174fc9f 100644 --- a/aip_xx1_gen2_launch/launch/lidar.launch.py +++ b/aip_xx1_gen2_launch/launch/lidar.launch.py @@ -126,7 +126,7 @@ def load_yaml(yaml_file_path): IncludeLaunchDescription( PythonLaunchDescriptionSource( os.path.join( - get_package_share_directory("aip_xx1_launch"), + get_package_share_directory("aip_xx1_gen2_launch"), "launch", "pointcloud_preprocessor.launch.py", ) @@ -159,7 +159,7 @@ def generate_launch_description(): config_file_arg = DeclareLaunchArgument( "config_file", default_value=os.path.join( - get_package_share_directory("aip_xx1_launch"), "config", "lidar_launch.yaml" + get_package_share_directory("aip_xx1_gen2_launch"), "config", "lidar_launch.yaml" ), description="Path to the configuration file", ) diff --git a/aip_xx1_gen2_launch/launch/lidar.launch.xml b/aip_xx1_gen2_launch/launch/lidar.launch.xml index b524b788..4f4b37b7 100644 --- a/aip_xx1_gen2_launch/launch/lidar.launch.xml +++ b/aip_xx1_gen2_launch/launch/lidar.launch.xml @@ -114,7 +114,7 @@ - + diff --git a/aip_xx1_gen2_launch/launch/radar.launch.xml b/aip_xx1_gen2_launch/launch/radar.launch.xml index 41ac94b3..7eb4dbcb 100644 --- a/aip_xx1_gen2_launch/launch/radar.launch.xml +++ b/aip_xx1_gen2_launch/launch/radar.launch.xml @@ -226,7 +226,7 @@ - + diff --git a/aip_xx1_gen2_launch/launch/sensing.launch.xml b/aip_xx1_gen2_launch/launch/sensing.launch.xml index 8213cba8..74f24c15 100644 --- a/aip_xx1_gen2_launch/launch/sensing.launch.xml +++ b/aip_xx1_gen2_launch/launch/sensing.launch.xml @@ -9,29 +9,29 @@ - + - - + - + - + diff --git a/aip_xx1_gen2_launch/package.xml b/aip_xx1_gen2_launch/package.xml index 93246e4b..8f2f9df9 100644 --- a/aip_xx1_gen2_launch/package.xml +++ b/aip_xx1_gen2_launch/package.xml @@ -1,9 +1,9 @@ - aip_xx1_launch + aip_xx1_gen2_launch 0.1.0 - The aip_xx1_launch package + The aip_xx1_gen2_launch package Hiroki OTA Apache License 2.0