-
Notifications
You must be signed in to change notification settings - Fork 110
/
wheeledodometry.go
507 lines (428 loc) · 15.3 KB
/
wheeledodometry.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
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
// Package wheeledodometry implements an odometery estimate from an encoder wheeled base.
package wheeledodometry
import (
"context"
"errors"
"fmt"
"math"
"sync"
"time"
"github.com/golang/geo/r3"
geo "github.com/kellydunn/golang-geo"
"go.viam.com/utils"
"go.viam.com/rdk/components/base"
"go.viam.com/rdk/components/motor"
"go.viam.com/rdk/components/movementsensor"
"go.viam.com/rdk/logging"
"go.viam.com/rdk/resource"
"go.viam.com/rdk/spatialmath"
rdkutils "go.viam.com/rdk/utils"
)
var model = resource.DefaultModelFamily.WithModel("wheeled-odometry")
const (
defaultTimeIntervalMSecs = 500
oneTurn = 2 * math.Pi
mToKm = 1e-3
returnRelative = "return_relative_pos_m"
setLong = "setLong"
setLat = "setLat"
useCompass = "use_compass"
shiftPos = "shift_position"
resetShift = "reset"
moveX = "moveX"
moveY = "moveY"
)
// Config is the config for a wheeledodometry MovementSensor.
type Config struct {
LeftMotors []string `json:"left_motors"`
RightMotors []string `json:"right_motors"`
Base string `json:"base"`
TimeIntervalMSecs float64 `json:"time_interval_msecs,omitempty"`
}
type motorPair struct {
left motor.Motor
right motor.Motor
}
type odometry struct {
resource.Named
resource.AlwaysRebuild
lastLeftPos float64
lastRightPos float64
baseWidth float64
wheelCircumference float64
base base.Base
timeIntervalMSecs float64
motors []motorPair
angularVelocity spatialmath.AngularVelocity
linearVelocity r3.Vector
position r3.Vector
orientation spatialmath.EulerAngles
coord *geo.Point
originCoord *geo.Point
useCompass bool
shiftPos bool
cancelFunc func()
activeBackgroundWorkers sync.WaitGroup
mu sync.Mutex
logger logging.Logger
}
func init() {
resource.RegisterComponent(
movementsensor.API,
model,
resource.Registration[movementsensor.MovementSensor, *Config]{Constructor: newWheeledOdometry})
}
// Validate ensures all parts of the config are valid.
func (cfg *Config) Validate(path string) ([]string, error) {
var deps []string
if cfg.Base == "" {
return nil, resource.NewConfigValidationFieldRequiredError(path, "base")
}
deps = append(deps, cfg.Base)
if len(cfg.LeftMotors) == 0 {
return nil, resource.NewConfigValidationFieldRequiredError(path, "left motors")
}
deps = append(deps, cfg.LeftMotors...)
if len(cfg.RightMotors) == 0 {
return nil, resource.NewConfigValidationFieldRequiredError(path, "right motors")
}
deps = append(deps, cfg.RightMotors...)
if len(cfg.LeftMotors) != len(cfg.RightMotors) {
return nil, errors.New("mismatch number of left and right motors")
}
// Temporary validation check until support for more than one left and right motor each is added.
if len(cfg.LeftMotors) > 1 || len(cfg.RightMotors) > 1 {
return nil, errors.New("wheeled odometry only supports one left and right motor each")
}
return deps, nil
}
// Reconfigure automatically reconfigures this movement sensor based on the updated config.
func (o *odometry) Reconfigure(ctx context.Context, deps resource.Dependencies, conf resource.Config) error {
if len(o.motors) > 0 {
if err := o.motors[0].left.Stop(ctx, nil); err != nil {
return err
}
if err := o.motors[0].right.Stop(ctx, nil); err != nil {
return err
}
}
if o.cancelFunc != nil {
o.cancelFunc()
o.activeBackgroundWorkers.Wait()
}
o.mu.Lock()
defer o.mu.Unlock()
newConf, err := resource.NativeConfig[*Config](conf)
if err != nil {
return err
}
// set the new timeIntervalMSecs
o.timeIntervalMSecs = newConf.TimeIntervalMSecs
if o.timeIntervalMSecs == 0 {
o.timeIntervalMSecs = defaultTimeIntervalMSecs
}
if o.timeIntervalMSecs > 1000 {
o.logger.CWarn(ctx, "if the time interval is more than 1000 ms, be sure to move the base slowly for better accuracy")
}
// set baseWidth and wheelCircumference from the new base properties
newBase, err := base.FromDependencies(deps, newConf.Base)
if err != nil {
return err
}
props, err := newBase.Properties(ctx, nil)
if err != nil {
return err
}
o.baseWidth = props.WidthMeters
o.wheelCircumference = props.WheelCircumferenceMeters
if o.baseWidth == 0 || o.wheelCircumference == 0 {
return errors.New("base width or wheel circumference are 0, movement sensor cannot be created")
}
o.base = newBase
o.logger.Debugf("using base %v for wheeled_odometry sensor", newBase.Name().ShortName())
// check if new motors have been added, or the existing motors have been changed, and update the motorPairs accorodingly
for i := range newConf.LeftMotors {
var motorLeft, motorRight motor.Motor
motorLeft, err = motor.FromDependencies(deps, newConf.LeftMotors[i])
if err != nil {
return err
}
properties, err := motorLeft.Properties(ctx, nil)
if err != nil {
return err
}
if !properties.PositionReporting {
return motor.NewPropertyUnsupportedError(properties, newConf.LeftMotors[i])
}
motorRight, err = motor.FromDependencies(deps, newConf.RightMotors[i])
if err != nil {
return err
}
properties, err = motorRight.Properties(ctx, nil)
if err != nil {
return err
}
if !properties.PositionReporting {
return motor.NewPropertyUnsupportedError(properties, newConf.LeftMotors[i])
}
// append if motors have been added, replace if motors have changed
thisPair := motorPair{left: motorLeft, right: motorRight}
if i >= len(o.motors) {
o.motors = append(o.motors, thisPair)
} else if (o.motors[i].left.Name().ShortName() != newConf.LeftMotors[i]) ||
(o.motors[i].right.Name().ShortName() != newConf.RightMotors[i]) {
o.motors[i].left = motorLeft
o.motors[i].right = motorRight
}
o.logger.Debugf("using motors %v for wheeled odometery",
[]string{motorLeft.Name().ShortName(), motorRight.Name().ShortName()})
}
if len(o.motors) > 1 {
o.logger.CWarn(ctx, "odometry will not be accurate if the left and right motors that are paired are not listed in the same order")
}
o.orientation.Yaw = 0
o.originCoord = geo.NewPoint(0, 0)
ctx, cancelFunc := context.WithCancel(context.Background())
o.cancelFunc = cancelFunc
o.trackPosition(ctx)
return nil
}
// newWheeledOdometry returns a new wheeled encoder movement sensor defined by the given config.
func newWheeledOdometry(
ctx context.Context,
deps resource.Dependencies,
conf resource.Config,
logger logging.Logger,
) (movementsensor.MovementSensor, error) {
o := &odometry{
Named: conf.ResourceName().AsNamed(),
lastLeftPos: 0.0,
lastRightPos: 0.0,
originCoord: geo.NewPoint(0, 0),
logger: logger,
}
if err := o.Reconfigure(ctx, deps, conf); err != nil {
return nil, err
}
return o, nil
}
func (o *odometry) AngularVelocity(ctx context.Context, extra map[string]interface{}) (spatialmath.AngularVelocity, error) {
o.mu.Lock()
defer o.mu.Unlock()
return o.angularVelocity, nil
}
func (o *odometry) LinearAcceleration(ctx context.Context, extra map[string]interface{}) (r3.Vector, error) {
return r3.Vector{}, movementsensor.ErrMethodUnimplementedLinearAcceleration
}
func (o *odometry) Orientation(ctx context.Context, extra map[string]interface{}) (spatialmath.Orientation, error) {
o.mu.Lock()
defer o.mu.Unlock()
ov := &spatialmath.OrientationVector{Theta: o.orientation.Yaw, OX: 0, OY: 0, OZ: 1}
return ov, nil
}
func (o *odometry) CompassHeading(ctx context.Context, extra map[string]interface{}) (float64, error) {
o.mu.Lock()
defer o.mu.Unlock()
if o.useCompass {
return yawToCompassHeading(o.orientation.Yaw), nil
}
return 0, movementsensor.ErrMethodUnimplementedCompassHeading
}
// computes the compass heading in degrees from a yaw in radians, with 0 -> 360 and Z down.
func yawToCompassHeading(yaw float64) float64 {
yawDeg := rdkutils.RadToDeg(yaw)
if yawDeg < 0 {
yawDeg = 180 - yawDeg
}
return 360 - yawDeg
}
func (o *odometry) LinearVelocity(ctx context.Context, extra map[string]interface{}) (r3.Vector, error) {
o.mu.Lock()
defer o.mu.Unlock()
return o.linearVelocity, nil
}
func (o *odometry) Position(ctx context.Context, extra map[string]interface{}) (*geo.Point, float64, error) {
o.mu.Lock()
defer o.mu.Unlock()
if relative, ok := extra[returnRelative]; ok {
if relative.(bool) {
return geo.NewPoint(o.position.Y, o.position.X), o.position.Z, nil
}
}
return o.coord, o.position.Z, nil
}
func (o *odometry) Readings(ctx context.Context, extra map[string]interface{}) (map[string]interface{}, error) {
readings, err := movementsensor.DefaultAPIReadings(ctx, o, extra)
if err != nil {
return nil, err
}
// movementsensor.Readings calls all the APIs with their owm mutex lock in this driver
// the lock has been released, so for the last two readings we lock again to append them to the readings map
o.mu.Lock()
defer o.mu.Unlock()
readings["position_meters_X"] = o.position.X
readings["position_meters_Y"] = o.position.Y
return readings, nil
}
func (o *odometry) Accuracy(ctx context.Context, extra map[string]interface{}) (*movementsensor.Accuracy, error,
) {
return movementsensor.UnimplementedOptionalAccuracies(), nil
}
func (o *odometry) Properties(ctx context.Context, extra map[string]interface{}) (*movementsensor.Properties, error) {
return &movementsensor.Properties{
LinearVelocitySupported: true,
AngularVelocitySupported: true,
OrientationSupported: true,
PositionSupported: true,
CompassHeadingSupported: o.useCompass,
}, nil
}
func (o *odometry) Close(ctx context.Context) error {
o.cancelFunc()
o.activeBackgroundWorkers.Wait()
return nil
}
func (o *odometry) checkBaseProps(ctx context.Context) {
props, err := o.base.Properties(ctx, nil)
if err != nil {
if !errors.Is(err, context.Canceled) {
o.logger.Error(err)
return
}
}
if (o.baseWidth != props.WidthMeters) || (o.wheelCircumference != props.WheelCircumferenceMeters) {
o.baseWidth = props.WidthMeters
o.wheelCircumference = props.WheelCircumferenceMeters
o.logger.Warnf("Base %v's properties have changed: baseWidth = %v and wheelCirumference = %v.",
"Odometry can optionally be reset using DoCommand",
o.base.Name().ShortName(), o.baseWidth, o.wheelCircumference)
}
}
// trackPosition uses the motor positions to calculate an estimation of the position, orientation,
// linear velocity, and angular velocity of the wheeled base.
// The estimations in this function are based on the math outlined in this article:
// https://stuff.mit.edu/afs/athena/course/6/6.186/OldFiles/2005/doc/odomtutorial/odomtutorial.pdf
func (o *odometry) trackPosition(ctx context.Context) {
if o.originCoord == nil {
o.originCoord = geo.NewPoint(0, 0)
}
o.activeBackgroundWorkers.Add(1)
utils.PanicCapturingGo(func() {
defer o.activeBackgroundWorkers.Done()
ticker := time.NewTicker(time.Duration(o.timeIntervalMSecs) * time.Millisecond)
for {
select {
case <-ctx.Done():
return
default:
}
// Sleep until it's time to update the position again.
select {
case <-ctx.Done():
return
case <-ticker.C:
}
// Use GetInParallel to ensure the left and right motors are polled at the same time.
positionFuncs := func() []rdkutils.FloatFunc {
fs := []rdkutils.FloatFunc{}
// Always use the first pair until more than one pair of motors is supported in this model.
fs = append(fs, func(ctx context.Context) (float64, error) { return o.motors[0].left.Position(ctx, nil) })
fs = append(fs, func(ctx context.Context) (float64, error) { return o.motors[0].right.Position(ctx, nil) })
return fs
}
_, positions, err := rdkutils.GetInParallel(ctx, positionFuncs())
if err != nil {
o.logger.CError(ctx, err)
continue
}
// Current position of the left and right motors in revolutions.
if len(positions) != len(o.motors)*2 {
o.logger.CError(ctx, "error getting both motor positions, trying again")
continue
}
left := positions[0]
right := positions[1]
// Base properties need to be checked every time because dependent components reconfiguring does not trigger
// the parent component to reconfigure. In this case, that means if the base properties change, the wheeled
// odometry movement sensor will not be aware of these changes and will continue to use the old values
o.checkBaseProps(ctx)
// Difference in the left and right motors since the last iteration, in mm.
leftDist := (left - o.lastLeftPos) * o.wheelCircumference
rightDist := (right - o.lastRightPos) * o.wheelCircumference
// Update lastLeftPos and lastRightPos to be the current position in mm.
o.lastLeftPos = left
o.lastRightPos = right
// Linear and angular distance the center point has traveled. This works based on
// the assumption that the time interval between calulations is small enough that
// the inner angle of the rotation will be small enough that it can be accurately
// estimated using the below equations.
centerDist := (leftDist + rightDist) / 2
centerAngle := (rightDist - leftDist) / o.baseWidth
// Update the position and orientation values accordingly.
o.mu.Lock()
o.orientation.Yaw += centerAngle
// Limit the yaw to a range of positive 0 to 360 degrees.
o.orientation.Yaw = math.Mod(o.orientation.Yaw, oneTurn)
o.orientation.Yaw = math.Mod(o.orientation.Yaw+oneTurn, oneTurn)
angle := o.orientation.Yaw
xFlip := -1.0
if o.useCompass {
angle = rdkutils.DegToRad(yawToCompassHeading(o.orientation.Yaw))
xFlip = 1.0
}
o.position.X += xFlip * (centerDist * math.Sin(angle))
o.position.Y += (centerDist * math.Cos(angle))
distance := math.Hypot(o.position.X, o.position.Y)
heading := rdkutils.RadToDeg(math.Atan2(o.position.X, o.position.Y))
o.coord = o.originCoord.PointAtDistanceAndBearing(distance*mToKm, heading)
// Update the linear and angular velocity values using the provided time interval.
o.linearVelocity.Y = centerDist / (o.timeIntervalMSecs / 1000)
o.angularVelocity.Z = centerAngle * (180 / math.Pi) / (o.timeIntervalMSecs / 1000)
o.mu.Unlock()
}
})
}
func (o *odometry) DoCommand(ctx context.Context,
req map[string]interface{},
) (map[string]interface{}, error) {
resp := make(map[string]interface{})
o.mu.Lock()
defer o.mu.Unlock()
cmd, ok := req[useCompass].(bool)
if ok {
o.useCompass = cmd
resp[useCompass] = fmt.Sprintf("using orientation as compass heading set to %v", cmd)
}
reset, ok := req[resetShift].(bool)
if ok {
o.shiftPos = reset
o.originCoord = geo.NewPoint(0, 0)
o.position.X = 0
o.position.Y = 0
o.orientation.Yaw = 0
resp[resetShift] = fmt.Sprintf("resetting position and setting shift to %v", reset)
}
lat, okY := req[setLat].(float64)
long, okX := req[setLong].(float64)
if okY && okX {
o.originCoord = geo.NewPoint(lat, long)
o.shiftPos = true
resp[setLat] = fmt.Sprintf("lat shifted to %.8f", lat)
resp[setLong] = fmt.Sprintf("lng shifted to %.8f", long)
} else if okY || okX {
// If only one value is given, return an error.
// This prevents errors when neither is given.
resp["bad shift"] = "need both lat and long shifts"
}
xMove, okX := req[moveX].(float64)
yMove, okY := req[moveY].(float64)
if okX {
o.position.X += xMove
resp[moveX] = fmt.Sprintf("x position moved to %.8f", o.position.X)
}
if okY {
o.position.Y += yMove
resp[moveY] = fmt.Sprintf("y position shifted to %.8f", o.position.Y)
}
return resp, nil
}