]> defiant.homedns.org Git - wt_open_manipulator.git/blobdiff - urdf/open_manipulator.urdf
replace id 12 with xm540-w270
[wt_open_manipulator.git] / urdf / open_manipulator.urdf
index 8cfa94b58a1ba025cbabd9a29d7d9065b9f93fe2..9461acf7eadfdba9e71f51dd04c3c637c1867423 100644 (file)
@@ -1,10 +1,10 @@
 <?xml version="1.0" encoding="utf-8"?>
 <!-- =================================================================================== -->
-<!-- |    This document was autogenerated by xacro from open_manipulator.urdf.xacro    | -->
+<!-- |    This document was autogenerated by xacro from /home/erik/Projects/ros_catkin_ws/src/wt_open_manipulator/urdf/open_manipulator.urdf.xacro | -->
 <!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
 <!-- =================================================================================== -->
 <!-- Open_Manipulator Chain -->
-<robot name="open_manipulator" xmlns:xacro="http://ros.org/wiki/xacro">
+<robot name="open_manipulator">
   <!-- World -->
   <gazebo reference="world">
   </gazebo>
   <material name="brown">
     <color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
   </material>
+  <link name="open_manipulator_base">
+       </link>
+  <joint name="world_fixed" type="fixed">
+    <origin rpy="0 0 0" xyz="0 0 0"/>
+    <parent link="open_manipulator_base"/>
+    <child link="link1"/>
+  </joint>
   <!-- Link 1 -->
   <link name="link1">
     <visual>
   <joint name="joint1" type="revolute">
     <parent link="link1"/>
     <child link="link2"/>
-    <origin rpy="0 0 0" xyz="0.012 0.0 0.017"/>
+    <origin rpy="0 0 0" xyz="0.012 0.0 0.036"/>
+    <!-- Height servo+horn -->
     <axis xyz="0 0 1"/>
-    <limit effort="1" lower="-3.14159265359" upper="3.14159265359" velocity="4.8"/>
+    <limit effort="1" lower="-3.14159265359" upper="3.14159265359" velocity="3.1"/>
   </joint>
   <transmission name="tran1">
     <type>transmission_interface/SimpleTransmission</type>
   <!--  Link 2 -->
   <link name="link2">
     <visual>
-      <origin rpy="0 0 0" xyz="0 0 0.019"/>
       <geometry>
-        <mesh filename="package://open_manipulator_description/meshes/chain_link2.stl" scale="0.001 0.001 0.001"/>
+        <mesh filename="package://open_manipulator_description/meshes/chain_link2.stl" scale="0.00117543859649 0.00129411764706 0.00125806451613"/>
+        <!-- scale by XM540 -->
       </geometry>
       <material name="grey"/>
     </visual>
     <collision>
-      <origin rpy="0 0 0" xyz="0 0 0.019"/>
       <geometry>
-        <mesh filename="package://open_manipulator_description/meshes/chain_link2.stl" scale="0.001 0.001 0.001"/>
+        <mesh filename="package://open_manipulator_description/meshes/chain_link2.stl" scale="0.00117543859649 0.00129411764706 0.00125806451613"/>
+        <!-- scale by XM540 -->
       </geometry>
     </collision>
     <!--    <inertial>
   <joint name="joint2" type="revolute">
     <parent link="link2"/>
     <child link="link3"/>
-    <origin rpy="0 0 0" xyz="0.0 0.0 0.0595"/>
+    <origin rpy="0 0 0" xyz="0.0 0.0 0.0515"/>
+    <!-- fr13-s102k to middle of servo horn -->
     <axis xyz="0 1 0"/>
     <limit effort="1" lower="-2.0106192983" upper="2.0106192983" velocity="4.8"/>
   </joint>
     <visual>
       <origin rpy="0 0 0" xyz="0 0 0"/>
       <geometry>
-        <mesh filename="package://open_manipulator_description/meshes/chain_link3.stl" scale="0.001 0.001 0.001"/>
+        <mesh filename="package://open_manipulator_description/meshes/chain_link3.stl" scale="0.001 0.001 0.00103125"/>
+        <!-- scale by 4mm more, see joint3 -->
       </geometry>
       <material name="grey"/>
     </visual>
     <collision>
       <origin rpy="0 0 0" xyz="0 0 0"/>
       <geometry>
-        <mesh filename="package://open_manipulator_description/meshes/chain_link3.stl" scale="0.001 0.001 0.001"/>
+        <mesh filename="package://open_manipulator_description/meshes/chain_link3.stl" scale="0.001 0.001 0.00103125"/>
+        <!-- scale by 4mm more, see joint3 -->
       </geometry>
     </collision>
     <!--    <inertial>
   <joint name="joint3" type="revolute">
     <parent link="link3"/>
     <child link="link4"/>
-    <origin rpy="0 0 0" xyz="0.024 0 0.128"/>
+    <origin rpy="0 0 0" xyz="0.024 0 0.132"/>
+    <!-- 4mm more for FR13-H101K-->
     <axis xyz="0 1 0"/>
     <limit effort="1" lower="-2.0106192983" upper="1.50796447372" velocity="4.8"/>
   </joint>
       <inertia ixx="1.0e-06" ixy="0.0" ixz="0.0" iyy="1.0e-06" iyz="0.0" izz="1.0e-06"/>
     </inertial>
   </link>
+  <material name="camera_aluminum">
+    <color rgba="0.5 0.5 0.5 1"/>
+  </material>
+  <!-- camera body, with origin at bottom screw mount -->
+  <joint name="camera_joint" type="fixed">
+    <origin rpy="0 0 0" xyz="-0.02 -0.018 0.055"/>
+    <parent link="gripper_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 0.0175 0.0125"/>
+    <parent link="camera_bottom_screw_frame"/>
+    <child link="camera_link"/>
+  </joint>
+  <link name="camera_link">
+    <visual>
+      <origin rpy="1.57079632679 0 1.57079632679" xyz="0.0149 -0.0175 0"/>
+      <geometry>
+        <!-- <box size="${d435_cam_width} ${d435_cam_height} ${d435_cam_depth}"/> -->
+        <mesh filename="package://realsense2_description/meshes/d435.dae"/>
+        <!--<mesh filename="package://realsense2_description/meshes/d435/d435.dae" />-->
+      </geometry>
+      <material name="camera_aluminum"/>
+    </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.564"/>
+      <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.57079632679 0 -1.57079632679" 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_left_ir_joint" type="fixed">
+    <origin rpy="0 0 0" xyz="0 0.0 0"/>
+    <parent link="camera_depth_frame"/>
+    <child link="camera_left_ir_frame"/>
+  </joint>
+  <link name="camera_left_ir_frame"/>
+  <joint name="camera_left_ir_optical_joint" type="fixed">
+    <origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0"/>
+    <parent link="camera_left_ir_frame"/>
+    <child link="camera_left_ir_optical_frame"/>
+  </joint>
+  <link name="camera_left_ir_optical_frame"/>
+  <!-- camera right IR joints and links -->
+  <joint name="camera_right_ir_joint" type="fixed">
+    <origin rpy="0 0 0" xyz="0 -0.05 0"/>
+    <parent link="camera_depth_frame"/>
+    <child link="camera_right_ir_frame"/>
+  </joint>
+  <link name="camera_right_ir_frame"/>
+  <joint name="camera_right_ir_optical_joint" type="fixed">
+    <origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0"/>
+    <parent link="camera_right_ir_frame"/>
+    <child link="camera_right_ir_optical_frame"/>
+  </joint>
+  <link name="camera_right_ir_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_depth_frame"/>
+    <child link="camera_color_frame"/>
+  </joint>
+  <link name="camera_color_frame"/>
+  <joint name="camera_color_optical_joint" type="fixed">
+    <origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0"/>
+    <parent link="camera_color_frame"/>
+    <child link="camera_color_optical_frame"/>
+  </joint>
+  <link name="camera_color_optical_frame"/>
 </robot>