浏览代码

Refine the pre-tracking

customisations
alemart 9 个月前
父节点
当前提交
24f7ca1ed5

+ 10
- 1
src/trackers/image-tracker/settings.ts 查看文件

51
 export const SCAN_CONSECUTIVE_FRAMES = 30;//15;//45;
51
 export const SCAN_CONSECUTIVE_FRAMES = 30;//15;//45;
52
 
52
 
53
 /** Reprojection error, in NIS pixels, used when estimating a motion model (scanning state) */
53
 /** Reprojection error, in NIS pixels, used when estimating a motion model (scanning state) */
54
-export const SCAN_RANSAC_REPROJECTIONERROR_NIS = (NIS_SIZE * 0.02) | 0;
54
+export const SCAN_RANSAC_REPROJECTIONERROR_NIS = (NIS_SIZE * 0.0125) | 0;
55
 
55
 
56
 /** Reprojection error, in NDC, used when estimating a motion model (scanning state) */
56
 /** Reprojection error, in NDC, used when estimating a motion model (scanning state) */
57
 export const SCAN_RANSAC_REPROJECTIONERROR_NDC = SCAN_RANSAC_REPROJECTIONERROR_NIS / (NIS_SIZE / 2);
57
 export const SCAN_RANSAC_REPROJECTIONERROR_NDC = SCAN_RANSAC_REPROJECTIONERROR_NIS / (NIS_SIZE / 2);
95
 /** Minimum acceptable number of matched keypoints when in a pre-tracking state */
95
 /** Minimum acceptable number of matched keypoints when in a pre-tracking state */
96
 export const PRE_TRACK_MIN_MATCHES = 4;
96
 export const PRE_TRACK_MIN_MATCHES = 4;
97
 
97
 
98
+/** Maximum number of iterations in Pre-tracking B */
99
+export const PRE_TRACK_MAX_ITERATIONS = 3;
100
+
101
+/** Reprojection error, in NIS pixels, used when pre-tracking */
102
+export const PRE_TRACK_RANSAC_REPROJECTIONERROR_NIS = (NIS_SIZE * 0.0125 * 0.5) | 0;
103
+
104
+/** Reprojection error, in NDC, used when pre-tracking */
105
+export const PRE_TRACK_RANSAC_REPROJECTIONERROR_NDC = PRE_TRACK_RANSAC_REPROJECTIONERROR_NIS / (NIS_SIZE / 2);
106
+
98
 /** Minimum acceptable number of matched keypoints when in the tracking state */
107
 /** Minimum acceptable number of matched keypoints when in the tracking state */
99
 export const TRACK_MIN_MATCHES = 4;//10; //20;
108
 export const TRACK_MIN_MATCHES = 4;//10; //20;
100
 
109
 

+ 38
- 13
src/trackers/image-tracker/states/pre-tracking-b.ts 查看文件

29
 import { SpeedyPipeline, SpeedyPipelineOutput } from 'speedy-vision/types/core/pipeline/pipeline';
29
 import { SpeedyPipeline, SpeedyPipelineOutput } from 'speedy-vision/types/core/pipeline/pipeline';
30
 import { SpeedyPipelineNodeImageSource } from 'speedy-vision/types/core/pipeline/nodes/images/source';
30
 import { SpeedyPipelineNodeImageSource } from 'speedy-vision/types/core/pipeline/nodes/images/source';
31
 import { SpeedyPipelineNodeImageMultiplexer } from 'speedy-vision/types/core/pipeline/nodes/images/multiplexer';
31
 import { SpeedyPipelineNodeImageMultiplexer } from 'speedy-vision/types/core/pipeline/nodes/images/multiplexer';
32
+import { SpeedyPipelineNodeImageBuffer } from 'speedy-vision/types/core/pipeline/nodes/images/buffer';
32
 import { SpeedyPipelineNodeImagePortalSource, SpeedyPipelineNodeImagePortalSink } from 'speedy-vision/types/core/pipeline/nodes/images/portal';
33
 import { SpeedyPipelineNodeImagePortalSource, SpeedyPipelineNodeImagePortalSink } from 'speedy-vision/types/core/pipeline/nodes/images/portal';
33
 import { SpeedyPipelineNodeKeypointPortalSource, SpeedyPipelineNodeKeypointPortalSink } from 'speedy-vision/types/core/pipeline/nodes/keypoints/portal';
34
 import { SpeedyPipelineNodeKeypointPortalSource, SpeedyPipelineNodeKeypointPortalSink } from 'speedy-vision/types/core/pipeline/nodes/keypoints/portal';
34
 import { SpeedyPipelineNodeResize } from 'speedy-vision/types/core/pipeline/nodes/transforms/resize';
35
 import { SpeedyPipelineNodeResize } from 'speedy-vision/types/core/pipeline/nodes/transforms/resize';
48
     ORB_GAUSSIAN_KSIZE, ORB_GAUSSIAN_SIGMA,
49
     ORB_GAUSSIAN_KSIZE, ORB_GAUSSIAN_SIGMA,
49
     TRACK_HARRIS_QUALITY, TRACK_DETECTOR_CAPACITY, TRACK_MAX_KEYPOINTS,
50
     TRACK_HARRIS_QUALITY, TRACK_DETECTOR_CAPACITY, TRACK_MAX_KEYPOINTS,
50
     SUBPIXEL_GAUSSIAN_KSIZE, SUBPIXEL_GAUSSIAN_SIGMA,
51
     SUBPIXEL_GAUSSIAN_KSIZE, SUBPIXEL_GAUSSIAN_SIGMA,
51
-    PRE_TRACK_MIN_MATCHES, TRACK_MATCH_RATIO, TRACK_RANSAC_REPROJECTIONERROR_NDC,
52
+    PRE_TRACK_MIN_MATCHES, PRE_TRACK_MAX_ITERATIONS,
53
+    TRACK_MATCH_RATIO, PRE_TRACK_RANSAC_REPROJECTIONERROR_NDC,
52
     NIGHTVISION_QUALITY,
54
     NIGHTVISION_QUALITY,
53
     SUBPIXEL_METHOD,
55
     SUBPIXEL_METHOD,
54
 } from '../settings';
56
 } from '../settings';
75
     /** portal with keypoints from Pre-Tracking A */
77
     /** portal with keypoints from Pre-Tracking A */
76
     private _referenceKeypointPortalSink: Nullable<SpeedyPipelineNodeKeypointPortalSink>;
78
     private _referenceKeypointPortalSink: Nullable<SpeedyPipelineNodeKeypointPortalSink>;
77
 
79
 
80
+    /** number of iterations */
81
+    private _iterations: number;
82
+
78
 
83
 
79
 
84
 
80
 
85
 
92
         this._referenceImage = null;
97
         this._referenceImage = null;
93
         this._snapshot = null;
98
         this._snapshot = null;
94
         this._referenceKeypointPortalSink = null;
99
         this._referenceKeypointPortalSink = null;
100
+        this._iterations = 0;
95
     }
101
     }
96
 
102
 
97
     /**
103
     /**
104
         const referenceImage = settings.referenceImage as ReferenceImageWithMedia;
110
         const referenceImage = settings.referenceImage as ReferenceImageWithMedia;
105
         const snapshot = settings.snapshot as SpeedyPipelineNodeImagePortalSink;
111
         const snapshot = settings.snapshot as SpeedyPipelineNodeImagePortalSink;
106
         const referenceKeypointPortalSink = settings.referenceKeypointPortalSink as SpeedyPipelineNodeKeypointPortalSink;
112
         const referenceKeypointPortalSink = settings.referenceKeypointPortalSink as SpeedyPipelineNodeKeypointPortalSink;
113
+        const sourceMux = this._pipeline.node('sourceMux') as SpeedyPipelineNodeImageMultiplexer;
114
+        const sourceBuffer = this._pipeline.node('sourceBuffer') as SpeedyPipelineNodeImageBuffer;
107
 
115
 
108
         // set attributes
116
         // set attributes
109
         this._homography = homography;
117
         this._homography = homography;
110
         this._referenceImage = referenceImage;
118
         this._referenceImage = referenceImage;
111
         this._snapshot = snapshot;
119
         this._snapshot = snapshot;
112
         this._referenceKeypointPortalSink = referenceKeypointPortalSink;
120
         this._referenceKeypointPortalSink = referenceKeypointPortalSink;
121
+        this._iterations = 0;
122
+
123
+        // reset nodes
124
+        sourceMux.port = 0;
125
+        sourceBuffer.frozen = false;
113
     }
126
     }
114
 
127
 
115
     /**
128
     /**
166
         const keypoints = result.keypoints as SpeedyMatchedKeypoint[]; // from Pre-Tracking B
179
         const keypoints = result.keypoints as SpeedyMatchedKeypoint[]; // from Pre-Tracking B
167
         const image = result.image as SpeedyMedia | undefined;
180
         const image = result.image as SpeedyMedia | undefined;
168
         const keypointPortalSink = this._pipeline.node('keypointPortalSink') as SpeedyPipelineNodeKeypointPortalSink;
181
         const keypointPortalSink = this._pipeline.node('keypointPortalSink') as SpeedyPipelineNodeKeypointPortalSink;
182
+        const sourceMux = this._pipeline.node('sourceMux') as SpeedyPipelineNodeImageMultiplexer;
183
+        const sourceBuffer = this._pipeline.node('sourceBuffer') as SpeedyPipelineNodeImageBuffer;
169
 
184
 
170
         // tracker output
185
         // tracker output
171
         const trackerOutput: ImageTrackerOutput = {
186
         const trackerOutput: ImageTrackerOutput = {
184
 
199
 
185
             // find a warp
200
             // find a warp
186
             const points = ImageTrackerUtils.compilePairsOfKeypointsNDC(pairs);
201
             const points = ImageTrackerUtils.compilePairsOfKeypointsNDC(pairs);
187
-            return this._findAffineMotionNDC(points);
202
+            return this._findMotionNDC(points);
188
 
203
 
189
         })
204
         })
190
         .then(warp => {
205
         .then(warp => {
191
 
206
 
207
+            // get the camera image in the next iteration
208
+            // the warped snapshot from the scanning state is occasionally very blurry
209
+            sourceMux.port = 1;
210
+            sourceBuffer.frozen = true;
211
+
192
             // refine the homography
212
             // refine the homography
193
             return this._homography.setTo(warp.times(this._homography));
213
             return this._homography.setTo(warp.times(this._homography));
194
 
214
 
195
         })
215
         })
196
         .then(_ => ({
216
         .then(_ => ({
197
-            nextState: 'tracking',
198
-            //nextState: 'pre-tracking-b',
217
+            nextState: (++this._iterations < PRE_TRACK_MAX_ITERATIONS) ? 'pre-tracking-b' : 'tracking',
199
             trackerOutput: trackerOutput,
218
             trackerOutput: trackerOutput,
200
             nextStateSettings: {
219
             nextStateSettings: {
201
                 // we export keypoints obtained in Pre-Tracking B, not in A.
220
                 // we export keypoints obtained in Pre-Tracking B, not in A.
202
-                // lighting conditions match, but what if the snapshot is too blurry?
203
                 templateKeypoints: keypoints,
221
                 templateKeypoints: keypoints,
204
                 templateKeypointPortalSink: keypointPortalSink,
222
                 templateKeypointPortalSink: keypointPortalSink,
205
                 referenceImage: this._referenceImage,
223
                 referenceImage: this._referenceImage,
217
     }
235
     }
218
 
236
 
219
     /**
237
     /**
220
-     * Find an affine motion model in NDC between pairs of keypoints in NDC
238
+     * Find a motion model in NDC between pairs of keypoints in NDC
221
      * given as a 2 x 2n [ src | dest ] matrix
239
      * given as a 2 x 2n [ src | dest ] matrix
222
      * @param points compiled pairs of keypoints in NDC
240
      * @param points compiled pairs of keypoints in NDC
223
      * @returns a promise that resolves to a 3x3 warp in NDC that maps source to destination
241
      * @returns a promise that resolves to a 3x3 warp in NDC that maps source to destination
224
      */
242
      */
225
-    private _findAffineMotionNDC(points: SpeedyMatrix): SpeedyPromise<SpeedyMatrixExpr>
243
+    private _findMotionNDC(points: SpeedyMatrix): SpeedyPromise<SpeedyMatrixExpr>
226
     {
244
     {
227
-        return ImageTrackerUtils.findAffineWarpNDC(points, {
245
+        //return ImageTrackerUtils.findAffineWarpNDC(points, {
246
+        return ImageTrackerUtils.findPerspectiveWarpNDC(points, {
228
             method: 'pransac',
247
             method: 'pransac',
229
-            reprojectionError: TRACK_RANSAC_REPROJECTIONERROR_NDC,
230
-            numberOfHypotheses: 512*4,
248
+            reprojectionError: PRE_TRACK_RANSAC_REPROJECTIONERROR_NDC,
249
+            numberOfHypotheses: 512*8, // we want a really good homography
231
             bundleSize: 128,
250
             bundleSize: 128,
232
             mask: undefined // score is not needed
251
             mask: undefined // score is not needed
233
         }).then(([ warp, score ]) => {
252
         }).then(([ warp, score ]) => {
290
 
309
 
291
         const source = Speedy.Image.Source('source');
310
         const source = Speedy.Image.Source('source');
292
         const imagePortalSource = Speedy.Image.Portal.Source('imagePortalSource');
311
         const imagePortalSource = Speedy.Image.Portal.Source('imagePortalSource');
312
+        const sourceMux = Speedy.Image.Multiplexer('sourceMux');
313
+        const sourceBuffer = Speedy.Image.Buffer('sourceBuffer');
293
         const referenceKeypointPortalSource = Speedy.Keypoint.Portal.Source('referenceKeypointPortalSource');
314
         const referenceKeypointPortalSource = Speedy.Keypoint.Portal.Source('referenceKeypointPortalSource');
294
         const screen = Speedy.Transform.Resize('screen');
315
         const screen = Speedy.Transform.Resize('screen');
295
         const greyscale = Speedy.Filter.Greyscale();
316
         const greyscale = Speedy.Filter.Greyscale();
312
 
333
 
313
         source.media = null;
334
         source.media = null;
314
         imagePortalSource.source = null;
335
         imagePortalSource.source = null;
336
+        sourceMux.port = 0; // 0 = portal; 1 = source
337
+        sourceBuffer.frozen = false;
315
         referenceKeypointPortalSource.source = null;
338
         referenceKeypointPortalSource.source = null;
316
         imageRectifier.transform = Speedy.Matrix.Eye(3);
339
         imageRectifier.transform = Speedy.Matrix.Eye(3);
317
         screen.size = Speedy.Size(0,0);
340
         screen.size = Speedy.Size(0,0);
335
         keypointSink.turbo = false;
358
         keypointSink.turbo = false;
336
 
359
 
337
         // prepare input
360
         // prepare input
338
-        //source.output(); // ignore, but keep it in the pipeline
339
-        imagePortalSource.output().connectTo(screen.input());
361
+        source.output().connectTo(sourceBuffer.input());
362
+        imagePortalSource.output().connectTo(sourceMux.input('in0'));
363
+        sourceBuffer.output().connectTo(sourceMux.input('in1'));
364
+        sourceMux.output().connectTo(screen.input());
340
         screen.output().connectTo(greyscale.input());
365
         screen.output().connectTo(greyscale.input());
341
 
366
 
342
         // preprocess images
367
         // preprocess images
374
 
399
 
375
         // done!
400
         // done!
376
         pipeline.init(
401
         pipeline.init(
377
-            source, screen, imagePortalSource,
402
+            source, imagePortalSource, sourceBuffer, sourceMux, screen,
378
             referenceKeypointPortalSource,
403
             referenceKeypointPortalSource,
379
             greyscale, imageRectifier,
404
             greyscale, imageRectifier,
380
             nightvision, nightvisionMux,
405
             nightvision, nightvisionMux,

+ 1
- 1
src/trackers/image-tracker/states/scanning.ts 查看文件

295
         return ImageTrackerUtils.findPerspectiveWarpNDC(points, {
295
         return ImageTrackerUtils.findPerspectiveWarpNDC(points, {
296
             method: 'pransac',
296
             method: 'pransac',
297
             reprojectionError: SCAN_RANSAC_REPROJECTIONERROR_NDC,
297
             reprojectionError: SCAN_RANSAC_REPROJECTIONERROR_NDC,
298
-            numberOfHypotheses: 512,
298
+            numberOfHypotheses: 512*2,
299
             bundleSize: 128,
299
             bundleSize: 128,
300
         });
300
         });
301
     }
301
     }

正在加载...
取消
保存