Commit 3ba6216ed9833a27c9a4d763da296524f285a7d6

Authored by Ricardo Rico Uribe
1 parent 49a7ebda

corrected for inertias

Showing 1 changed file with 35 additions and 27 deletions   Show diff stats
aquanaute_description/urdf/aquanaute.urdf
@@ -31,13 +31,21 @@ @@ -31,13 +31,21 @@
31 31
32 <!-- * * * Link Definitions * * * --> 32 <!-- * * * Link Definitions * * * -->
33 <link name="base_link"> 33 <link name="base_link">
34 - <!-- 34 + <visual>
  35 + <origin rpy="0.0 0 0" xyz="0 0 0"/>
  36 + <geometry>
  37 + <sphere radius="0.001"/>
  38 + </geometry>
  39 + <material name="blue"/>
  40 + </visual>
  41 + </link>
  42 +
  43 + <link name="platform_link">
35 <inertial> 44 <inertial>
36 - <origin xyz="0 0 0" rpy="0 0 0"/>  
37 - <mass value="10.5"/>  
38 - <inertia ixx="0.0002835" ixy="0.0" ixz="0.0" iyy="0.0002835" iyz="0.0" izz="0.000324"/> 45 + <origin xyz="-0.024 0 -0007" rpy="0 0 0"/>
  46 + <mass value="16"/>
  47 + <inertia ixx="4.206" ixy="0.0" ixz="-0.031" iyy="4.588" iyz="0.0" izz="8.785"/>
39 </inertial> 48 </inertial>
40 - -->  
41 49
42 <collision> 50 <collision>
43 <origin xyz="0 0 0" rpy="0 0 0"/> 51 <origin xyz="0 0 0" rpy="0 0 0"/>
@@ -56,13 +64,12 @@ @@ -56,13 +64,12 @@
56 </link> 64 </link>
57 65
58 <link name="right_hull_link"> 66 <link name="right_hull_link">
59 - <!--  
60 <inertial> 67 <inertial>
61 - <origin xyz="0 0 0" rpy="0 0 0"/>  
62 - <mass value="10.5"/>  
63 - <inertia ixx="0.0002835" ixy="0.0" ixz="0.0" iyy="0.0002835" iyz="0.0" izz="0.000324"/> 68 + <origin xyz="-0.124 0 -0.168" rpy="0 0 0"/>
  69 + <mass value="10.45"/>
  70 + <inertia ixx="0.244" ixy="3.346" ixz="0.009" iyy="4.974" iyz="-8.274" izz="4.965"/>
64 </inertial> 71 </inertial>
65 - --> 72 +
66 <collision> 73 <collision>
67 <origin xyz="0 0 0" rpy="0 0 0"/> 74 <origin xyz="0 0 0" rpy="0 0 0"/>
68 <geometry> 75 <geometry>
@@ -80,13 +87,11 @@ @@ -80,13 +87,11 @@
80 </link> 87 </link>
81 88
82 <link name="left_hull_link"> 89 <link name="left_hull_link">
83 - <!--  
84 <inertial> 90 <inertial>
85 - <origin xyz="0 0 0" rpy="0 0 0"/>  
86 - <mass value="10.5"/>  
87 - <inertia ixx="0.0002835" ixy="0.0" ixz="0.0" iyy="0.0002835" iyz="0.0" izz="0.000324"/> 91 + <origin xyz="-0.124 0 -0.168" rpy="0 0 0"/>
  92 + <mass value="10.45"/>
  93 + <inertia ixx="0.244" ixy="3.346" ixz="0.009" iyy="4.974" iyz="-8.274" izz="4.965"/>
88 </inertial> 94 </inertial>
89 - -->  
90 95
91 <collision> 96 <collision>
92 <origin xyz="0 0 0" rpy="0 0 0"/> 97 <origin xyz="0 0 0" rpy="0 0 0"/>
@@ -105,13 +110,11 @@ @@ -105,13 +110,11 @@
105 </link> 110 </link>
106 111
107 <link name="motor_link"> 112 <link name="motor_link">
108 - <!--  
109 <inertial> 113 <inertial>
110 - <origin xyz="0 0 0" rpy="0 0 0"/>  
111 - <mass value="10.5"/>  
112 - <inertia ixx="0.0002835" ixy="0.0" ixz="0.0" iyy="0.0002835" iyz="0.0" izz="0.000324"/> 114 + <origin xyz="-0.133 0 -0.391" rpy="0 0 0"/>
  115 + <mass value="6.6"/>
  116 + <inertia ixx="0.072" ixy="3.604" ixz="-0.011" iyy="0.111" iyz="5.484" izz="0.042"/>
113 </inertial> 117 </inertial>
114 - -->  
115 118
116 <collision> 119 <collision>
117 <origin xyz="0 0 0" rpy="0 0 0"/> 120 <origin xyz="0 0 0" rpy="0 0 0"/>
@@ -130,13 +133,12 @@ @@ -130,13 +133,12 @@
130 </link> 133 </link>
131 134
132 <link name="sensor_frame_link"> 135 <link name="sensor_frame_link">
133 - <!--  
134 <inertial> 136 <inertial>
135 - <origin xyz="0 0 0" rpy="0 0 0"/>  
136 - <mass value="10.5"/>  
137 - <inertia ixx="0.0002835" ixy="0.0" ixz="0.0" iyy="0.0002835" iyz="0.0" izz="0.000324"/> 137 + <origin xyz="-0.007 0 0.379" rpy="0 0 0"/>
  138 + <mass value="1.8"/>
  139 + <inertia ixx="0.308" ixy="0.00" ixz="0.007" iyy="0.297" iyz="0.00" izz="0.022"/>
138 </inertial> 140 </inertial>
139 - --> 141 +
140 <collision> 142 <collision>
141 <origin xyz="0 0 0" rpy="0 0 0"/> 143 <origin xyz="0 0 0" rpy="0 0 0"/>
142 <geometry> 144 <geometry>
@@ -154,14 +156,20 @@ @@ -154,14 +156,20 @@
154 </link> 156 </link>
155 157
156 <!-- * * * Joint Definitions * * * --> 158 <!-- * * * Joint Definitions * * * -->
157 - <joint name="right_hull_platform_joint" type="fixed"> 159 + <joint name="platform_base_joint" type="fixed">
158 <parent link="base_link"/> 160 <parent link="base_link"/>
  161 + <child link="platform_link"/>
  162 + <origin xyz="0 0 0" rpy="0 0 0"/>
  163 + </joint>
  164 +
  165 + <joint name="right_hull_platform_joint" type="fixed">
  166 + <parent link="platform_link"/>
159 <child link="right_hull_link"/> 167 <child link="right_hull_link"/>
160 <origin xyz="-0.05 -0.7 -0.036" rpy="0 0 0"/> 168 <origin xyz="-0.05 -0.7 -0.036" rpy="0 0 0"/>
161 </joint> 169 </joint>
162 170
163 <joint name="left_hull_platform_joint" type="fixed"> 171 <joint name="left_hull_platform_joint" type="fixed">
164 - <parent link="base_link"/> 172 + <parent link="platform_link"/>
165 <child link="left_hull_link"/> 173 <child link="left_hull_link"/>
166 <origin xyz="-0.05 0.7 -0.036" rpy="0 0 0"/> 174 <origin xyz="-0.05 0.7 -0.036" rpy="0 0 0"/>
167 </joint> 175 </joint>