forked from CoppeliaRobotics/simOMPL
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathcallbacks.xml
602 lines (601 loc) · 28.6 KB
/
callbacks.xml
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
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<?xml-stylesheet type="text/xsl" href="callbacks.xsl"?>
<plugin name="OMPL" short-name="OMPL" author="[email protected]">
<description>The list of API functions below allows you to define and solve a motion planning problem with OMPL.</description>
<command name="createStateSpace">
<description>Create a component of the state space for the motion planning problem. In case of a dubins state space, set additional parameters with <command-ref name="setDubinsParams" /></description>
<params>
<param name="name" type="string">
<description>a name for this state space</description>
</param>
<param name="type" type="int">
<description>type of this state space component (see <enum-ref name="StateSpaceType" />)</description>
</param>
<param name="objectHandle" type="int">
<description>the object handle (a joint object if type is simOMPL.StateSpaceType.joint_position, otherwise a shape)</description>
</param>
<param name="boundsLow" type="table" item-type="float">
<description>lower bounds (if type is pose, specify only the 3 position components)</description>
</param>
<param name="boundsHigh" type="table" item-type="float">
<description>upper bounds (if type is pose, specify only the 3 position components)</description>
</param>
<param name="useForProjection" type="int">
<description>if true, this object position or joint value will be used for computing a default projection</description>
</param>
<param name="weight" type="float" default="1.0">
<description>(optional) the weight of this state space component, used for computing distance between states. Default value is 1.0</description>
</param>
<param name="refObjectHandle" type="int" default="-1">
<description>(optional) an object handle relative to which reference frame position/orientations will be evaluated. Default value is -1, for the absolute reference frame</description>
</param>
</params>
<return>
<param name="stateSpaceHandle" type="int">
<description>a handle to the created state space component</description>
</param>
</return>
</command>
<command name="destroyStateSpace">
<description>Destroy the spacified state space component.<br /><br />Note: state space components created during simulation are automatically destroyed when simulation ends.</description>
<params>
<param name="stateSpaceHandle" type="int">
<description>handle to state space component</description>
</param>
</params>
<return>
</return>
</command>
<command name="setDubinsParams">
<description>Set extra state space parameters of a dubins state space.</description>
<params>
<param name="stateSpaceHandle" type="int">
<description>handle to state space component</description>
</param>
<param name="turningRadius" type="float">
<description>turning radius</description>
</param>
<param name="isSymmetric" type="bool">
<description>true if it is symmetric, otherwise false</description>
</param>
</params>
<return>
</return>
</command>
<command name="createTask">
<description>Create a task object, used to represent the motion planning task. A task object contains informations about: <ul>
<li>collision pairs (used by the default state validity checker)</li>
<li>state spaces</li>
<li>start state</li>
<li>goal state, or goal specification (e.g. pair of dummies, Lua callback, ...)</li>
<li>various Lua callbacks (projection evaluation, state validation, goal satisfaction)</li>
</ul></description>
<params>
<param name="name" type="string">
<description>a name for this task object</description>
</param>
</params>
<return>
<param name="taskHandle" type="int">
<description>a handle to the created task object</description>
</param>
</return>
</command>
<command name="destroyTask">
<description>Destroy the specified task object.<br /><br />Note: task objects created during simulation are automatically destroyed when simulation ends.</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
</params>
<return>
</return>
</command>
<command name="printTaskInfo">
<description>Print a summary of the specified task object. Useful for debugging and submitting bug reports.</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
</params>
<return>
</return>
</command>
<command name="setVerboseLevel">
<description>Set the verbosity level for messages printed to application console.</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
<param name="verboseLevel" type="int">
<description>level of verbosity (positive integer), 0 to suppress any message</description>
</param>
</params>
<return>
</return>
</command>
<command name="setStateValidityCheckingResolution">
<description>Set the resolution of state validity checking, expressed as fraction of state space's extent. Default resolution is 0.01 which is 1% fs the state space's extent.</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
<param name="resolution" type="float">
<description>resolution of state validity checking, expressed as fraction of state space's extent</description>
</param>
</params>
<return>
</return>
</command>
<command name="setStateSpace">
<description>Set the state space of this task object.</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
<param name="stateSpaceHandles" type="table" item-type="int">
<description>a table of handles to state space components, created with <command-ref name="createStateSpace" /></description>
</param>
</params>
<return>
</return>
</command>
<command name="setAlgorithm">
<description>Set the search algorithm for the specified task. Default algorithm used is KPIECE1.</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
<param name="algorithm" type="int">
<description>see <enum-ref name="Algorithm" /></description>
</param>
</params>
<return>
</return>
</command>
<command name="setCollisionPairs">
<description>Set the collision pairs for the specified task object.</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
<param name="collisionPairHandles" type="table" item-type="int">
<description>a table containing 2 entity handles for each collision pair. A collision pair is represented by a collider and a collidee, that will be tested against each other. The first pair could be used for robot self-collision testing, and a second pair could be used for robot-environment collision testing. The collider can be an object or a collection handle. The collidee can be an object or collection handle, or sim_handle_all, in which case the collider will be checked agains all other collidable objects in the scene.</description>
</param>
</params>
<return>
</return>
</command>
<command name="setStartState">
<description>Set the start state for the specified task object.</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
<param name="state" type="table" item-type="float">
<description>a table of numbers, whose size must be consistent with the robot's state space specified in this task object</description>
</param>
</params>
<return>
</return>
</command>
<command name="setGoalState">
<description>Set the goal state for the specified task object.</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
<param name="state" type="table" item-type="float">
<description>a table of numbers, whose size must be consistent with the robot's state space specified in this task object</description>
</param>
</params>
<return>
</return>
</command>
<command name="addGoalState">
<description>Add a goal state, without clearing previously set goal state(s), if any.</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
<param name="state" type="table" item-type="float">
<description>a table of numbers, whose size must be consistent with the robot's state space specified in this task object</description>
</param>
</params>
<return>
</return>
</command>
<command name="setGoal">
<description>Set the goal for the specificed task object by a dummy pair. One of the two dummies is part of the robot. The other dummy is fixed in the environment. When the task is solved, the position or pose of the two dummies will (approximatively) be the same. Dummy-dummy distances are relative to an optional reference dummy, and are evaluated using an optional metric</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
<param name="robotDummy" type="int">
<description>a dummy attached to the robot</description>
</param>
<param name="goalDummy" type="int">
<description>a dummy fixed in the environment, representing the goal pose/position</description>
</param>
<param name="tolerance" type="float" default="0.001f">
<description>an optional tolerated dummy-dummy distance. Defaults to 0.001</description>
</param>
<param name="metric" type="table" item-type="float" default="{1.0, 1.0, 1.0, 0.1}">
<description>an optional metric (x,y,z,angle) used to evaluate the dummy-dummy distance</description>
</param>
<param name="refDummy" type="int" default="-1">
<description>an optional reference dummy, relative to which the metric will be used</description>
</param>
</params>
<return>
</return>
</command>
<command name="setup">
<description>Setup the OMPL classes with the information contained in the task.</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
</params>
<return>
</return>
</command>
<command name="solve">
<description>Run the planning algorithm to search for a solution.</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
<param name="maxTime" type="float">
<description>maximum time used for the path searching procedure, in seconds.</description>
</param>
</params>
<return>
<param name="solved" type="bool">
<description>true if a solution is found.</description>
</param>
</return>
</command>
<command name="simplifyPath">
<description>Simplify the path found by planner.</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
<param name="maxSimplificationTime" type="float" default="-1.0">
<description>(optional) maximum time used for the path simplification procedure, in seconds. -1 for a default simplification procedure.</description>
</param>
</params>
<return>
</return>
</command>
<command name="interpolatePath">
<description>Interpolate the path found by planner to obtain a minimum number of states.</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
<param name="stateCnt" type="int" default="0">
<description>(optional) minimum number of states to be returned. 0 for a default behaviour.</description>
</param>
</params>
<return>
</return>
</command>
<command name="getPath">
<description>Use OMPL to find a solution for this motion planning task.</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
</params>
<return>
<param name="states" type="table" item-type="float">
<description>a table of states, representing the solution, from start to goal. States are specified linearly.</description>
</param>
</return>
</command>
<command name="getData">
<description>Get planner data for this motion planning task.</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" />.</description>
</param>
</params>
<return>
<param name="states" type="table" item-type="float">
<description>a table of states, representing the configurations in the constructed search graph. States are specified linearly followed by minimum distance to the closest X_obs.</description>
</param>
</return>
</command>
<command name="setParams">
<description>Set parameter for the planner.</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with simExtOMPL_createTask.</description>
</param>
<param name="number_of_params" type="int" item-type="string">
<description>the number of "key value" pairs in 'params'.</description>
</param>
<param name="params" type="table" item-type="string">
<description>a table of strings, representing a pair of "key value" parameter for each element in the table.</description>
</param>
</params>
<return>
<param name="result" type="int" default="0">
<description>0 for failure.</description>
</param>
</return>
</command>
<command name="compute">
<description>Use OMPL to find a solution for this motion planning task. It is equivalent to executing:<br/>
<br/>
simOMPL.setup(task)<br/>
if simOMPL.solve(task, maxTime) then<br/>
simOMPL.simplifyPath(task, maxSimplificationTime)<br/>
simOMPL.interpolatePath(task, stateCnt)<br/>
path = simOMPL.getPath(task)<br/>
end
</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
<param name="maxTime" type="float">
<description>maximum time used for the path searching procedure, in seconds.</description>
</param>
<param name="maxSimplificationTime" type="float" default="-1.0">
<description>(optional) maximum time used for the path simplification procedure, in seconds. -1 for a default simplification procedure.</description>
</param>
<param name="stateCnt" type="int" default="0">
<description>(optional) minimum number of states to be returned. 0 for a default behaviour.</description>
</param>
</params>
<return>
<param name="solved" type="bool">
<description>true if a solution has been found.</description>
</param>
<param name="states" type="table" item-type="float">
<description>a table of states, representing the solution, from start to goal. States are specified linearly.</description>
</param>
</return>
</command>
<command name="readState">
<description>Read a state vector from current simulator state.</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
</params>
<return>
<param name="state" type="table" item-type="float">
<description>state vector</description>
</param>
</return>
</command>
<command name="writeState">
<description>Write the specified state to simulator</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
<param name="state" type="table" item-type="float">
<description>state vector</description>
</param>
</params>
<return>
</return>
</command>
<command name="isStateValid">
<description>Check if the specified state is valid. If a state validation callback has been specified, that will be used to determine the validity of the state, otherwise the default state validation method will be used.</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
<param name="state" type="table" item-type="float">
<description>state vector</description>
</param>
</params>
<return>
<param name="valid" type="int">
<description>1 if valid, 0 otherwise</description>
</param>
</return>
</command>
<command name="setProjectionEvaluationCallback">
<description>Set a custom projection evaluation. The argument of the callback will be a state, and the return value must be a table of numbers, with a size equal to the projectionSize argument, i.e.<br /><br />table projection=evaluateProjection(table state)</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
<param name="callback" type="string">
<description>name of the Lua callback</description>
</param>
<param name="projectionSize" type="int">
<description>size of the projection (usually 2 or 3)</description>
</param>
</params>
<return>
</return>
</command>
<command name="setStateValidationCallback">
<description>Set a custom state validation. By default state validation is performed by collision checking, between robot's collision objects and environment's objects. By specifying a custom state validation, it is possible to perform any arbitrary check on a state to determine wether it is valid or not. Argument to the callback is the state to validate, and return value must be a boolean indicating the validity of the state, i.e.:<br /><br />boolean valid=stateValidator(table state)</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
<param name="callback" type="string">
<description>name of the Lua callback</description>
</param>
</params>
<return>
</return>
</command>
<command name="setGoalCallback">
<description>Set a custom goal callback for the specified task. The argument passed to the callback is the state to test for goal satisfaction. The return values must be a boolean indicating wether the goal is satisfied, and a float indicating the distance to the goal, i.e.:<br /><br />boolean satisfied, number distance=goalSatisfied(table state)<br /><br />If a distance to the goal is not known, a constant value can be used, but the performance of the algorithm will be worse.</description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
<param name="callback" type="string">
<description>name of the Lua callback</description>
</param>
</params>
<return>
</return>
</command>
<command name="setValidStateSamplerCallback">
<description>The valid state sampler callbacks must generate valid states. There are two callbacks to implement:<ul><li>the valid state sampling callback: table sampledState=sample()</li><li>the near valid state sampling callback: table sampledState=sampleNear(table state, number distance)</li></ul></description>
<params>
<param name="taskHandle" type="int">
<description>a handle to a task object created with <command-ref name="createTask" /></description>
</param>
<param name="callback" type="string">
<description>the name of the Lua callback for sampling a state</description>
</param>
<param name="callbackNear" type="string">
<description>the name of the Lua callback for sampling near a given state within the given distance</description>
</param>
</params>
<return>
</return>
</command>
<enum name="Algorithm" item-prefix="algorithm_" base="30001">
<item name="BiTRRT">
</item>
<item name="BITstar">
</item>
<item name="BKPIECE1">
</item>
<item name="CForest">
</item>
<item name="DancingPRMstar">
</item>
<item name="EST">
</item>
<item name="FMT">
</item>
<item name="KPIECE1">
</item>
<item name="LazyPRM">
</item>
<item name="LazyPRMstar">
</item>
<item name="LazyRRT">
</item>
<item name="LBKPIECE1">
</item>
<item name="LBTRRT">
</item>
<item name="PDST">
</item>
<item name="PRM">
</item>
<item name="PRMstar">
</item>
<item name="pRRT">
</item>
<item name="pSBL">
</item>
<item name="RRT">
</item>
<item name="RRTConnect">
</item>
<item name="RRTstar">
</item>
<item name="SBL">
</item>
<item name="SPARS">
</item>
<item name="SPARStwo">
</item>
<item name="STRIDE">
</item>
<item name="TRRT">
</item>
<item name="VolumetricTree">
</item>
</enum>
<enum name="StateSpaceType" item-prefix="statespacetype_" base="50001">
<item name="position2d">
</item>
<item name="pose2d">
</item>
<item name="position3d">
</item>
<item name="pose3d">
</item>
<item name="joint_position">
</item>
<item name="dubins">
</item>
</enum>
<script-function name="goalCallback">
<description>Callback for checking if the goal is satisfied.</description>
<params>
<param name="state" type="table" item-type="float">
<description>the state to test for goal satisfaction</description>
</param>
</params>
<return>
<param name="satisfied" type="bool">
<description>true if satisfied, false otherwise</description>
</param>
<param name="distance" type="float">
<description>distance to goal, if it is known. A constant value can be returned otherwise, but the performance of the algorithm will be worse.</description>
</param>
</return>
</script-function>
<script-function name="projectionEvaluationCallback">
<description>Callback for computing a (euclidean) projection of states.</description>
<params>
<param name="state" type="table" item-type="float">
<description>the state to compute the projection for</description>
</param>
</params>
<return>
<param name="projection" type="table" item-type="float">
<description>projected state, usualy of size 2 or 3, representing a point in plane or space.</description>
</param>
</return>
</script-function>
<script-function name="stateValidationCallback">
<description>Callback for checking the validity of states.</description>
<params>
<param name="state" type="table" item-type="float">
<description>the state to compute the projection for</description>
</param>
</params>
<return>
<param name="valid" type="bool">
<description>true if valid, false otherwise</description>
</param>
</return>
</script-function>
<script-function name="validStateSamplerCallback">
<description>Callback for sampling valid states from the state space.</description>
<params>
</params>
<return>
<param name="sampledState" type="table" item-type="float">
<description>a valid state</description>
</param>
</return>
</script-function>
<script-function name="validStateSamplerCallbackNear">
<description>Callback for sampling valid states in the proximity of a given state, within a certain distance.</description>
<params>
<param name="state" type="table" item-type="float">
<description>the center state</description>
</param>
<param name="distance" type="float">
<description>distance bound</description>
</param>
</params>
<return>
<param name="sampledState" type="table" item-type="float">
<description>a valid state</description>
</param>
</return>
</script-function>
</plugin>