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 @@
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
-
+
-
-
+
-
-
-
+
+
+
+
+
+
+
-