Skip to content

Commit

Permalink
use upper and lower
Browse files Browse the repository at this point in the history
  • Loading branch information
h-ohta committed Jul 4, 2024
1 parent 4b8659c commit bfade41
Show file tree
Hide file tree
Showing 2 changed files with 64 additions and 64 deletions.
16 changes: 8 additions & 8 deletions aip_x2_description/config/sensor_kit_calibration.yaml
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
sensor_kit_base_link:
# left upper
left/lidar_base_link:
left_upper/lidar_base_link:
x: 0.0
y: 0.0
z: 0.0
roll: 0.0
pitch: 0.0
yaw: 3.141592 # 180 [deg] to turn the connector toward the vehicle
left_bottom/lidar_base_link:
left_lower/lidar_base_link:
x: 0.0
y: -0.025
z: -0.115
Expand Down Expand Up @@ -37,14 +37,14 @@ sensor_kit_base_link:
yaw: 1.570796 # 90 [deg]

# right upper
right/lidar_base_link:
right_upper/lidar_base_link:
x: 0.0
y: -2.15178
z: 0.0
roll: 0.0
pitch: 0.0
yaw: 0.0 # to turn the connector toward the vehicle
right_bottom/lidar_base_link:
right_lower/lidar_base_link:
x: 0.0
y: -2.12678
z: -0.115
Expand Down Expand Up @@ -141,14 +141,14 @@ sensor_kit_base_link:
yaw: 0.0

# front lower
front/lidar_base_link:
front_upper/lidar_base_link:
x: 0.94058
y: -1.07589
z: -1.91826
roll: 0.0
pitch: 0.0
yaw: 1.570796 # 90 [deg] to turn the connector toward the vehicle
front_bottom/lidar_base_link:
front_lower/lidar_base_link:
x: 0.96758
y: -1.07589
z: -2.15234
Expand All @@ -157,14 +157,14 @@ sensor_kit_base_link:
yaw: 1.570796 # 90 [deg] to turn the connector toward the vehicle

# rear lower
rear/lidar_base_link:
rear_upper/lidar_base_link:
x: -6.08042
y: -1.07589
z: -1.91826
roll: 0.0
pitch: 0.0
yaw: -1.570796 # 90 [deg] to turn the connector toward the vehicle
rear_bottom/lidar_base_link:
rear_lower/lidar_base_link:
x: -6.10742
y: -1.07589
z: -2.15234
Expand Down
112 changes: 56 additions & 56 deletions aip_x2_description/urdf/sensor_kit.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -24,25 +24,25 @@

<!-- left upper-->
<xacro:PandarQT
name="left/lidar"
name="left_upper/lidar"
parent="sensor_kit_base_link"
x="${calibration['sensor_kit_base_link']['left/lidar_base_link']['x']}"
y="${calibration['sensor_kit_base_link']['left/lidar_base_link']['y']}"
z="${calibration['sensor_kit_base_link']['left/lidar_base_link']['z']}"
roll="${calibration['sensor_kit_base_link']['left/lidar_base_link']['roll']}"
pitch="${calibration['sensor_kit_base_link']['left/lidar_base_link']['pitch']}"
yaw="${calibration['sensor_kit_base_link']['left/lidar_base_link']['yaw']}"
x="${calibration['sensor_kit_base_link']['left_upper/lidar_base_link']['x']}"
y="${calibration['sensor_kit_base_link']['left_upper/lidar_base_link']['y']}"
z="${calibration['sensor_kit_base_link']['left_upper/lidar_base_link']['z']}"
roll="${calibration['sensor_kit_base_link']['left_upper/lidar_base_link']['roll']}"
pitch="${calibration['sensor_kit_base_link']['left_upper/lidar_base_link']['pitch']}"
yaw="${calibration['sensor_kit_base_link']['left_upper/lidar_base_link']['yaw']}"
/>

<xacro:PandarQT
name="left_bottom/lidar"
name="left_lower/lidar"
parent="sensor_kit_base_link"
x="${calibration['sensor_kit_base_link']['left_bottom/lidar_base_link']['x']}"
y="${calibration['sensor_kit_base_link']['left_bottom/lidar_base_link']['y']}"
z="${calibration['sensor_kit_base_link']['left_bottom/lidar_base_link']['z']}"
roll="${calibration['sensor_kit_base_link']['left_bottom/lidar_base_link']['roll']}"
pitch="${calibration['sensor_kit_base_link']['left_bottom/lidar_base_link']['pitch']}"
yaw="${calibration['sensor_kit_base_link']['left_bottom/lidar_base_link']['yaw']}"
x="${calibration['sensor_kit_base_link']['left_lower/lidar_base_link']['x']}"
y="${calibration['sensor_kit_base_link']['left_lower/lidar_base_link']['y']}"
z="${calibration['sensor_kit_base_link']['left_lower/lidar_base_link']['z']}"
roll="${calibration['sensor_kit_base_link']['left_lower/lidar_base_link']['roll']}"
pitch="${calibration['sensor_kit_base_link']['left_lower/lidar_base_link']['pitch']}"
yaw="${calibration['sensor_kit_base_link']['left_lower/lidar_base_link']['yaw']}"
/>

<xacro:monocular_camera_macro
Expand Down Expand Up @@ -95,25 +95,25 @@

<!-- right upper-->
<xacro:PandarQT
name="right/lidar"
name="right_upper/lidar"
parent="sensor_kit_base_link"
x="${calibration['sensor_kit_base_link']['right/lidar_base_link']['x']}"
y="${calibration['sensor_kit_base_link']['right/lidar_base_link']['y']}"
z="${calibration['sensor_kit_base_link']['right/lidar_base_link']['z']}"
roll="${calibration['sensor_kit_base_link']['right/lidar_base_link']['roll']}"
pitch="${calibration['sensor_kit_base_link']['right/lidar_base_link']['pitch']}"
yaw="${calibration['sensor_kit_base_link']['right/lidar_base_link']['yaw']}"
x="${calibration['sensor_kit_base_link']['right_upper/lidar_base_link']['x']}"
y="${calibration['sensor_kit_base_link']['right_upper/lidar_base_link']['y']}"
z="${calibration['sensor_kit_base_link']['right_upper/lidar_base_link']['z']}"
roll="${calibration['sensor_kit_base_link']['right_upper/lidar_base_link']['roll']}"
pitch="${calibration['sensor_kit_base_link']['right_upper/lidar_base_link']['pitch']}"
yaw="${calibration['sensor_kit_base_link']['right_upper/lidar_base_link']['yaw']}"
/>

<xacro:PandarQT
name="right_bottom/lidar"
name="right_lower/lidar"
parent="sensor_kit_base_link"
x="${calibration['sensor_kit_base_link']['right_bottom/lidar_base_link']['x']}"
y="${calibration['sensor_kit_base_link']['right_bottom/lidar_base_link']['y']}"
z="${calibration['sensor_kit_base_link']['right_bottom/lidar_base_link']['z']}"
roll="${calibration['sensor_kit_base_link']['right_bottom/lidar_base_link']['roll']}"
pitch="${calibration['sensor_kit_base_link']['right_bottom/lidar_base_link']['pitch']}"
yaw="${calibration['sensor_kit_base_link']['right_bottom/lidar_base_link']['yaw']}"
x="${calibration['sensor_kit_base_link']['right_lower/lidar_base_link']['x']}"
y="${calibration['sensor_kit_base_link']['right_lower/lidar_base_link']['y']}"
z="${calibration['sensor_kit_base_link']['right_lower/lidar_base_link']['z']}"
roll="${calibration['sensor_kit_base_link']['right_lower/lidar_base_link']['roll']}"
pitch="${calibration['sensor_kit_base_link']['right_lower/lidar_base_link']['pitch']}"
yaw="${calibration['sensor_kit_base_link']['right_lower/lidar_base_link']['yaw']}"
/>

<xacro:monocular_camera_macro
Expand Down Expand Up @@ -296,48 +296,48 @@

<!-- front lower -->
<xacro:PandarQT
name="front/lidar"
name="front_upper/lidar"
parent="sensor_kit_base_link"
x="${calibration['sensor_kit_base_link']['front/lidar_base_link']['x']}"
y="${calibration['sensor_kit_base_link']['front/lidar_base_link']['y']}"
z="${calibration['sensor_kit_base_link']['front/lidar_base_link']['z']}"
roll="${calibration['sensor_kit_base_link']['front/lidar_base_link']['roll']}"
pitch="${calibration['sensor_kit_base_link']['front/lidar_base_link']['pitch']}"
yaw="${calibration['sensor_kit_base_link']['front/lidar_base_link']['yaw']}"
x="${calibration['sensor_kit_base_link']['front_upper/lidar_base_link']['x']}"
y="${calibration['sensor_kit_base_link']['front_upper/lidar_base_link']['y']}"
z="${calibration['sensor_kit_base_link']['front_upper/lidar_base_link']['z']}"
roll="${calibration['sensor_kit_base_link']['front_upper/lidar_base_link']['roll']}"
pitch="${calibration['sensor_kit_base_link']['front_upper/lidar_base_link']['pitch']}"
yaw="${calibration['sensor_kit_base_link']['front_upper/lidar_base_link']['yaw']}"
/>

<xacro:PandarQT
name="front_bottom/lidar"
name="front_lower/lidar"
parent="sensor_kit_base_link"
x="${calibration['sensor_kit_base_link']['front_bottom/lidar_base_link']['x']}"
y="${calibration['sensor_kit_base_link']['front_bottom/lidar_base_link']['y']}"
z="${calibration['sensor_kit_base_link']['front_bottom/lidar_base_link']['z']}"
roll="${calibration['sensor_kit_base_link']['front_bottom/lidar_base_link']['roll']}"
pitch="${calibration['sensor_kit_base_link']['front_bottom/lidar_base_link']['pitch']}"
yaw="${calibration['sensor_kit_base_link']['front_bottom/lidar_base_link']['yaw']}"
x="${calibration['sensor_kit_base_link']['front_lower/lidar_base_link']['x']}"
y="${calibration['sensor_kit_base_link']['front_lower/lidar_base_link']['y']}"
z="${calibration['sensor_kit_base_link']['front_lower/lidar_base_link']['z']}"
roll="${calibration['sensor_kit_base_link']['front_lower/lidar_base_link']['roll']}"
pitch="${calibration['sensor_kit_base_link']['front_lower/lidar_base_link']['pitch']}"
yaw="${calibration['sensor_kit_base_link']['front_lower/lidar_base_link']['yaw']}"
/>

<!-- rear lower -->
<xacro:PandarQT
name="rear/lidar"
name="rear_upper/lidar"
parent="sensor_kit_base_link"
x="${calibration['sensor_kit_base_link']['rear/lidar_base_link']['x']}"
y="${calibration['sensor_kit_base_link']['rear/lidar_base_link']['y']}"
z="${calibration['sensor_kit_base_link']['rear/lidar_base_link']['z']}"
roll="${calibration['sensor_kit_base_link']['rear/lidar_base_link']['roll']}"
pitch="${calibration['sensor_kit_base_link']['rear/lidar_base_link']['pitch']}"
yaw="${calibration['sensor_kit_base_link']['rear/lidar_base_link']['yaw']}"
x="${calibration['sensor_kit_base_link']['rear_upper/lidar_base_link']['x']}"
y="${calibration['sensor_kit_base_link']['rear_upper/lidar_base_link']['y']}"
z="${calibration['sensor_kit_base_link']['rear_upper/lidar_base_link']['z']}"
roll="${calibration['sensor_kit_base_link']['rear_upper/lidar_base_link']['roll']}"
pitch="${calibration['sensor_kit_base_link']['rear_upper/lidar_base_link']['pitch']}"
yaw="${calibration['sensor_kit_base_link']['rear_upper/lidar_base_link']['yaw']}"
/>

<xacro:PandarQT
name="rear_bottom/lidar"
name="rear_lower/lidar"
parent="sensor_kit_base_link"
x="${calibration['sensor_kit_base_link']['rear_bottom/lidar_base_link']['x']}"
y="${calibration['sensor_kit_base_link']['rear_bottom/lidar_base_link']['y']}"
z="${calibration['sensor_kit_base_link']['rear_bottom/lidar_base_link']['z']}"
roll="${calibration['sensor_kit_base_link']['rear_bottom/lidar_base_link']['roll']}"
pitch="${calibration['sensor_kit_base_link']['rear_bottom/lidar_base_link']['pitch']}"
yaw="${calibration['sensor_kit_base_link']['rear_bottom/lidar_base_link']['yaw']}"
x="${calibration['sensor_kit_base_link']['rear_lower/lidar_base_link']['x']}"
y="${calibration['sensor_kit_base_link']['rear_lower/lidar_base_link']['y']}"
z="${calibration['sensor_kit_base_link']['rear_lower/lidar_base_link']['z']}"
roll="${calibration['sensor_kit_base_link']['rear_lower/lidar_base_link']['roll']}"
pitch="${calibration['sensor_kit_base_link']['rear_lower/lidar_base_link']['pitch']}"
yaw="${calibration['sensor_kit_base_link']['rear_lower/lidar_base_link']['yaw']}"
/>

</xacro:macro>
Expand Down

0 comments on commit bfade41

Please sign in to comment.