-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathcustom.wbt
274 lines (272 loc) · 6.21 KB
/
custom.wbt
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
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
#VRML_SIM R2023b utf8
EXTERNPROTO "../protos/TexturedBackground.proto"
EXTERNPROTO "../protos/TexturedBackgroundLight.proto"
EXTERNPROTO "../protos/RectangleArena.proto"
EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023b/projects/objects/rocks/protos/Rock.proto"
EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023b/projects/objects/factory/containers/protos/WoodenBox.proto"
WorldInfo {
}
Viewpoint {
orientation 0.18478028940301824 0.013995871723725156 -0.9826801922410108 3.9519606702489782
position 1.3563665091102002 -1.501207425260114 0.9017480762905308
}
TexturedBackground {
}
TexturedBackgroundLight {
}
RectangleArena {
floorSize 2 2
}
Robot {
translation -0.16383931543279195 -0.0006081326586651825 0.03972057905040909
rotation 0.00023326557207525826 0.05854029199138639 -0.9982850193210034 0.0002700720940811805
children [
HingeJoint {
jointParameters HingeJointParameters {
position -3.4237080817774506
axis 0 1 0
anchor 0.05 0.06 0
}
device [
DEF wheel1 RotationalMotor {
name "wheel1"
}
]
endPoint Solid {
translation 0.05 0.06 0
rotation -0.09990751758662259 -0.7035676412145337 0.7035702254682866 3.340746096725138
children [
DEF wheel Shape {
appearance PBRAppearance {
baseColor 0.870588 0.866667 0.854902
metalness 0
}
geometry Cylinder {
height 0.02
radius 0.04
}
}
]
boundingObject USE wheel
physics DEF wheel_physics Physics {
}
}
}
HingeJoint {
jointParameters HingeJointParameters {
position -4.095650518772092
axis 0 1 0
anchor 0.05 -0.06 0
}
device [
DEF wheel2 RotationalMotor {
name "wheel2"
}
]
endPoint Solid {
translation 0.05 -0.06 0
rotation -0.34325705371324244 -0.6641428139726565 0.664145253483442 3.802900710995585
children [
USE wheel
]
name "wheel2"
boundingObject USE wheel
physics USE wheel_physics
}
}
HingeJoint {
jointParameters HingeJointParameters {
position -4.095650539074345
axis 0 1 0
anchor -0.05 0.06 0
}
device [
DEF wheel3 RotationalMotor {
name "wheel3"
}
]
endPoint Solid {
translation -0.05 0.06 0
rotation -0.3432570612494133 -0.6641428120251653 0.6641452515359291 3.802900724479189
children [
USE wheel
]
name "wheel3"
boundingObject USE wheel
physics USE wheel_physics
}
}
HingeJoint {
jointParameters HingeJointParameters {
position -4.095650569420188
axis 0 1 0
anchor -0.05 -0.06 0
}
device [
DEF wheel4 RotationalMotor {
name "wheel4"
}
]
endPoint Solid {
translation -0.05 -0.06 0
rotation -0.3432570725137577 -0.6641428091142306 0.6641452486249854 3.8029007446331615
children [
USE wheel
]
name "wheel4"
boundingObject USE wheel
physics USE wheel_physics
}
}
DistanceSensor {
translation 0.1 0.02 0
rotation 0 0 1 0.3
children [
DEF sensor Shape {
geometry Box {
size 0.01 0.01 0.01
}
}
]
name "ds_left"
boundingObject USE sensor
physics Physics {
}
}
DEF ds_right DistanceSensor {
translation 0.1 -0.02 0
rotation 0 0 1 -0.3
children [
DEF sensor Shape {
geometry Box {
size 0.01 0.01 0.01
}
}
]
name "ds_right"
boundingObject USE sensor
physics Physics {
}
}
DEF body Shape {
appearance PBRAppearance {
}
geometry Box {
size 0.2 0.1 0.05
}
}
GPS {
translation 0.01 0 0.03
children [
Shape {
geometry Cylinder {
height 0.02
radius 0.01
}
}
]
name "global"
}
InertialUnit {
translation 0.07 0 0.03
children [
Shape {
geometry Box {
size 0.02 0.02 0.02
}
}
]
name "imu"
}
DEF L1 Solid {
translation -0.05 0 0.12
children [
Shape {
geometry Box {
size 0.02 0.02 0.25
}
}
]
name "solid(1)"
}
SliderJoint {
jointParameters JointParameters {
}
device [
LinearMotor {
name "linear"
maxPosition 0.2
}
]
endPoint Solid {
translation -0.05 -0.085 0.06
children [
DEF L2 Shape {
geometry Box {
size 0.02 0.15 0.02
}
}
HingeJoint {
jointParameters HingeJointParameters {
axis 0 0 1
anchor 0 -0.075 1
}
device [
RotationalMotor {
name "RM"
}
]
endPoint Solid {
translation 0 -0.08 0
rotation 1 0 0 1.5708
children [
Shape {
appearance PBRAppearance {
}
geometry Cylinder {
height 0.02
radius 0.01
}
}
Camera {
translation 0 0 0.01
rotation 0.577349935856137 0.5773509358560258 0.577349935856137 -2.094395307179586
name "CAM"
}
]
}
}
]
name "L2"
}
}
]
boundingObject USE body
physics Physics {
}
controller "gpbot"
}
Rock {
translation 0.51 -0.39 0.04
}
Rock {
translation 0.4 0.13 0.04
name "rock(1)"
}
Rock {
translation -0.64 0.18 0.12
name "rock(2)"
}
Rock {
translation -0.27 -0.69 0.09
name "rock(3)"
}
WoodenBox {
translation 0 0.55 0.07
size 0.1 0.1 0.1
}
WoodenBox {
translation 0.1 -0.56 0.07
name "wooden box(1)"
size 0.1 0.1 0.1
}