-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathrobot1.xacro
141 lines (126 loc) · 4.36 KB
/
robot1.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
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
name="robot1_xacro">
<xacro:property name="length_wheel" value="0.05" />
<xacro:property name="radius_wheel" value="0.05" />
<xacro:macro name="default_inertial" params="mass">
<inertial>
<mass value="${mass}" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0" />
</inertial>
</xacro:macro>
<link name="base_link">
<visual>
<geometry>
<box size="0.2 .3 .1"/>
</geometry>
<origin rpy="0 0 1.54" xyz="0 0 0.05"/>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<geometry>
<box size="0.2 .3 0.1"/>
</geometry>
</collision>
<xacro:default_inertial mass="10"/>
</link>
<link name="wheel_1">
<visual>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
<!-- <origin rpy="0 1.5 0" xyz="0.1 0.1 0"/> -->
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
</collision>
<xacro:default_inertial mass="1"/>
</link>
<link name="wheel_2">
<visual>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
<!-- <origin rpy="0 1.5 0" xyz="-0.1 0.1 0"/> -->
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="black"/>
</visual>
<collision>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
</collision>
<xacro:default_inertial mass="1"/>
</link>
<link name="wheel_3">
<visual>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
<!-- <origin rpy="0 1.5 0" xyz="0.1 -0.1 0"/> -->
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="black"/>
</visual>
<collision>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
</collision>
<xacro:default_inertial mass="1"/>
</link>
<link name="wheel_4">
<visual>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
<!-- <origin rpy="0 1.5 0" xyz="-0.1 -0.1 0"/> -->
<origin rpy="0 0 0" xyz="0 0 0" />
<material name="black"/>
</visual>
<collision>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
</collision>
<xacro:default_inertial mass="1"/>
</link>
<joint name="base_to_wheel1" type="continuous">
<parent link="base_link"/>
<child link="wheel_1"/>
<origin rpy="1.5707 0 0" xyz="0.1 0.15 0"/>
<axis xyz="0 0 1" />
</joint>
<joint name="base_to_wheel2" type="continuous">
<axis xyz="0 0 1" />
<anchor xyz="0 0 0" />
<limit effort="100" velocity="100" />
<parent link="base_link"/>
<child link="wheel_2"/>
<origin rpy="1.5707 0 0" xyz="-0.1 0.15 0"/>
</joint>
<joint name="base_to_wheel3" type="continuous">
<parent link="base_link"/>
<axis xyz="0 0 1" />
<child link="wheel_3"/>
<origin rpy="1.5707 0 0" xyz="0.1 -0.15 0"/>
</joint>
<joint name="base_to_wheel4" type="continuous">
<parent link="base_link"/>
<axis xyz="0 0 1" />
<child link="wheel_4"/>
<origin rpy="1.5707 0 0" xyz="-0.1 -0.15 0"/>
</joint>
</robot>