Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat: add x2 gen2 files #269

Merged
merged 2 commits into from
Jul 25, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 11 additions & 0 deletions aip_x2_gen2_description/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
cmake_minimum_required(VERSION 3.5)
project(aip_x2_gen2_description)

find_package(ament_cmake_auto REQUIRED)

ament_auto_find_build_dependencies()

ament_auto_package(INSTALL_TO_SHARE
urdf
config
)
173 changes: 173 additions & 0 deletions aip_x2_gen2_description/config/sensor_kit_calibration.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,173 @@
sensor_kit_base_link:
# left upper
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_lower/lidar_base_link:
x: 0.0
y: -0.025
z: -0.115
roll: 0.6981 # 40[deg]
pitch: 0.0
yaw: 3.141592 # 180 [deg] to turn the connector toward the vehicle
left_front/camera_link:
x: 0.12758
y: -0.04589
z: -0.0866
roll: 0.0
pitch: 0.08722 # 5 [deg]
yaw: 0.85478 # 49 [deg]
left_rear/camera_link:
x: -0.12842
y: -0.04589
z: -0.0866
roll: 0.0
pitch: 0.08722 # 5 [deg]
yaw: 2.2678 # 130 [deg]
left_center/camera_link:
x: 0.0
y: -0.04089
z: -0.18666
roll: 0.0
pitch: 0.933278 # 53.50 [deg]
yaw: 1.570796 # 90 [deg]

# right upper
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_lower/lidar_base_link:
x: 0.0
y: -2.12678
z: -0.115
roll: 0.6981 # 40 [deg]
pitch: 0.0
yaw: 0.0 # to turn the connector toward the vehicle
right_front/camera_link:
x: 0.12758
y: -2.10589
z: -0.0866
roll: 0.0
pitch: 0.08722 # 5 [deg]
yaw: -0.85478 # -49 [deg]
right_rear/camera_link:
x: -0.12842
y: -2.10589
z: -0.0866
roll: 0.0
pitch: 0.08722 # 5 [deg]
yaw: -2.2678 # -130 [deg]
right_center/camera_link:
x: 0.0
y: -2.11089
z: -0.18666
roll: 0.0
pitch: 0.933278 # 53.50 [deg]
yaw: -1.570796 # -90 [deg]

# front upper
top_front_left/imu_link:
x: 0.562
y: -0.99974
z: -0.06146
roll: 3.141592
pitch: 0.0
yaw: 0.0
top_front_right/imu_link:
x: 0.562
y: -1.13974
z: -0.06146
roll: 3.141592
pitch: 0.0
yaw: 0.0
top_front_right/camera_link:
x: 0.73758
y: -1.26439
z: -0.06666
roll: 0.0
pitch: 0.8373 # 48 [deg]
yaw: 0.0
top_front_center_right/camera_link:
x: 0.73058
y: -1.18899
z: -0.02166
roll: 0.0
pitch: 0.0
yaw: 0.0
top_front_center_left/camera_link:
x: 0.73058
y: -1.03819
z: -0.02166
roll: 0.0
pitch: 0.0
yaw: 0.0
top_front_left/camera_link:
x: 0.73058
y: -0.96279
z: -0.02166
roll: 0.0
pitch: 0.0
yaw: 0.0
top_front/gnss_link:
x: 0.30133
y: -1.07589
z: 0.02861
roll: 0.0
pitch: 0.0
yaw: 0.0

# rear upper
top_rear_center/camera_link:
x: -6.06359
y: -1.20389
z: -0.14078
roll: 0.0
pitch: 0.0
yaw: 3.141592 # 180 [deg] to turn the connector toward the vehicle
top_rear/gnss_link:
x: -5.77517
y: -1.07589
z: 0.02861
roll: 0.0
pitch: 0.0
yaw: 0.0

# front lower
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_lower/lidar_base_link:
x: 0.96758
y: -1.07589
z: -2.15234
roll: 0.6981 # 40[deg]
pitch: 0.0
yaw: 1.570796 # 90 [deg] to turn the connector toward the vehicle

# rear lower
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_lower/lidar_base_link:
x: -6.10742
y: -1.07589
z: -2.15234
roll: 0.6981 # 40[deg]
pitch: 0.0
yaw: -1.570796 # 90 [deg] to turn the connector toward the vehicle
57 changes: 57 additions & 0 deletions aip_x2_gen2_description/config/sensors_calibration.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
base_link:
sensor_kit_base_link:
x: 4.66244
y: 1.07589
z: 2.78926
roll: 0.0
pitch: 0.0
yaw: 0.0

# radar
front_center/radar_link:
x: 5.69207
y: 0.0
z: 0.78894
roll: 0.0
pitch: 0.0
yaw: 0.0

front_left/radar_link:
x: 5.37204
y: 1.08537
z: 0.73431
roll: 0.0
pitch: 0.0
yaw: 1.2211 # 70 [deg]

front_right/radar_link:
x: 5.37204
y: -1.06642
z: 0.73431
roll: 0.0
pitch: 0.0
yaw: -1.2211 # 70 [deg]

rear_center/radar_link:
x: -1.50704
y: 0.0
z: 0.78894
roll: 0.0
pitch: 0.0
yaw: 3.141592 # 180 [deg]

rear_left/radar_link:
x: -1.27564
y: 1.07767
z: 0.5487
roll: 0.0
pitch: 0.0
yaw: 1.9189 # 110 [deg]

rear_right/radar_link:
x: -1.27564
y: -1.07768
z: 0.5487
roll: 0.0
pitch: 0.0
yaw: -1.9189 # 110 [deg]
17 changes: 17 additions & 0 deletions aip_x2_gen2_description/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
<?xml version="1.0"?>
<package format="2">
<name>aip_x2_gen2_description</name>
<version>0.1.0</version>
<description>The aip_x2_gen2_description package</description>

<maintainer email="[email protected]">Tomohito Ando</maintainer>
<license>Apache 2</license>

<buildtool_depend>ament_cmake_auto</buildtool_depend>

<depend>pandar_description</depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
24 changes: 24 additions & 0 deletions aip_x2_gen2_description/urdf/gnss.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="gnss_macro" params="name parent x y z roll pitch yaw">
<xacro:property name="sensor_box" value="0.05"/>

<joint name="${name}_joint" type="fixed">
<origin rpy="${roll} ${pitch} ${yaw}" xyz="${x} ${y} ${z}"/>
<parent link="${parent}"/>
<child link="${name}_link"/>
</joint>

<link name="${name}_link">
<visual>
<geometry>
<box size="${sensor_box} ${sensor_box} ${sensor_box}"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="green">
<color rgba="0.0 1.0 0.0 1.0"/>
</material>
</visual>
</link>
</xacro:macro>
</robot>
31 changes: 31 additions & 0 deletions aip_x2_gen2_description/urdf/radar.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="radar_macro" params="name parent x y z roll pitch yaw">
<xacro:property name="mass" value="0.01" />

<joint name="${name}_base_mount_joint" type="fixed">
<origin rpy="${roll} ${pitch} ${yaw}" xyz="${x} ${y} ${z}"/>
<parent link="${parent}"/>
<child link="${name}"/>
</joint>

<link name="${name}">
<visual>
<geometry>
<box size="0.03 0.1 0.1"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="black">
<color rgba="0.1 0.1 0.1 1.0"/>
</material>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="${mass}"/>
<inertia ixx="${(0.03*0.03+0.03*0.03)*mass/12.0}" ixy="0.0" ixz="0.0"
iyy="${(0.1*0.1+0.1*0.1)*mass/12.0}" iyz="0.0"
izz="${(0.1*0.1+0.1*0.1)*mass/12.0}"/>
</inertial>
</link>
</xacro:macro>
</robot>
Loading
Loading