Skip to content

Commit

Permalink
chore: generalized radar names
Browse files Browse the repository at this point in the history
Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>
  • Loading branch information
knzo25 authored and yuki-takagi-66 committed Feb 28, 2024
1 parent dec2668 commit 78d388b
Show file tree
Hide file tree
Showing 2 changed files with 48 additions and 48 deletions.
12 changes: 6 additions & 6 deletions aip_xx1_description/config/sensors_calibration.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
84 changes: 42 additions & 42 deletions aip_xx1_description/urdf/sensors.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -59,63 +59,63 @@
<!-- embedded radar sensors -->
<!-- <xacro:include filename="$(find radar_description)/urdf/radar.xacro"/>
<xacro:radar_macro
name="ars548_front_center"
name="radar_front_center"
parent="base_link"
x="${calibration['base_link']['ars548_front_center_base_link']['x']}"
y="${calibration['base_link']['ars548_front_center_base_link']['y']}"
z="${calibration['base_link']['ars548_front_center_base_link']['z']}"
roll="${calibration['base_link']['ars548_front_center_base_link']['roll']}"
pitch="${calibration['base_link']['ars548_front_center_base_link']['pitch']}"
yaw="${calibration['base_link']['ars548_front_center_base_link']['yaw']}"
x="${calibration['base_link']['front_center/radar_link']['x']}"
y="${calibration['base_link']['front_center/radar_link']['y']}"
z="${calibration['base_link']['front_center/radar_link']['z']}"
roll="${calibration['base_link']['front_center/radar_link']['roll']}"
pitch="${calibration['base_link']['front_center/radar_link']['pitch']}"
yaw="${calibration['base_link']['front_center/radar_link']['yaw']}"
/>
<xacro:radar_macro
name="ars548_front_right"
name="radar_front_right"
parent="base_link"
x="${calibration['base_link']['ars548_front_right_base_link']['x']}"
y="${calibration['base_link']['ars548_front_right_base_link']['y']}"
z="${calibration['base_link']['ars548_front_right_base_link']['z']}"
roll="${calibration['base_link']['ars548_front_right_base_link']['roll']}"
pitch="${calibration['base_link']['ars548_front_right_base_link']['pitch']}"
yaw="${calibration['base_link']['ars548_front_right_base_link']['yaw']}"
x="${calibration['base_link']['front_right/radar_link']['x']}"
y="${calibration['base_link']['front_right/radar_link']['y']}"
z="${calibration['base_link']['front_right/radar_link']['z']}"
roll="${calibration['base_link']['front_right/radar_link']['roll']}"
pitch="${calibration['base_link']['front_right/radar_link']['pitch']}"
yaw="${calibration['base_link']['front_right/radar_link']['yaw']}"
/>
<xacro:radar_macro
name="ars548_front_left"
name="radar_front_left"
parent="base_link"
x="${calibration['base_link']['ars548_front_left_base_link']['x']}"
y="${calibration['base_link']['ars548_front_left_base_link']['y']}"
z="${calibration['base_link']['ars548_front_left_base_link']['z']}"
roll="${calibration['base_link']['ars548_front_left_base_link']['roll']}"
pitch="${calibration['base_link']['ars548_front_left_base_link']['pitch']}"
yaw="${calibration['base_link']['ars548_front_left_base_link']['yaw']}"
x="${calibration['base_link']['front_left/radar_link']['x']}"
y="${calibration['base_link']['front_left/radar_link']['y']}"
z="${calibration['base_link']['front_left/radar_link']['z']}"
roll="${calibration['base_link']['front_left/radar_link']['roll']}"
pitch="${calibration['base_link']['front_left/radar_link']['pitch']}"
yaw="${calibration['base_link']['front_left/radar_link']['yaw']}"
/>
<xacro:radar_macro
name="ars548_back_center"
name="radar_back_center"
parent="base_link"
x="${calibration['base_link']['ars548_back_center_base_link']['x']}"
y="${calibration['base_link']['ars548_back_center_base_link']['y']}"
z="${calibration['base_link']['ars548_back_center_base_link']['z']}"
roll="${calibration['base_link']['ars548_back_center_base_link']['roll']}"
pitch="${calibration['base_link']['ars548_back_center_base_link']['pitch']}"
yaw="${calibration['base_link']['ars548_back_center_base_link']['yaw']}"
x="${calibration['base_link']['rear_center/radar_link']['x']}"
y="${calibration['base_link']['rear_center/radar_link']['y']}"
z="${calibration['base_link']['rear_center/radar_link']['z']}"
roll="${calibration['base_link']['rear_center/radar_link']['roll']}"
pitch="${calibration['base_link']['rear_center/radar_link']['pitch']}"
yaw="${calibration['base_link']['rear_center/radar_link']['yaw']}"
/>
<xacro:radar_macro
name="ars548_back_right"
name="radar_back_right"
parent="base_link"
x="${calibration['base_link']['ars548_back_right_base_link']['x']}"
y="${calibration['base_link']['ars548_back_right_base_link']['y']}"
z="${calibration['base_link']['ars548_back_right_base_link']['z']}"
roll="${calibration['base_link']['ars548_back_right_base_link']['roll']}"
pitch="${calibration['base_link']['ars548_back_right_base_link']['pitch']}"
yaw="${calibration['base_link']['ars548_back_right_base_link']['yaw']}"
x="${calibration['base_link']['rear_right/radar_link']['x']}"
y="${calibration['base_link']['rear_right/radar_link']['y']}"
z="${calibration['base_link']['rear_right/radar_link']['z']}"
roll="${calibration['base_link']['rear_right/radar_link']['roll']}"
pitch="${calibration['base_link']['rear_right/radar_link']['pitch']}"
yaw="${calibration['base_link']['rear_right/radar_link']['yaw']}"
/>
<xacro:radar_macro
name="ars548_back_left"
name="radar_back_left"
parent="base_link"
x="${calibration['base_link']['ars548_back_left_base_link']['x']}"
y="${calibration['base_link']['ars548_back_left_base_link']['y']}"
z="${calibration['base_link']['ars548_back_left_base_link']['z']}"
roll="${calibration['base_link']['ars548_back_left_base_link']['roll']}"
pitch="${calibration['base_link']['ars548_back_left_base_link']['pitch']}"
yaw="${calibration['base_link']['ars548_back_left_base_link']['yaw']}"
x="${calibration['base_link']['rear_left/radar_link']['x']}"
y="${calibration['base_link']['rear_left/radar_link']['y']}"
z="${calibration['base_link']['rear_left/radar_link']['z']}"
roll="${calibration['base_link']['rear_left/radar_link']['roll']}"
pitch="${calibration['base_link']['rear_left/radar_link']['pitch']}"
yaw="${calibration['base_link']['rear_left/radar_link']['yaw']}"
/> -->
</robot>

0 comments on commit 78d388b

Please sign in to comment.