Browse Source

Updated xacro files (to match kraken prefab)

Signed-off-by: Paweł Budziszewski <[email protected]>
Paweł Budziszewski 2 years ago
parent
commit
dbea4288b8

+ 17 - 57
Project/Assets/robotec_freezed_urdf_chasis/kraken_chasis.xacro

@@ -17,7 +17,6 @@
         <mass value="300"/>
         <inertia ixx="50.0" ixy="0.0" ixz="0.0" iyy="240.0" iyz="0.0" izz="250.0"/>
       </inertial>
-         
       <visual>
         <origin rpy="0.000000 -0.000000 -1.570796" xyz="1.101831 0.000000 0.000000"/>
         <geometry>
@@ -55,9 +54,9 @@
          </geometry>
        </collision>
        <collision>
-        <origin rpy="1.570796 -0.000000 1.570796" xyz="2.565201 0.000000 0.432055"/>
+        <origin rpy="1.570796 -0.000000 1.570796" xyz="2.5402429 0.000000 0.562592"/>
         <geometry>
-           <box size="0.513190 0.131902 0.055878"/>
+           <box size="0.437199 0.131902 0.055878"/>
          </geometry>
        </collision>
        <collision>
@@ -66,6 +65,7 @@
            <box size="0.592215 0.555096 0.228493"/>
          </geometry>
        </collision>         
+
     </link>
 
     <link name="wheel_rear_right_link">
@@ -76,14 +76,14 @@
       </inertial>
 
       <visual>
-        <origin rpy="0 1.571 0" xyz="0 0 ${wheel_width}"/>
+        <origin rpy="0 1.571 0" xyz="0 0 0"/>
         <geometry>
-          <mesh filename="meshes/Wheels/WheelRight.dae" scale="0.6 0.6 0.6"/>
+          <mesh filename="meshes/Wheels/WheelRight.dae" scale="1 1 1"/>
         </geometry>
       </visual>
 
       <collision>
-        <origin rpy="0 0 0" xyz="0 0 ${wheel_width/2}"/>
+        <origin rpy="0 0 0" xyz="0 0 ${-wheel_width/2}"/>
         <geometry>
           <cylinder radius="${wheel_radius}" length="${wheel_width}" />
         </geometry>
@@ -98,14 +98,14 @@
       </inertial>
 
       <visual>
-        <origin rpy="0 -1.571 0 " xyz="0 0 0.0"/>
+        <origin rpy="0 1.571 0 " xyz="0 0 0.0"/>
         <geometry>
-          <mesh filename="meshes/Wheels/WheelLeft.dae" scale="0.6 0.6 0.6"/>
+          <mesh filename="meshes/Wheels/WheelLeft.dae" scale="1 1 1"/>
         </geometry>
       </visual>
 
       <collision>
-        <origin rpy="0 0 0" xyz="0 0 -${wheel_width/2}"/>
+        <origin rpy="0 0 0" xyz="0 0 ${wheel_width/2}"/>
         <geometry>
           <cylinder radius="${wheel_radius}" length="${wheel_width}" />
         </geometry>
@@ -114,7 +114,7 @@
 
     <link name="wheel_front_right_link">
       <inertial>
-        <origin rpy="0 0 0" xyz="0 0.0 ${-wheel_width/2}"/>
+        <origin rpy="0 0 0" xyz="0 0.0 ${wheel_width/2}"/>
         <mass value="24.5"/>
         <inertia ixx="0.787" ixy="0.0" ixz="0.0" iyy="0.787" iyz="0.0" izz="1.309"/>
       </inertial>
@@ -122,7 +122,7 @@
       <visual>
         <origin rpy="0 1.571 0" xyz="0 0 0"/>
         <geometry>
-          <mesh filename="meshes/Wheels/WheelRight.dae" scale="0.6 0.6 0.6"/>
+          <mesh filename="meshes/Wheels/WheelRight.dae" scale="1 1 1"/>
         </geometry>
       </visual>
 
@@ -142,9 +142,9 @@
       </inertial>
 
       <visual>
-        <origin rpy="0 -1.571 0" xyz="0 0 ${wheel_width}"/>
+        <origin rpy="0 1.571 0" xyz="0 0 0"/>
         <geometry>
-          <mesh filename="meshes/Wheels/WheelLeft.dae" scale="0.6 0.6 0.6"/>
+          <mesh filename="meshes/Wheels/WheelLeft.dae" scale="1 1 1"/>
         </geometry>
       </visual>
 
@@ -162,7 +162,7 @@
     <link name="steering_front_right_link">
       <inertial>
         <origin rpy="0 0 -1.571" xyz="0 0 -0.04"/>
-        <mass value="1"/>
+        <mass value="20.0"/>
         <inertia ixx="1" ixy="0.0" ixz="0.0" iyy="1" iyz="0.0" izz="1"/>
       </inertial>
 
@@ -177,7 +177,7 @@
     <link name="steering_front_left_link">
       <inertial>
         <origin rpy="0 0 -1.571" xyz="0 0 -0.04"/>
-        <mass value="1"/>
+        <mass value="20.0"/>
         <inertia ixx="1" ixy="0.0" ixz="0.0" iyy="1" iyz="0.0" izz="1"/>
       </inertial>
       <visual>
@@ -189,7 +189,7 @@
     </link>
 
     <joint name="wheel_rear_right_joint" type="continuous">
-      <origin rpy="-1.570796 -0.000000 0.000000" xyz="0.000000 ${wheel_base_rear} ${wheel_radius}"/>
+      <origin rpy="-1.570796 0.000000 0.000000" xyz="0.000000 ${-wheel_base_rear} ${wheel_radius}"/>
       <parent link="base_link"/>
       <child link="wheel_rear_right_link"/>
       <axis xyz="0.0 0.0 1.0"/>
@@ -197,7 +197,7 @@
     </joint>
 
     <joint name="wheel_rear_left_joint" type="continuous">
-      <origin rpy="-1.570796 -0.000000 0.000000" xyz="0.000000 ${-wheel_base_rear} ${wheel_radius}"/>
+      <origin rpy="-1.570796 -0.000000 0.000000" xyz="0.000000 ${wheel_base_rear} ${wheel_radius}"/>
       <parent link="base_link"/>
       <child link="wheel_rear_left_link"/>
       <axis xyz="0.0 0.0 1.0"/>
@@ -238,45 +238,5 @@
       <limit effort="1000000.0" lower="-0.5235" upper="0.5235" velocity="100"/>
     </joint>
 
-<!--     
-    <link name="manipulator_link_0_old">
-      <inertial>
-        <origin rpy="0.1745 0 0" xyz="0.0 -0.6 2.0"/>
-        <mass value="25.0"/>
-        <inertia ixx="0.002" ixy="0.0" ixz="0.0" iyy="0.068" iyz="0.0" izz="0.067"/>
-      </inertial>
-
-      <visual>
-        <origin rpy="-0.174533 0 0" xyz="0.9 -0.65 2.4"/>
-        <geometry>
-          <box size = "0.1 0.1 2.0"/>
-        </geometry>
-      </visual>
-      <visual>
-        <origin rpy="-0.174533 0 0" xyz="-0.9 -0.65 2.4"/>
-        <geometry>
-          <box size = "0.1 0.1 2.0"/>
-        </geometry>
-      </visual>
-
-      <collision>
-        <origin rpy="-0.174533 0 0" xyz="0.9 -0.65 2.4"/>
-        <geometry>
-          <box size = "0.1 0.1 2.0"/>
-        </geometry>
-      </collision>
-        <collision>
-        <origin rpy="-0.174533 0 0" xyz="-0.9 -0.65 2.4"/>
-        <geometry>
-          <box size = "0.1 0.1 2.0"/>
-        </geometry>
-      </collision>
-    </link>
-    <joint name="manipulator_joint_0" type="fixed">
-      <origin rpy="0 0 0" xyz="${manip_x+0.003927} ${manip_y} ${manip_z-1.0}"/>
-      <parent link="base_link"/>
-      <child link="manipulator_link_0_old"/>
-    </joint>  -->
-
  
 </robot>

+ 21 - 19
Project/Assets/robotec_freezed_urdf_chasis/kraken_manipulator.xacro

@@ -9,7 +9,7 @@
       <inertial>
         <origin rpy="0.1745 0 0" xyz="0.0 -0.6 2.0"/>
         <mass value="25.0"/>
-        <inertia ixx="0.002" ixy="0.0" ixz="0.0" iyy="0.068" iyz="0.0" izz="0.067"/>
+        <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
       </inertial>
 
       <visual>
@@ -18,7 +18,7 @@
           <mesh filename="meshes/ChassisAndFrame/ChassisAndFrame.dae" scale="1 1 1"/>
         </geometry>
       </visual>
-
+      <!--
       <collision>
         <origin rpy="1.570798 1.396264 4.712389" xyz="0.485927 -0.460373 1.404769"/>
         <geometry>
@@ -31,8 +31,9 @@
            <box size="2.451889 0.088234 0.088234"/>
          </geometry>
        </collision>
+       -->
        <collision>
-        <origin rpy="-0.174561 0.000000 0.000000" xyz="-0.646611 -0.254306 2.573430"/>
+        <origin rpy="-0.0872664626 0.000000 0.000000" xyz="-0.3812585 -0.374285 2.5734301"/>
         <geometry>
            <box size="2.087586 0.088237 0.062286"/>
          </geometry>
@@ -47,13 +48,13 @@
       </inertial>
 
       <visual>
-        <origin rpy="0 0 -1.571" xyz="0.0 0.0 0"/>
+        <origin rpy="0 0 -1.571" xyz="0.2528269 0.0 0"/>
         <geometry>
           <mesh filename="meshes/VacuumMechanismPart01/VacuumMechanismPart01.dae" scale="1 1 1"/>
         </geometry>
       </visual>
       <collision>
-        <origin rpy="-0.001888 -0.000000 0.000000" xyz="0.000000 0.062564 -0.000045"/>
+        <origin rpy="-0.000 -0.000000 0.000000" xyz="0.000000 0.062564 -0.000045"/>
         <geometry>
            <box size="2.019587 0.172379 0.067739"/>
          </geometry>
@@ -64,8 +65,8 @@
     <link name="kraken_manipulator_link_2">
       <inertial>
         <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
-        <mass value="10.0"/>
-        <inertia ixx="0.05" ixy="0.0" ixz="0.0" iyy="0.05" iyz="0.0" izz="0.05"/>
+        <mass value="25.0"/>
+        <inertia ixx="0.804004" ixy="0.0" ixz="0.0" iyy="0.9002936" iyz="0.0" izz="1.0483408"/>
       </inertial>
 
       <visual>
@@ -74,13 +75,14 @@
           <mesh filename="meshes/VacuumMechanismPart02/VacuumMechanismPart02.dae" scale="1 1 1"/>
         </geometry>
       </visual>
-
+      <!--
       <collision>
         <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
         <geometry>
            <box size="0.396177 0.322944 0.312368"/>
          </geometry>
        </collision>
+       -->
        <collision>
         <origin rpy="-1.570829 0 0 " xyz="-0.066974 -0.2 -0.000000"/>
         <geometry>
@@ -94,8 +96,8 @@
     <link name="kraken_manipulator_link_3">
       <inertial>
         <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
-        <mass value="5.0"/>
-        <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01"/>
+        <mass value="10.0"/>
+        <inertia ixx="0.5" ixy="0.0" ixz="0.0" iyy="0.5" iyz="0.0" izz="0.2"/>
       </inertial>
 
       <visual>
@@ -104,7 +106,7 @@
           <mesh filename="meshes/VacuumNozzle/VacuumNozzle.dae" scale="1 1 1"/>
         </geometry>
       </visual>
-
+      <!--
       <collision>
         <origin rpy="0 0 0" xyz="0 0 0.0"/>
         <geometry>
@@ -118,19 +120,19 @@
            <sphere  radius="0.03"/>
          </geometry>
        </collision>
-
+      -->
     </link>
 
     <!-- Nozzle02 -->
     <link name="kraken_manipulator_link_4">
       <inertial>
         <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
-        <mass value="5.0"/>
-        <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01"/>
+        <mass value="10.0"/>
+        <inertia ixx="0.5" ixy="0.0" ixz="0.0" iyy="0.5" iyz="0.0" izz="0.2"/>
       </inertial>
 
       <visual>
-        <origin rpy="0 -1.571 0" xyz="0.0 0.0 0"/>
+        <origin rpy="0 -1.4835298642 0" xyz="0.0 0.0 0"/>
         <geometry>
           <mesh filename="meshes/VacuumNozzle02/VacuumNozzle02.dae" scale="1 1 1"/>
         </geometry>
@@ -154,7 +156,7 @@
 
     <!-- Joint that moves manipulator along Z-Axis -->
     <joint name="kraken_manipulator_joint_1" type="prismatic">
-      <origin rpy="-0.1745 0 0" xyz="${manip_x-0.650001} -0.511055 1.6569"/>
+      <origin rpy="-0.0872664626 0 0" xyz="${manip_x-0.650001} -0.511055 1.6569"/>
       <parent link="base_link"/>
       <child link="kraken_manipulator_link_1"/>
       <axis xyz="0.0 0.0 1.0"/>
@@ -169,7 +171,7 @@
       <child link="kraken_manipulator_link_2"/>
       <axis xyz="0.0 0.0 1.0"/>
       <dynamics damping="2.0" friction="1.0"/>
-      <limit effort="1000.0" lower="-1.0" upper="1.0" velocity="1.0"/>
+      <limit effort="1000.0" lower="-0.8" upper="1.2" velocity="1.0"/>
     </joint>
 
     <!-- Nozzle -->
@@ -179,7 +181,7 @@
       <child link="kraken_manipulator_link_3"/>
       <axis xyz="0.0 0.0 1.0"/>
       <dynamics damping="2.0" friction="1.0"/>
-      <limit effort="1000.0" lower="0" upper="0.28" velocity="1.0"/>
+      <limit effort="1000.0" lower="0" upper="0.3" velocity="1.0"/>
     </joint>
 
     <!-- Nozzle02 -->
@@ -189,7 +191,7 @@
       <child link="kraken_manipulator_link_4"/>
       <axis xyz="0.0 0.0 1.0"/>
       <dynamics damping="2.0" friction="1.0"/>
-      <limit effort="1000.0" lower="0" upper="0.28" velocity="1.0"/>
+      <limit effort="1000.0" lower="0" upper="0.3" velocity="1.0"/>
     </joint>