-
Notifications
You must be signed in to change notification settings - Fork 192
/
Copy pathbus.urdf
135 lines (132 loc) · 4.07 KB
/
bus.urdf
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
<?xml version="1.0"?>
<!-- note: if inertia values are set to 0, bullet will re-compute our inertias for us-->
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="vehicle">
<link name="base_link">
<inertial>
<mass value="1"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
</link>
<link name="chassis">
<collision name="chassis">
<origin xyz="0.0 0.0 1.4" rpy="0 0 0"/>
<geometry>
<box size="2.2026 7 2.4"/>
</geometry>
</collision>
<inertial>
<mass value="6000.0"/>
<origin xyz="0 -0.1 0.20" rpy="0 0 1.5708"/>
<inertia ixx="27380" ixy="0.0" ixz="0.0" iyy="5300" iyz="0.0" izz="26920"/>
</inertial>
</link>
<link name="fl_axle">
<inertial>
<mass value="5"/>
<origin xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="6" izz="0"/>
</inertial>
</link>
<link name="fr_axle">
<inertial>
<mass value="5"/>
<origin xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="6" izz="0"/>
</inertial>
</link>
<link name="front_left_wheel">
<inertial>
<mass value="25"/>
<origin xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="4"/>
</inertial>
<collision name="front_left_wheel_collision">
<origin rpy="0 1.5707963267948966 0"/>
<geometry>
<cylinder length="0.35" radius="0.52"/>
</geometry>
</collision>
</link>
<link name="front_right_wheel">
<inertial>
<mass value="25"/>
<origin xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="4"/>
</inertial>
<collision name="front_right_wheel_collision">
<origin rpy="0 1.5707963267948966 0"/>
<geometry>
<cylinder length="0.35" radius="0.52"/>
</geometry>
</collision>
</link>
<link name="rear_left_wheel">
<inertial>
<mass value="25"/>
<origin xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="4"/>
</inertial>
<collision name="rear_left_wheel_collision">
<origin rpy="0 1.5707963267948966 0"/>
<geometry>
<cylinder length="0.35" radius="0.52"/>
</geometry>
</collision>
</link>
<link name="rear_right_wheel">
<inertial>
<mass value="25"/>
<origin xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="4"/>
</inertial>
<collision name="rear_right_wheel_collision">
<origin rpy="0 1.5707963267948966 0"/>
<geometry>
<cylinder length="0.35" radius="0.52"/>
</geometry>
</collision>
</link>
<joint name="base_link_connection" type="fixed">
<parent link="base_link"/>
<child link="chassis"/>
<origin xyz="0 0 0" rpy="0 0 3.141592653589793"/>
</joint>
<joint name="front_left_steer_joint" type="revolute">
<parent link="chassis"/>
<child link="fl_axle"/>
<origin xyz="0.5 -2.5 0.5" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="-0.8727" upper="0.8727" effort="10000000" velocity="1000000"/>
</joint>
<joint name="front_right_steer_joint" type="revolute">
<parent link="chassis"/>
<child link="fr_axle"/>
<origin xyz="-0.5 -2.5 0.5" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="-0.8727" upper="0.8727" effort="10000000" velocity="1000000"/>
</joint>
<joint name="front_left_wheel_joint" type="continuous">
<parent link="fl_axle"/>
<child link="front_left_wheel"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="front_right_wheel_joint" type="continuous">
<parent link="fr_axle"/>
<child link="front_right_wheel"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="rear_left_wheel_joint" type="continuous">
<parent link="chassis"/>
<child link="rear_left_wheel"/>
<origin xyz="0.5 2.5 0.5" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="rear_right_wheel_joint" type="continuous">
<parent link="chassis"/>
<child link="rear_right_wheel"/>
<origin xyz="-0.5 2.5 0.5" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
</robot>