|
@@ -9,7 +9,7 @@
|
|
<inertial>
|
|
<inertial>
|
|
<origin rpy="0.1745 0 0" xyz="0.0 -0.6 2.0"/>
|
|
<origin rpy="0.1745 0 0" xyz="0.0 -0.6 2.0"/>
|
|
<mass value="25.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>
|
|
</inertial>
|
|
|
|
|
|
<visual>
|
|
<visual>
|
|
@@ -18,7 +18,7 @@
|
|
<mesh filename="meshes/ChassisAndFrame/ChassisAndFrame.dae" scale="1 1 1"/>
|
|
<mesh filename="meshes/ChassisAndFrame/ChassisAndFrame.dae" scale="1 1 1"/>
|
|
</geometry>
|
|
</geometry>
|
|
</visual>
|
|
</visual>
|
|
-
|
|
|
|
|
|
+ <!--
|
|
<collision>
|
|
<collision>
|
|
<origin rpy="1.570798 1.396264 4.712389" xyz="0.485927 -0.460373 1.404769"/>
|
|
<origin rpy="1.570798 1.396264 4.712389" xyz="0.485927 -0.460373 1.404769"/>
|
|
<geometry>
|
|
<geometry>
|
|
@@ -31,8 +31,9 @@
|
|
<box size="2.451889 0.088234 0.088234"/>
|
|
<box size="2.451889 0.088234 0.088234"/>
|
|
</geometry>
|
|
</geometry>
|
|
</collision>
|
|
</collision>
|
|
|
|
+ -->
|
|
<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>
|
|
<geometry>
|
|
<box size="2.087586 0.088237 0.062286"/>
|
|
<box size="2.087586 0.088237 0.062286"/>
|
|
</geometry>
|
|
</geometry>
|
|
@@ -47,13 +48,13 @@
|
|
</inertial>
|
|
</inertial>
|
|
|
|
|
|
<visual>
|
|
<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>
|
|
<geometry>
|
|
<mesh filename="meshes/VacuumMechanismPart01/VacuumMechanismPart01.dae" scale="1 1 1"/>
|
|
<mesh filename="meshes/VacuumMechanismPart01/VacuumMechanismPart01.dae" scale="1 1 1"/>
|
|
</geometry>
|
|
</geometry>
|
|
</visual>
|
|
</visual>
|
|
<collision>
|
|
<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>
|
|
<geometry>
|
|
<box size="2.019587 0.172379 0.067739"/>
|
|
<box size="2.019587 0.172379 0.067739"/>
|
|
</geometry>
|
|
</geometry>
|
|
@@ -64,8 +65,8 @@
|
|
<link name="kraken_manipulator_link_2">
|
|
<link name="kraken_manipulator_link_2">
|
|
<inertial>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
|
|
<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>
|
|
</inertial>
|
|
|
|
|
|
<visual>
|
|
<visual>
|
|
@@ -74,13 +75,14 @@
|
|
<mesh filename="meshes/VacuumMechanismPart02/VacuumMechanismPart02.dae" scale="1 1 1"/>
|
|
<mesh filename="meshes/VacuumMechanismPart02/VacuumMechanismPart02.dae" scale="1 1 1"/>
|
|
</geometry>
|
|
</geometry>
|
|
</visual>
|
|
</visual>
|
|
-
|
|
|
|
|
|
+ <!--
|
|
<collision>
|
|
<collision>
|
|
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
|
|
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
|
|
<geometry>
|
|
<geometry>
|
|
<box size="0.396177 0.322944 0.312368"/>
|
|
<box size="0.396177 0.322944 0.312368"/>
|
|
</geometry>
|
|
</geometry>
|
|
</collision>
|
|
</collision>
|
|
|
|
+ -->
|
|
<collision>
|
|
<collision>
|
|
<origin rpy="-1.570829 0 0 " xyz="-0.066974 -0.2 -0.000000"/>
|
|
<origin rpy="-1.570829 0 0 " xyz="-0.066974 -0.2 -0.000000"/>
|
|
<geometry>
|
|
<geometry>
|
|
@@ -94,8 +96,8 @@
|
|
<link name="kraken_manipulator_link_3">
|
|
<link name="kraken_manipulator_link_3">
|
|
<inertial>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
|
|
<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>
|
|
</inertial>
|
|
|
|
|
|
<visual>
|
|
<visual>
|
|
@@ -104,7 +106,7 @@
|
|
<mesh filename="meshes/VacuumNozzle/VacuumNozzle.dae" scale="1 1 1"/>
|
|
<mesh filename="meshes/VacuumNozzle/VacuumNozzle.dae" scale="1 1 1"/>
|
|
</geometry>
|
|
</geometry>
|
|
</visual>
|
|
</visual>
|
|
-
|
|
|
|
|
|
+ <!--
|
|
<collision>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0.0"/>
|
|
<origin rpy="0 0 0" xyz="0 0 0.0"/>
|
|
<geometry>
|
|
<geometry>
|
|
@@ -118,19 +120,19 @@
|
|
<sphere radius="0.03"/>
|
|
<sphere radius="0.03"/>
|
|
</geometry>
|
|
</geometry>
|
|
</collision>
|
|
</collision>
|
|
-
|
|
|
|
|
|
+ -->
|
|
</link>
|
|
</link>
|
|
|
|
|
|
<!-- Nozzle02 -->
|
|
<!-- Nozzle02 -->
|
|
<link name="kraken_manipulator_link_4">
|
|
<link name="kraken_manipulator_link_4">
|
|
<inertial>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
|
|
<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>
|
|
</inertial>
|
|
|
|
|
|
<visual>
|
|
<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>
|
|
<geometry>
|
|
<mesh filename="meshes/VacuumNozzle02/VacuumNozzle02.dae" scale="1 1 1"/>
|
|
<mesh filename="meshes/VacuumNozzle02/VacuumNozzle02.dae" scale="1 1 1"/>
|
|
</geometry>
|
|
</geometry>
|
|
@@ -154,7 +156,7 @@
|
|
|
|
|
|
<!-- Joint that moves manipulator along Z-Axis -->
|
|
<!-- Joint that moves manipulator along Z-Axis -->
|
|
<joint name="kraken_manipulator_joint_1" type="prismatic">
|
|
<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"/>
|
|
<parent link="base_link"/>
|
|
<child link="kraken_manipulator_link_1"/>
|
|
<child link="kraken_manipulator_link_1"/>
|
|
<axis xyz="0.0 0.0 1.0"/>
|
|
<axis xyz="0.0 0.0 1.0"/>
|
|
@@ -169,7 +171,7 @@
|
|
<child link="kraken_manipulator_link_2"/>
|
|
<child link="kraken_manipulator_link_2"/>
|
|
<axis xyz="0.0 0.0 1.0"/>
|
|
<axis xyz="0.0 0.0 1.0"/>
|
|
<dynamics damping="2.0" friction="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>
|
|
</joint>
|
|
|
|
|
|
<!-- Nozzle -->
|
|
<!-- Nozzle -->
|
|
@@ -179,7 +181,7 @@
|
|
<child link="kraken_manipulator_link_3"/>
|
|
<child link="kraken_manipulator_link_3"/>
|
|
<axis xyz="0.0 0.0 1.0"/>
|
|
<axis xyz="0.0 0.0 1.0"/>
|
|
<dynamics damping="2.0" friction="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>
|
|
</joint>
|
|
|
|
|
|
<!-- Nozzle02 -->
|
|
<!-- Nozzle02 -->
|
|
@@ -189,7 +191,7 @@
|
|
<child link="kraken_manipulator_link_4"/>
|
|
<child link="kraken_manipulator_link_4"/>
|
|
<axis xyz="0.0 0.0 1.0"/>
|
|
<axis xyz="0.0 0.0 1.0"/>
|
|
<dynamics damping="2.0" friction="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>
|
|
</joint>
|
|
|
|
|
|
|
|
|