|
15 | 15 | <!-- Include sensors --> |
16 | 16 | <xacro:include filename="$(find curt_mini)/models/curt_mini/sensors.xacro" /> |
17 | 17 |
|
18 | | - <link name="base_link"> |
| 18 | + <link name="base_link" /> |
| 19 | + |
| 20 | + <!-- Chassis link at same position as base_link, as root is not allowed to have inertial information --> |
| 21 | + <link name="chassis"> |
19 | 22 | <inertial> |
20 | 23 | <origin xyz="-0.0076959 -0.0021447 0.056616" rpy="0 0 0" /> |
21 | 24 | <mass value="9.6512" /> |
22 | | - <inertia ixx="0.036046" ixy="-1.6181E-05" ixz="-0.00088314" iyy="0.10986" iyz="-3.4695E-06" izz="0.12533" /> |
| 25 | + <inertia ixx="0.036046" ixy="-1.6181E-05" ixz="-0.00088314" iyy="0.10986" iyz="-3.4695E-06" |
| 26 | + izz="0.12533" /> |
23 | 27 | </inertial> |
24 | 28 | <visual> |
25 | 29 | <origin xyz="0 0 0" rpy="0 0 0" /> |
|
37 | 41 | </geometry> |
38 | 42 | </collision> |
39 | 43 | </link> |
| 44 | + <joint name="base_to_footprint" type="fixed"> |
| 45 | + <parent link="base_link" /> |
| 46 | + <child link="chassis" /> |
| 47 | + </joint> |
40 | 48 |
|
41 | 49 | <link name="front_right_wheel"> |
42 | 50 | <inertial> |
43 | 51 | <origin xyz="-5.87030424270552E-15 0.00750997550383756 -5.38805111638396E-15" rpy="0 0 0" /> |
44 | 52 | <mass value="1.16081815267191" /> |
45 | | - <inertia ixx="0.00489876810873934" ixy="9.50165704321153E-19" ixz="-2.61848606081355E-08" iyy="0.00918238967794609" iyz="-1.71449040958554E-17" izz="0.00489885881575725" /> |
| 53 | + <inertia ixx="0.00489876810873934" ixy="9.50165704321153E-19" ixz="-2.61848606081355E-08" |
| 54 | + iyy="0.00918238967794609" iyz="-1.71449040958554E-17" izz="0.00489885881575725" /> |
46 | 55 | </inertial> |
47 | 56 | <visual> |
48 | 57 | <origin xyz="0 0 0" rpy="0 0 0" /> |
|
56 | 65 | <collision> |
57 | 66 | <origin xyz="0 0.01 0" rpy="${PI / 2} 0 0" /> |
58 | 67 | <geometry> |
59 | | - <cylinder radius="${wheel_radius}" length="${wheel_width}"/> |
| 68 | + <cylinder radius="${wheel_radius}" length="${wheel_width}" /> |
60 | 69 | </geometry> |
61 | 70 | </collision> |
62 | 71 | </link> |
|
74 | 83 | <inertial> |
75 | 84 | <origin xyz="2.97539770599542E-14 -0.00750997550383714 6.53053999766229E-14" rpy="0 0 0" /> |
76 | 85 | <mass value="1.16081815267191" /> |
77 | | - <inertia ixx="0.00489876810873935" ixy="3.91724337570418E-19" ixz="2.61848606067545E-08" iyy="0.00918238967794612" iyz="1.81861039773823E-17" izz="0.00489885881575728" /> |
| 86 | + <inertia ixx="0.00489876810873935" ixy="3.91724337570418E-19" ixz="2.61848606067545E-08" |
| 87 | + iyy="0.00918238967794612" iyz="1.81861039773823E-17" izz="0.00489885881575728" /> |
78 | 88 | </inertial> |
79 | 89 | <visual> |
80 | 90 | <origin xyz="0 0 0" rpy="0 0 0" /> |
|
88 | 98 | <collision> |
89 | 99 | <origin xyz="0 -0.01 0" rpy="${PI / 2} 0 0" /> |
90 | 100 | <geometry> |
91 | | - <cylinder radius="${wheel_radius}" length="${wheel_width}"/> |
| 101 | + <cylinder radius="${wheel_radius}" length="${wheel_width}" /> |
92 | 102 | </geometry> |
93 | 103 | </collision> |
94 | 104 | </link> |
|
106 | 116 | <inertial> |
107 | 117 | <origin xyz="-3.25850457727483E-14 0.00750997550383728 5.8935495372836E-14" rpy="0 0 0" /> |
108 | 118 | <mass value="1.16081815267191" /> |
109 | | - <inertia ixx="0.00489876810873933" ixy="9.33801693307905E-19" ixz="-2.61848606033406E-08" iyy="0.00918238967794609" iyz="-1.82258288287945E-17" izz="0.00489885881575725" /> |
| 119 | + <inertia ixx="0.00489876810873933" ixy="9.33801693307905E-19" ixz="-2.61848606033406E-08" |
| 120 | + iyy="0.00918238967794609" iyz="-1.82258288287945E-17" izz="0.00489885881575725" /> |
110 | 121 | </inertial> |
111 | 122 | <visual> |
112 | 123 | <origin xyz="0 0 0" rpy="0 0 0" /> |
|
120 | 131 | <collision> |
121 | 132 | <origin xyz="0 0.01 0" rpy="${PI / 2} 0 0" /> |
122 | 133 | <geometry> |
123 | | - <cylinder radius="${wheel_radius}" length="${wheel_width}"/> |
| 134 | + <cylinder radius="${wheel_radius}" length="${wheel_width}" /> |
124 | 135 | </geometry> |
125 | 136 | </collision> |
126 | 137 | </link> |
|
138 | 149 | <inertial> |
139 | 150 | <origin xyz="3.05311331771918E-15 -0.00750997550383753 2.26554885962571E-15" rpy="0 0 0" /> |
140 | 151 | <mass value="1.16081815267191" /> |
141 | | - <inertia ixx="0.00489876810873933" ixy="1.74686590365548E-18" ixz="2.61848606031113E-08" iyy="0.00918238967794607" iyz="1.56928180377104E-17" izz="0.00489885881575724" /> |
| 152 | + <inertia ixx="0.00489876810873933" ixy="1.74686590365548E-18" ixz="2.61848606031113E-08" |
| 153 | + iyy="0.00918238967794607" iyz="1.56928180377104E-17" izz="0.00489885881575724" /> |
142 | 154 | </inertial> |
143 | 155 | <visual> |
144 | 156 | <origin xyz="0 0 0" rpy="0 0 0" /> |
|
152 | 164 | <collision> |
153 | 165 | <origin xyz="0 -0.01 0" rpy="${PI / 2} 0 0" /> |
154 | 166 | <geometry> |
155 | | - <cylinder radius="${wheel_radius}" length="${wheel_width}"/> |
| 167 | + <cylinder radius="${wheel_radius}" length="${wheel_width}" /> |
156 | 168 | </geometry> |
157 | 169 | </collision> |
158 | 170 | </link> |
|
167 | 179 | <xacro:wheel_transmissions prefix="back_left_motor" /> |
168 | 180 |
|
169 | 181 | <!-- Import gazebo infos --> |
170 | | - <xacro:if value="$(arg simulation)" > |
| 182 | + <xacro:if value="$(arg simulation)"> |
171 | 183 | <xacro:include filename="$(find curt_mini)/models/curt_mini/gazebo.xacro" /> |
172 | 184 | </xacro:if> |
173 | 185 |
|
|
0 commit comments