Skip to content

Commit 89b7ae7

Browse files
committed
add chassis link
1 parent 6ccbf6e commit 89b7ae7

File tree

1 file changed

+23
-11
lines changed

1 file changed

+23
-11
lines changed

curt_mini/models/curt_mini/robot.urdf.xacro

Lines changed: 23 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -15,11 +15,15 @@
1515
<!-- Include sensors -->
1616
<xacro:include filename="$(find curt_mini)/models/curt_mini/sensors.xacro" />
1717

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">
1922
<inertial>
2023
<origin xyz="-0.0076959 -0.0021447 0.056616" rpy="0 0 0" />
2124
<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" />
2327
</inertial>
2428
<visual>
2529
<origin xyz="0 0 0" rpy="0 0 0" />
@@ -37,12 +41,17 @@
3741
</geometry>
3842
</collision>
3943
</link>
44+
<joint name="base_to_footprint" type="fixed">
45+
<parent link="base_link" />
46+
<child link="chassis" />
47+
</joint>
4048

4149
<link name="front_right_wheel">
4250
<inertial>
4351
<origin xyz="-5.87030424270552E-15 0.00750997550383756 -5.38805111638396E-15" rpy="0 0 0" />
4452
<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" />
4655
</inertial>
4756
<visual>
4857
<origin xyz="0 0 0" rpy="0 0 0" />
@@ -56,7 +65,7 @@
5665
<collision>
5766
<origin xyz="0 0.01 0" rpy="${PI / 2} 0 0" />
5867
<geometry>
59-
<cylinder radius="${wheel_radius}" length="${wheel_width}"/>
68+
<cylinder radius="${wheel_radius}" length="${wheel_width}" />
6069
</geometry>
6170
</collision>
6271
</link>
@@ -74,7 +83,8 @@
7483
<inertial>
7584
<origin xyz="2.97539770599542E-14 -0.00750997550383714 6.53053999766229E-14" rpy="0 0 0" />
7685
<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" />
7888
</inertial>
7989
<visual>
8090
<origin xyz="0 0 0" rpy="0 0 0" />
@@ -88,7 +98,7 @@
8898
<collision>
8999
<origin xyz="0 -0.01 0" rpy="${PI / 2} 0 0" />
90100
<geometry>
91-
<cylinder radius="${wheel_radius}" length="${wheel_width}"/>
101+
<cylinder radius="${wheel_radius}" length="${wheel_width}" />
92102
</geometry>
93103
</collision>
94104
</link>
@@ -106,7 +116,8 @@
106116
<inertial>
107117
<origin xyz="-3.25850457727483E-14 0.00750997550383728 5.8935495372836E-14" rpy="0 0 0" />
108118
<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" />
110121
</inertial>
111122
<visual>
112123
<origin xyz="0 0 0" rpy="0 0 0" />
@@ -120,7 +131,7 @@
120131
<collision>
121132
<origin xyz="0 0.01 0" rpy="${PI / 2} 0 0" />
122133
<geometry>
123-
<cylinder radius="${wheel_radius}" length="${wheel_width}"/>
134+
<cylinder radius="${wheel_radius}" length="${wheel_width}" />
124135
</geometry>
125136
</collision>
126137
</link>
@@ -138,7 +149,8 @@
138149
<inertial>
139150
<origin xyz="3.05311331771918E-15 -0.00750997550383753 2.26554885962571E-15" rpy="0 0 0" />
140151
<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" />
142154
</inertial>
143155
<visual>
144156
<origin xyz="0 0 0" rpy="0 0 0" />
@@ -152,7 +164,7 @@
152164
<collision>
153165
<origin xyz="0 -0.01 0" rpy="${PI / 2} 0 0" />
154166
<geometry>
155-
<cylinder radius="${wheel_radius}" length="${wheel_width}"/>
167+
<cylinder radius="${wheel_radius}" length="${wheel_width}" />
156168
</geometry>
157169
</collision>
158170
</link>
@@ -167,7 +179,7 @@
167179
<xacro:wheel_transmissions prefix="back_left_motor" />
168180

169181
<!-- Import gazebo infos -->
170-
<xacro:if value="$(arg simulation)" >
182+
<xacro:if value="$(arg simulation)">
171183
<xacro:include filename="$(find curt_mini)/models/curt_mini/gazebo.xacro" />
172184
</xacro:if>
173185

0 commit comments

Comments
 (0)