-
Notifications
You must be signed in to change notification settings - Fork 109
/
fake_kinematics.go
225 lines (197 loc) · 5.79 KB
/
fake_kinematics.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
//go:build !no_cgo
package kinematicbase
import (
"context"
"errors"
"sync"
"time"
"go.viam.com/rdk/components/base/fake"
"go.viam.com/rdk/logging"
"go.viam.com/rdk/motionplan/tpspace"
"go.viam.com/rdk/referenceframe"
"go.viam.com/rdk/services/motion"
"go.viam.com/rdk/spatialmath"
)
type fakeDiffDriveKinematics struct {
*fake.Base
parentFrame string
planningFrame, executionFrame referenceframe.Frame
inputs []referenceframe.Input
options Options
sensorNoise spatialmath.Pose
lock sync.RWMutex
}
// WrapWithFakeDiffDriveKinematics creates a DiffDrive KinematicBase from the fake Base so that it satisfies the ModelFramer and
// InputEnabled interfaces.
func WrapWithFakeDiffDriveKinematics(
ctx context.Context,
b *fake.Base,
localizer motion.Localizer,
limits []referenceframe.Limit,
options Options,
sensorNoise spatialmath.Pose,
) (KinematicBase, error) {
position, err := localizer.CurrentPosition(ctx)
if err != nil {
return nil, err
}
pt := position.Pose().Point()
if sensorNoise == nil {
sensorNoise = spatialmath.NewZeroPose()
}
fk := &fakeDiffDriveKinematics{
Base: b,
parentFrame: position.Parent(),
inputs: referenceframe.FloatsToInputs([]float64{pt.X, pt.Y}),
sensorNoise: sensorNoise,
}
var geometry spatialmath.Geometry
if len(fk.Base.Geometry) != 0 {
geometry = fk.Base.Geometry[0]
}
fk.executionFrame, err = referenceframe.New2DMobileModelFrame(b.Name().ShortName(), limits, geometry)
if err != nil {
return nil, err
}
if options.PositionOnlyMode {
fk.planningFrame, err = referenceframe.New2DMobileModelFrame(b.Name().ShortName(), limits[:2], geometry)
if err != nil {
return nil, err
}
} else {
fk.planningFrame = fk.executionFrame
}
fk.options = options
return fk, nil
}
func (fk *fakeDiffDriveKinematics) Kinematics() referenceframe.Frame {
return fk.planningFrame
}
func (fk *fakeDiffDriveKinematics) CurrentInputs(ctx context.Context) ([]referenceframe.Input, error) {
fk.lock.RLock()
defer fk.lock.RUnlock()
return fk.inputs, nil
}
func (fk *fakeDiffDriveKinematics) GoToInputs(ctx context.Context, inputs []referenceframe.Input) error {
_, err := fk.planningFrame.Transform(inputs)
if err != nil {
return err
}
fk.lock.Lock()
fk.inputs = inputs
fk.lock.Unlock()
// Sleep for a short amount to time to simulate a base taking some amount of time to reach the inputs
time.Sleep(150 * time.Millisecond)
return nil
}
func (fk *fakeDiffDriveKinematics) ErrorState(
ctx context.Context,
plan [][]referenceframe.Input,
currentNode int,
) (spatialmath.Pose, error) {
return fk.sensorNoise, nil
}
func (fk *fakeDiffDriveKinematics) CurrentPosition(ctx context.Context) (*referenceframe.PoseInFrame, error) {
fk.lock.RLock()
inputs := fk.inputs
fk.lock.RUnlock()
currentPose, err := fk.planningFrame.Transform(inputs)
if err != nil {
return nil, err
}
return referenceframe.NewPoseInFrame(fk.parentFrame, spatialmath.Compose(currentPose, fk.sensorNoise)), nil
}
type fakePTGKinematics struct {
*fake.Base
frame referenceframe.Frame
options Options
sensorNoise spatialmath.Pose
origin *referenceframe.PoseInFrame
lock sync.RWMutex
logger logging.Logger
sleepTime int
}
// WrapWithFakePTGKinematics creates a PTG KinematicBase from the fake Base so that it satisfies the ModelFramer and InputEnabled
// interfaces.
func WrapWithFakePTGKinematics(
ctx context.Context,
b *fake.Base,
logger logging.Logger,
origin *referenceframe.PoseInFrame,
options Options,
sensorNoise spatialmath.Pose,
sleepTime int,
) (KinematicBase, error) {
properties, err := b.Properties(ctx, nil)
if err != nil {
return nil, err
}
baseMillimetersPerSecond := options.LinearVelocityMMPerSec
if baseMillimetersPerSecond == 0 {
baseMillimetersPerSecond = defaultLinearVelocityMMPerSec
}
baseTurningRadiusMeters := properties.TurningRadiusMeters
if baseTurningRadiusMeters < 0 {
return nil, errors.New("can only wrap with PTG kinematics if turning radius is greater than or equal to zero")
}
geometries, err := b.Geometries(ctx, nil)
if err != nil {
return nil, err
}
frame, err := tpspace.NewPTGFrameFromKinematicOptions(
b.Name().ShortName(),
logger,
baseMillimetersPerSecond,
options.AngularVelocityDegsPerSec,
baseTurningRadiusMeters,
0, // If zero, will use default on the receiver end.
geometries,
options.NoSkidSteer,
)
if err != nil {
return nil, err
}
if sensorNoise == nil {
sensorNoise = spatialmath.NewZeroPose()
}
fk := &fakePTGKinematics{
Base: b,
frame: frame,
origin: origin,
sensorNoise: sensorNoise,
logger: logger,
sleepTime: sleepTime,
}
fk.options = options
return fk, nil
}
func (fk *fakePTGKinematics) Kinematics() referenceframe.Frame {
return fk.frame
}
func (fk *fakePTGKinematics) CurrentInputs(ctx context.Context) ([]referenceframe.Input, error) {
return make([]referenceframe.Input, 3), nil
}
func (fk *fakePTGKinematics) GoToInputs(ctx context.Context, inputs []referenceframe.Input) error {
newPose, err := fk.frame.Transform(inputs)
if err != nil {
return err
}
fk.lock.Lock()
fk.origin = referenceframe.NewPoseInFrame(fk.origin.Parent(), spatialmath.Compose(fk.origin.Pose(), newPose))
fk.lock.Unlock()
time.Sleep(time.Duration(fk.sleepTime) * time.Millisecond)
return nil
}
func (fk *fakePTGKinematics) ErrorState(
ctx context.Context,
plan [][]referenceframe.Input,
currentNode int,
) (spatialmath.Pose, error) {
return fk.sensorNoise, nil
}
func (fk *fakePTGKinematics) CurrentPosition(ctx context.Context) (*referenceframe.PoseInFrame, error) {
fk.lock.RLock()
defer fk.lock.RUnlock()
origin := fk.origin
return referenceframe.NewPoseInFrame(origin.Parent(), spatialmath.Compose(origin.Pose(), fk.sensorNoise)), nil
}