-
Notifications
You must be signed in to change notification settings - Fork 110
/
motionPlanner.go
458 lines (404 loc) · 14.7 KB
/
motionPlanner.go
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
//go:build !no_cgo
// Package motionplan is a motion planning library.
package motionplan
import (
"context"
"fmt"
"math/rand"
"sort"
"sync"
"time"
"github.com/pkg/errors"
pb "go.viam.com/api/service/motion/v1"
"go.viam.com/utils"
"go.viam.com/rdk/logging"
"go.viam.com/rdk/motionplan/ik"
frame "go.viam.com/rdk/referenceframe"
"go.viam.com/rdk/spatialmath"
)
const defaultRandomSeed = 0
// motionPlanner provides an interface to path planning methods, providing ways to request a path to be planned, and
// management of the constraints used to plan paths.
type motionPlanner interface {
// Plan will take a context, a goal position, and an input start state and return a series of state waypoints which
// should be visited in order to arrive at the goal while satisfying all constraints
plan(context.Context, spatialmath.Pose, []frame.Input) ([]node, error)
// Everything below this point should be covered by anything that wraps the generic `planner`
smoothPath(context.Context, []node) []node
checkPath([]frame.Input, []frame.Input) bool
checkInputs([]frame.Input) bool
getSolutions(context.Context, []frame.Input) ([]node, error)
opt() *plannerOptions
sample(node, int) (node, error)
}
type plannerConstructor func(frame.Frame, *rand.Rand, logging.Logger, *plannerOptions) (motionPlanner, error)
// PlanRequest is a struct to store all the data necessary to make a call to PlanMotion.
type PlanRequest struct {
Logger logging.Logger
Goal *frame.PoseInFrame
Frame frame.Frame
FrameSystem frame.FrameSystem
StartPose spatialmath.Pose
StartConfiguration map[string][]frame.Input
WorldState *frame.WorldState
BoundingRegions []spatialmath.Geometry
ConstraintSpecs *pb.Constraints
Options map[string]interface{}
}
// validatePlanRequest ensures PlanRequests are not malformed.
func (req *PlanRequest) validatePlanRequest() error {
if req == nil {
return errors.New("PlanRequest cannot be nil")
}
if req.Logger == nil {
return errors.New("PlanRequest cannot have nil logger")
}
if req.Frame == nil {
return errors.New("PlanRequest cannot have nil frame")
}
if req.FrameSystem == nil {
return errors.New("PlanRequest cannot have nil framesystem")
} else if req.FrameSystem.Frame(req.Frame.Name()) == nil {
return frame.NewFrameMissingError(req.Frame.Name())
}
if req.Goal == nil {
return errors.New("PlanRequest cannot have nil goal")
}
goalParentFrame := req.Goal.Parent()
if req.FrameSystem.Frame(goalParentFrame) == nil {
return frame.NewParentFrameMissingError(req.Goal.Name(), goalParentFrame)
}
if len(req.BoundingRegions) > 0 {
buffer, ok := req.Options["collision_buffer_mm"].(float64)
if !ok {
buffer = defaultCollisionBufferMM
}
// check that the request frame's geometries are within or in collision with the bounding regions
robotGifs, err := req.Frame.Geometries(make([]frame.Input, len(req.Frame.DoF())))
if err != nil {
return err
}
var robotGeoms []spatialmath.Geometry
for _, geom := range robotGifs.Geometries() {
robotGeoms = append(robotGeoms, geom.Transform(req.StartPose))
}
robotGeomBoundingRegionCheck := NewBoundingRegionConstraint(robotGeoms, req.BoundingRegions, buffer)
if !robotGeomBoundingRegionCheck(&ik.State{}) {
return fmt.Errorf("frame named %s is not within the provided bounding regions", req.Frame.Name())
}
// check that the destination is within or in collision with the bounding regions
destinationAsGeom := []spatialmath.Geometry{spatialmath.NewPoint(req.Goal.Pose().Point(), "")}
destinationBoundingRegionCheck := NewBoundingRegionConstraint(destinationAsGeom, req.BoundingRegions, buffer)
if !destinationBoundingRegionCheck(&ik.State{}) {
return errors.New("destination was not within the provided bounding regions")
}
}
frameDOF := len(req.Frame.DoF())
seedMap, ok := req.StartConfiguration[req.Frame.Name()]
if frameDOF > 0 {
if !ok {
return errors.Errorf("%s does not have a start configuration", req.Frame.Name())
}
if frameDOF != len(seedMap) {
return frame.NewIncorrectInputLengthError(len(seedMap), len(req.Frame.DoF()))
}
} else if ok && frameDOF != len(seedMap) {
return frame.NewIncorrectInputLengthError(len(seedMap), len(req.Frame.DoF()))
}
return nil
}
// PlanMotion plans a motion from a provided plan request.
func PlanMotion(ctx context.Context, request *PlanRequest) (Plan, error) {
// Calls Replan but without a seed plan
return Replan(ctx, request, nil, 0)
}
// PlanFrameMotion plans a motion to destination for a given frame with no frame system. It will create a new FS just for the plan.
// WorldState is not supported in the absence of a real frame system.
func PlanFrameMotion(ctx context.Context,
logger logging.Logger,
dst spatialmath.Pose,
f frame.Frame,
seed []frame.Input,
constraintSpec *pb.Constraints,
planningOpts map[string]interface{},
) ([][]frame.Input, error) {
// ephemerally create a framesystem containing just the frame for the solve
fs := frame.NewEmptyFrameSystem("")
if err := fs.AddFrame(f, fs.World()); err != nil {
return nil, err
}
plan, err := PlanMotion(ctx, &PlanRequest{
Logger: logger,
Goal: frame.NewPoseInFrame(frame.World, dst),
Frame: f,
StartConfiguration: map[string][]frame.Input{f.Name(): seed},
FrameSystem: fs,
ConstraintSpecs: constraintSpec,
Options: planningOpts,
})
if err != nil {
return nil, err
}
return plan.Trajectory().GetFrameInputs(f.Name())
}
// Replan plans a motion from a provided plan request, and then will return that plan only if its cost is better than the cost of the
// passed-in plan multiplied by `replanCostFactor`.
func Replan(ctx context.Context, request *PlanRequest, currentPlan Plan, replanCostFactor float64) (Plan, error) {
// make sure request is well formed and not missing vital information
if err := request.validatePlanRequest(); err != nil {
return nil, err
}
// Create a frame to solve for, and an IK solver with that frame.
sf, err := newSolverFrame(request.FrameSystem, request.Frame.Name(), request.Goal.Parent(), request.StartConfiguration)
if err != nil {
return nil, err
}
if len(sf.DoF()) == 0 {
return nil, errors.New("solver frame has no degrees of freedom, cannot perform inverse kinematics")
}
request.Logger.CDebugf(ctx, "constraint specs for this step: %v", request.ConstraintSpecs)
request.Logger.CDebugf(ctx, "motion config for this step: %v", request.Options)
rseed := defaultRandomSeed
if seed, ok := request.Options["rseed"].(int); ok {
rseed = seed
}
sfPlanner, err := newPlanManager(sf, request.Logger, rseed)
if err != nil {
return nil, err
}
newPlan, err := sfPlanner.PlanSingleWaypoint(ctx, request, currentPlan)
if err != nil {
return nil, err
}
if replanCostFactor > 0 && currentPlan != nil {
initialPlanCost := currentPlan.Trajectory().EvaluateCost(sfPlanner.opt().ScoreFunc)
finalPlanCost := newPlan.Trajectory().EvaluateCost(sfPlanner.opt().ScoreFunc)
request.Logger.CDebugf(ctx,
"initialPlanCost %f adjusted with cost factor to %f, replan cost %f",
initialPlanCost, initialPlanCost*replanCostFactor, finalPlanCost,
)
if finalPlanCost > initialPlanCost*replanCostFactor {
return nil, errHighReplanCost
}
}
return newPlan, nil
}
type planner struct {
solver ik.InverseKinematics
frame frame.Frame
logger logging.Logger
randseed *rand.Rand
start time.Time
planOpts *plannerOptions
}
func newPlanner(frame frame.Frame, seed *rand.Rand, logger logging.Logger, opt *plannerOptions) (*planner, error) {
solver, err := ik.CreateCombinedIKSolver(frame, logger, opt.NumThreads, opt.GoalThreshold)
if err != nil {
return nil, err
}
mp := &planner{
solver: solver,
frame: frame,
logger: logger,
randseed: seed,
planOpts: opt,
}
return mp, nil
}
func (mp *planner) checkInputs(inputs []frame.Input) bool {
ok, _ := mp.planOpts.CheckStateConstraints(&ik.State{
Configuration: inputs,
Frame: mp.frame,
})
return ok
}
func (mp *planner) checkPath(seedInputs, target []frame.Input) bool {
ok, _ := mp.planOpts.CheckSegmentAndStateValidity(
&ik.Segment{
StartConfiguration: seedInputs,
EndConfiguration: target,
Frame: mp.frame,
},
mp.planOpts.Resolution,
)
return ok
}
func (mp *planner) sample(rSeed node, sampleNum int) (node, error) {
// If we have done more than 50 iterations, start seeding off completely random positions 2 at a time
// The 2 at a time is to ensure random seeds are added onto both the seed and goal maps.
if sampleNum >= mp.planOpts.IterBeforeRand && sampleNum%4 >= 2 {
return newConfigurationNode(frame.RandomFrameInputs(mp.frame, mp.randseed)), nil
}
// Seeding nearby to valid points results in much faster convergence in less constrained space
q, err := frame.RestrictedRandomFrameInputs(mp.frame, mp.randseed, 0.1, rSeed.Q())
if err != nil {
return nil, err
}
return newConfigurationNode(q), nil
}
func (mp *planner) opt() *plannerOptions {
return mp.planOpts
}
// smoothPath will try to naively smooth the path by picking points partway between waypoints and seeing if it can interpolate
// directly between them. This will significantly improve paths from RRT*, as it will shortcut the randomly-selected configurations.
// This will only ever improve paths (or leave them untouched), and runs very quickly.
func (mp *planner) smoothPath(ctx context.Context, path []node) []node {
mp.logger.CDebugf(ctx, "running simple smoother on path of len %d", len(path))
if mp.planOpts == nil {
mp.logger.CDebug(ctx, "nil opts, cannot shortcut")
return path
}
if len(path) <= 2 {
mp.logger.CDebug(ctx, "path too short, cannot shortcut")
return path
}
// Randomly pick which quarter of motion to check from; this increases flexibility of smoothing.
waypoints := []float64{0.25, 0.5, 0.75}
for i := 0; i < mp.planOpts.SmoothIter; i++ {
select {
case <-ctx.Done():
return path
default:
}
// get start node of first edge. Cannot be either the last or second-to-last node.
// Intn will return an int in the half-open interval half-open interval [0,n)
firstEdge := mp.randseed.Intn(len(path) - 2)
secondEdge := firstEdge + 1 + mp.randseed.Intn((len(path)-2)-firstEdge)
wayPoint1, err := mp.frame.Interpolate(path[firstEdge].Q(), path[firstEdge+1].Q(), waypoints[mp.randseed.Intn(3)])
if err != nil {
return path
}
wayPoint2, err := mp.frame.Interpolate(path[secondEdge].Q(), path[secondEdge+1].Q(), waypoints[mp.randseed.Intn(3)])
if err != nil {
return path
}
if mp.checkPath(wayPoint1, wayPoint2) {
newpath := []node{}
newpath = append(newpath, path[:firstEdge+1]...)
newpath = append(newpath, newConfigurationNode(wayPoint1), newConfigurationNode(wayPoint2))
// have to split this up due to go compiler quirk where elipses operator can't be mixed with other vars in append
newpath = append(newpath, path[secondEdge+1:]...)
path = newpath
}
}
return path
}
// getSolutions will initiate an IK solver for the given position and seed, collect solutions, and score them by constraints.
// If maxSolutions is positive, once that many solutions have been collected, the solver will terminate and return that many solutions.
// If minScore is positive, if a solution scoring below that amount is found, the solver will terminate and return that one solution.
func (mp *planner) getSolutions(ctx context.Context, seed []frame.Input) ([]node, error) {
// Linter doesn't properly handle loop labels
nSolutions := mp.planOpts.MaxSolutions
if nSolutions == 0 {
nSolutions = defaultSolutionsToSeed
}
seedPos, err := mp.frame.Transform(seed)
if err != nil {
return nil, err
}
if mp.planOpts.goalMetric == nil {
return nil, errors.New("metric is nil")
}
ctxWithCancel, cancel := context.WithCancel(ctx)
defer cancel()
solutionGen := make(chan *ik.Solution, mp.planOpts.NumThreads*2)
ikErr := make(chan error, 1)
var activeSolvers sync.WaitGroup
defer activeSolvers.Wait()
activeSolvers.Add(1)
// Spawn the IK solver to generate solutions until done
utils.PanicCapturingGo(func() {
defer close(ikErr)
defer activeSolvers.Done()
ikErr <- mp.solver.Solve(ctxWithCancel, solutionGen, seed, mp.planOpts.goalMetric, mp.randseed.Int())
})
solutions := map[float64][]frame.Input{}
// A map keeping track of which constraints fail
failures := map[string]int{}
constraintFailCnt := 0
// Solve the IK solver. Loop labels are required because `break` etc in a `select` will break only the `select`.
IK:
for {
select {
case <-ctx.Done():
return nil, ctx.Err()
default:
}
select {
case stepSolution := <-solutionGen:
step := stepSolution.Configuration
// Ensure the end state is a valid one
statePass, failName := mp.planOpts.CheckStateConstraints(&ik.State{
Configuration: step,
Frame: mp.frame,
})
if statePass {
stepArc := &ik.Segment{
StartConfiguration: seed,
StartPosition: seedPos,
EndConfiguration: step,
Frame: mp.frame,
}
arcPass, failName := mp.planOpts.CheckSegmentConstraints(stepArc)
if arcPass {
score := mp.planOpts.goalArcScore(stepArc)
if score < mp.planOpts.MinScore && mp.planOpts.MinScore > 0 {
solutions = map[float64][]frame.Input{}
solutions[score] = step
// good solution, stopping early
break IK
}
solutions[score] = step
if len(solutions) >= nSolutions {
// sufficient solutions found, stopping early
break IK
}
} else {
constraintFailCnt++
failures[failName]++
}
} else {
constraintFailCnt++
failures[failName]++
}
// Skip the return check below until we have nothing left to read from solutionGen
continue IK
default:
}
select {
case <-ikErr:
// If we have a return from the IK solver, there are no more solutions, so we finish processing above
// until we've drained the channel, handled by the `continue` above
break IK
default:
}
}
// Cancel any ongoing processing within the IK solvers if we're done receiving solutions
cancel()
for done := false; !done; {
select {
case <-solutionGen:
default:
done = true
}
}
if len(solutions) == 0 {
// We have failed to produce a usable IK solution. Let the user know if zero IK solutions were produced, or if non-zero solutions
// were produced, which constraints were failed
if constraintFailCnt == 0 {
return nil, errIKSolve
}
return nil, genIKConstraintErr(failures, constraintFailCnt)
}
keys := make([]float64, 0, len(solutions))
for k := range solutions {
keys = append(keys, k)
}
// TODO: switch this to slices.Sort when golang 1.21 is supported by RDK
sort.Float64s(keys)
orderedSolutions := make([]node, 0)
for _, key := range keys {
orderedSolutions = append(orderedSolutions, &basicNode{q: solutions[key], cost: key})
}
return orderedSolutions, nil
}