Add updated urdfs

This commit is contained in:
Thomason Zhou 2025-04-23 18:33:41 +09:00
parent 1a1084c627
commit f7ca1fe7b7
2 changed files with 131 additions and 17 deletions

View File

@ -32,7 +32,121 @@
<inertia ixx="0.6232810322991779" ixy="7.916644206828546e-12" ixz="-1.094192214704477e-11" iyy="0.6253514495087933" iyz="-0.03342233248166168" izz="0.02000994027356939"/>
</inertial>
</link>
<!-- <xacro:include filename="openarm_bimanual_sensors.xacro"/> -->
<material name="aluminum">
<color rgba="0.5 0.5 0.5 1"/>
</material>
<material name="plastic">
<color rgba="0.1 0.1 0.1 1"/>
</material>
<!-- camera body, with origin at bottom screw mount -->
<joint name="camera_joint" type="fixed">
<origin rpy="0.0 1.3962634015954636 -1.5707963267948966" xyz="0.0 -0.025 0.995216"/>
<parent link="pedestal_link"/>
<child link="camera_bottom_screw_frame"/>
</joint>
<link name="camera_bottom_screw_frame"/>
<joint name="camera_link_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.010600000000000002 0.0175 0.0125"/>
<parent link="camera_bottom_screw_frame"/>
<child link="camera_link"/>
</joint>
<link name="camera_link">
<visual>
<!-- the mesh origin is at front plate in between the two infrared camera axes -->
<origin rpy="1.5707963267948966 0 1.5707963267948966" xyz="0.0043 -0.0175 0"/>
<geometry>
<mesh filename="file:///opt/ros/humble/share/realsense2_description/meshes/d435.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 -0.0175 0"/>
<geometry>
<box size="0.02505 0.09 0.025"/>
</geometry>
</collision>
<inertial>
<!-- The following are not reliable values, and should not be used for modeling -->
<mass value="0.072"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.003881243" ixy="0.0" ixz="0.0" iyy="0.000498940" iyz="0.0" izz="0.003879257"/>
</inertial>
</link>
<!-- camera depth joints and links -->
<joint name="camera_depth_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="camera_link"/>
<child link="camera_depth_frame"/>
</joint>
<link name="camera_depth_frame"/>
<joint name="camera_depth_optical_joint" type="fixed">
<origin rpy="-1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0"/>
<parent link="camera_depth_frame"/>
<child link="camera_depth_optical_frame"/>
</joint>
<link name="camera_depth_optical_frame"/>
<!-- camera left IR joints and links -->
<joint name="camera_infra1_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0 0"/>
<parent link="camera_link"/>
<child link="camera_infra1_frame"/>
</joint>
<link name="camera_infra1_frame"/>
<joint name="camera_infra1_optical_joint" type="fixed">
<origin rpy="-1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0"/>
<parent link="camera_infra1_frame"/>
<child link="camera_infra1_optical_frame"/>
</joint>
<link name="camera_infra1_optical_frame"/>
<!-- camera right IR joints and links -->
<joint name="camera_infra2_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.05 0"/>
<parent link="camera_link"/>
<child link="camera_infra2_frame"/>
</joint>
<link name="camera_infra2_frame"/>
<joint name="camera_infra2_optical_joint" type="fixed">
<origin rpy="-1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0"/>
<parent link="camera_infra2_frame"/>
<child link="camera_infra2_optical_frame"/>
</joint>
<link name="camera_infra2_optical_frame"/>
<!-- camera color joints and links -->
<joint name="camera_color_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.015 0"/>
<parent link="camera_link"/>
<child link="camera_color_frame"/>
</joint>
<link name="camera_color_frame"/>
<joint name="camera_color_optical_joint" type="fixed">
<origin rpy="-1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0"/>
<parent link="camera_color_frame"/>
<child link="camera_color_optical_frame"/>
</joint>
<link name="camera_color_optical_frame"/>
<link name="camera_accel_frame"/>
<link name="camera_accel_optical_frame"/>
<link name="camera_gyro_frame"/>
<link name="camera_gyro_optical_frame"/>
<joint name="camera_accel_joint" type="fixed">
<origin rpy="0 0 0" xyz="-0.01174 -0.00552 0.0051"/>
<parent link="camera_link"/>
<child link="camera_accel_frame"/>
</joint>
<joint name="camera_accel_optical_joint" type="fixed">
<origin rpy="-1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0"/>
<parent link="camera_accel_frame"/>
<child link="camera_accel_optical_frame"/>
</joint>
<joint name="camera_gyro_joint" type="fixed">
<origin rpy="0 0 0" xyz="-0.01174 -0.00552 0.0051"/>
<parent link="camera_link"/>
<child link="camera_gyro_frame"/>
</joint>
<joint name="camera_gyro_optical_joint" type="fixed">
<origin rpy="-1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0"/>
<parent link="camera_gyro_frame"/>
<child link="camera_gyro_optical_frame"/>
</joint>
<link name="world"/>
<joint name="dummy_joint" type="fixed">
<parent link="world"/>
@ -334,15 +448,15 @@
<parent link="right_link2"/>
<child link="right_link3"/>
<origin rpy="-1.5707963267948968 0.0 0.0" xyz="0.0 -0.02975 0.04475"/>
<axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-3.141592653589793" upper="0" velocity="0.0"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="0" upper="3.141592653589793" velocity="0.0"/>
</joint>
<joint name="right_rev3" type="revolute">
<parent link="right_link3"/>
<child link="right_link4"/>
<origin rpy="-1.5707963267949054 0 -1.562038143900564" xyz="-0.0612477 -0.000536432 0.02975"/>
<axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-3.6651914291880923" upper="0.5235987755982988" velocity="0.0"/>
<limit effort="0.0" lower="-0.52359" upper="3.66519" velocity="0.0"/>
</joint>
<joint name="right_rev4" type="revolute">
<parent link="right_link4"/>
@ -376,14 +490,14 @@
<parent link="right_link8"/>
<child link="right_link_left_jaw"/>
<origin rpy="1.570796326795101 -0.014066001454929162 0.00875904933542146" xyz="-0.1071 0.0768568 0.0132053"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.0"/>
<axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.1"/>
</joint>
<joint name="right_right_pris2" type="prismatic">
<parent link="right_link8"/>
<child link="right_link_right_jaw"/>
<origin rpy="1.570796326794883 -0.014066001454927403 0.008759049336290027" xyz="-0.10571 -0.0781373 0.0132053"/>
<axis xyz="0 0 1"/>
<axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.0"/>
<mimic joint="right_left_pris1" multiplier="-1.0" offset="0.0"/>
</joint>
@ -693,14 +807,14 @@
<child link="left_link3"/>
<origin rpy="-1.5707963267948968 0.0 0.0" xyz="0.0 -0.02975 0.04475"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="0.0" upper="3.141592653589793" velocity="0.0"/>
<limit effort="0.0" lower="0" upper="3.141592653589793" velocity="0.0"/>
</joint>
<joint name="left_rev3" type="revolute">
<parent link="left_link3"/>
<child link="left_link4"/>
<origin rpy="-1.5707963267949054 3.141592653589793 -1.562038143900564" xyz="-0.0612477 -0.000536432 0.02975"/>
<axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-3.6651914291880923" upper="0.5235987755982988" velocity="0.0"/>
<limit effort="0.0" lower="-3.66519" upper="0.52359" velocity="0.0"/>
</joint>
<joint name="left_rev4" type="revolute">
<parent link="left_link4"/>
@ -734,14 +848,14 @@
<parent link="left_link8"/>
<child link="left_link_left_jaw"/>
<origin rpy="1.570796326795101 -0.014066001454929162 0.00875904933542146" xyz="-0.1071 0.0768568 0.0132053"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.0"/>
<axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.1"/>
</joint>
<joint name="left_right_pris2" type="prismatic">
<parent link="left_link8"/>
<child link="left_link_right_jaw"/>
<origin rpy="1.570796326794883 -0.014066001454927403 0.008759049336290027" xyz="-0.10571 -0.0781373 0.0132053"/>
<axis xyz="0 0 1"/>
<axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.0"/>
<mimic joint="left_left_pris1" multiplier="-1.0" offset="0.0"/>
</joint>

View File

@ -305,7 +305,7 @@
<parent link="link2"/>
<child link="link3"/>
<origin rpy="-1.5707963267948968 1.5707963267948966 0.0" xyz="0.0 -0.02975 0.04475"/>
<axis xyz="0 0 -1"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-1.5707963267948966" upper="1.5707963267948966" velocity="0.0"/>
</joint>
<joint name="rev3" type="revolute">
@ -313,7 +313,7 @@
<child link="link4"/>
<origin rpy="-1.5707963267949054 0 -1.562038143900564" xyz="-0.0612477 -0.000536432 0.02975"/>
<axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-3.6651914291880923" upper="0.5235987755982988" velocity="0.0"/>
<limit effort="0.0" lower="-0.52359" upper="3.66519" velocity="0.0"/>
</joint>
<joint name="rev4" type="revolute">
<parent link="link4"/>
@ -347,14 +347,14 @@
<parent link="link8"/>
<child link="link_left_jaw"/>
<origin rpy="1.570796326795101 -0.014066001454929162 0.00875904933542146" xyz="-0.1071 0.0768568 0.0132053"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.0"/>
<axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.1"/>
</joint>
<joint name="right_pris2" type="prismatic">
<parent link="link8"/>
<child link="link_right_jaw"/>
<origin rpy="1.570796326794883 -0.014066001454927403 0.008759049336290027" xyz="-0.10571 -0.0781373 0.0132053"/>
<axis xyz="0 0 1"/>
<axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.0"/>
<mimic joint="left_pris1" multiplier="-1.0" offset="0.0"/>
</joint>