-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathiRobot.xacro
164 lines (148 loc) · 5.59 KB
/
iRobot.xacro
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
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="iRobot">
<!-- MODELS -->
<xacro:include filename="$(find irobotcreate2)/model/materials.urdf"/>
<xacro:include filename="$(find irobotcreate2)/model/axis.urdf.xacro"/>
<xacro:include filename="$(find irobotcreate2)/model/wheel.urdf.xacro"/>
<xacro:include filename="$(find irobotcreate2)/model/shelf.urdf.xacro"/>
<xacro:include filename="$(find irobotcreate2)/gazebo/iRobot.gazebo.xacro"/>
<xacro:include filename="$(find irobotcreate2)/model/hokuyo.urdf.xacro"/>
<xacro:include filename="$(find irobotcreate2)/model/imu.urdf.xacro"/>
<xacro:include filename="$(find irobotcreate2)/model/camera.urdf.xacro"/>
<xacro:property name="pi" value="3.1415926535897931"/>
<xacro:property name="wheel_mass" value="0.5"/>
<xacro:property name="sphere_mass" value="0.3"/>
<link name="base_link">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="0"/>
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
</inertial>
</link>
<joint name="base_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="base_link"/>
<child link="chassis"/>
</joint>
<link name="chassis">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="10"/>
<inertia ixx="${1/12*10*3*0.17**2+1/12*5*3*0.08**2}" ixy="0.0" ixz="0.0" iyy="${1/12*10*3*0.17**2+1/12*5*3*0.08**2}" iyz="0.0" izz="${1/2*10*0.17**2}"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="0.08" radius="0.17"/>
</geometry>
<material name="iRobot/LightGrey"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="0.08" radius="0.17"/>
</geometry>
</collision>
</link>
<xacro:model_axis name="left_axis"
parent="chassis">
<origin xyz="0 0.14 -0.02" rpy="0 0 0"/>
</xacro:model_axis>
<xacro:model_wheel name="left_wheel"
parent="left_axis"
radius="0.03"
width="0.02"
mass="${wheel_mass}">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:model_wheel>
<xacro:model_axis name="right_axis"
parent="chassis">
<origin xyz="0 -0.14 -0.02" rpy="0 0 0"/>
</xacro:model_axis>
<xacro:model_wheel name="right_wheel"
parent="right_axis"
radius="0.03"
width="0.02"
mass="${wheel_mass}">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:model_wheel>
<joint name="sphere_joint1" type="revolute">
<origin xyz="0.14 0 -0.04" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="0" upper="0" effort="100" velocity="100"/>
<parent link="chassis"/>
<child link="sphere1"/>
</joint>
<link name="sphere1">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="${sphere_mass}"/>
<inertia ixx="${2/5*sphere_mass*0.01**2}" ixy="0.0" ixz="0.0" iyy="${2/5*sphere_mass*0.01**2}" iyz="0.0" izz="${2/5*sphere_mass*0.01**2}"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
<material name="iRobot/Black"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
</link>
<joint name="sphere_joint2" type="revolute">
<origin xyz="-0.14 0 -0.04" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="0" upper="0" effort="100" velocity="100"/>
<parent link="chassis"/>
<child link="sphere2"/>
</joint>
<link name="sphere2">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="${sphere_mass}"/>
<inertia ixx="${2/5*sphere_mass*0.01**2}" ixy="0.0" ixz="0.0" iyy="${2/5*sphere_mass*0.01**2}" iyz="0.0" izz="${2/5*sphere_mass*0.01**2}"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
<material name="iRobot/Black"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
</collision>
</link>
<!-- Laser link and plugin -->
<xacro:hokuyo_laser xyz="0 0 ${0.04 + 0.02}"
rpy="0 0 0"
parent="base_link">
</xacro:hokuyo_laser>
<!--Imu link and plugin-->
<xacro:imu_sensor xyz="-0.1 0 ${0.04 + 0.01}"
rpy="0 0 0"
parent="base_link">
</xacro:imu_sensor>
<!--Camera link and plugin-->
<xacro:camera_sensor xyz="0 0 ${0.04 + 0.02 + 0.04}"
rpy="0 0 0"
parent="base_link">
</xacro:camera_sensor>
<!-- <xacro:model_shelf name="first_shelf"
parent="chassis"
height="0.15">
</xacro:model_shelf>-->
<!-- <xacro:model_shelf name="second_shelf"
parent="first_shelf"
height="0.25">
</xacro:model_shelf>
-->
<xacro:iRobot_gazebo />
</robot>