Camera Motion#
When the camera itself moves, the apparent motion of tracked objects becomes
a mix of "the object moved" and "the camera moved". Norfair's camera motion
module estimates the camera's frame-to-frame transformation from optical flow
and lets the Tracker reason about positions in a
stable world coordinate system.
The main entry point is MotionEstimator.
It returns a CoordinatesTransformation
for each frame which you pass to Tracker.update(coord_transformations=...).
Two concrete transformation families are provided:
TranslationTransformation/TranslationTransformationGetter— cheap, good enough for pure pan/tilt.HomographyTransformation/HomographyTransformationGetter— full 8-DoF homography, handles rotation, zoom, and perspective. This is the default.
Example#
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 | |
You can pass a mask to motion_estimator.update() to ignore image regions
that contain the tracked objects themselves (which would otherwise pollute the
optical-flow estimate). A common pattern is to build the mask from the previous
frame's detections or tracked objects.
For debugging, set MotionEstimator(draw_flow=True) to overlay the sampled
optical-flow vectors on the frame, and use
draw_absolute_grid together with
FixedCamera to visualize the recovered
world coordinate system.
API#
Camera motion estimation module.
Contains the abstract coordinate transformation interfaces, the built-in
translation and homography implementations, and the :class:MotionEstimator
that ties them to OpenCV's sparse optical flow.
CoordinatesTransformation
#
Bases: ABC
Abstract base class representing a coordinate transformation.
Detection and tracked-object coordinates can be interpreted in two reference frames:
- Relative — their position on the current frame, where
(0, 0)is the top-left corner. - Absolute — their position in a fixed space, where
(0, 0)is the top-left corner of the first frame of the video.
A CoordinatesTransformation can map coordinates from one reference
to the other.
Source code in norfair/camera_motion.py
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 | |
abs_to_rel(points)
abstractmethod
#
Map absolute-frame points to the current relative frame.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
points
|
ndarray
|
Array of shape |
required |
Returns:
| Type | Description |
|---|---|
ndarray
|
Transformed points with the same shape, in relative coordinates. |
Source code in norfair/camera_motion.py
43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 | |
rel_to_abs(points)
abstractmethod
#
Map relative-frame points to the absolute frame.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
points
|
ndarray
|
Array of shape |
required |
Returns:
| Type | Description |
|---|---|
ndarray
|
Transformed points with the same shape, in absolute coordinates. |
Source code in norfair/camera_motion.py
60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 | |
TransformationGetter
#
Bases: ABC
Abstract base class for objects that infer a CoordinatesTransformation.
Subclasses take two point clouds (previous and current frame features) and return a flag indicating whether the reference frame should be reset together with the inferred transformation.
Source code in norfair/camera_motion.py
78 79 80 81 82 83 84 85 86 87 88 89 90 | |
__call__(curr_pts, prev_pts)
abstractmethod
#
Return (update_reference, transformation) for the current pair.
Source code in norfair/camera_motion.py
86 87 88 89 90 | |
TranslationTransformation
#
Bases: CoordinatesTransformation
Coordinate transformation using a simple 2D translation.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
movement_vector
|
ndarray
|
The vector representing the translation. |
required |
Source code in norfair/camera_motion.py
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 | |
__init__(movement_vector)
#
Store the movement_vector used for the translation.
Source code in norfair/camera_motion.py
106 107 108 | |
abs_to_rel(points)
#
Translate absolute points into the current relative frame.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
points
|
NDArray[float64]
|
Array of shape |
required |
Returns:
| Type | Description |
|---|---|
NDArray[float64]
|
Translated points with the same shape, in relative coordinates. |
Source code in norfair/camera_motion.py
110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 | |
rel_to_abs(points)
#
Translate relative points back into the absolute frame.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
points
|
NDArray[float64]
|
Array of shape |
required |
Returns:
| Type | Description |
|---|---|
NDArray[float64]
|
Translated points with the same shape, in absolute coordinates. |
Source code in norfair/camera_motion.py
127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 | |
TranslationTransformationGetter
#
Bases: TransformationGetter
Compute a :class:TranslationTransformation from a pair of point clouds.
The camera movement is estimated as the mode of the optical flow between the previous reference frame and the current one.
Comparing consecutive frames can yield differences too small to estimate the translation reliably, so the reference frame is kept fixed as we progress through the video. Once the transformation can no longer match enough points, the reference frame is reset.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
bin_size
|
float
|
Before calculating the mode, optical-flow vectors are bucketized into bins of this size. |
0.2
|
proportion_points_used_threshold
|
float
|
Proportion of points that must be matched; if the ratio drops below this value, the reference frame is updated. |
0.9
|
Source code in norfair/camera_motion.py
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 | |
__init__(bin_size=0.2, proportion_points_used_threshold=0.9)
#
Store parameters and initialize the running flow accumulator.
Source code in norfair/camera_motion.py
167 168 169 170 171 172 173 | |
__call__(curr_pts, prev_pts)
#
Return the translation that best matches the optical flow.
Source code in norfair/camera_motion.py
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 | |
HomographyTransformation
#
Bases: CoordinatesTransformation
Coordinate transformation using a 3×3 homography matrix.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
homography_matrix
|
ndarray
|
The matrix representing the homography. |
required |
Source code in norfair/camera_motion.py
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 | |
__init__(homography_matrix)
#
Store the homography and pre-compute its inverse.
Raises:
| Type | Description |
|---|---|
ValueError
|
If |
Source code in norfair/camera_motion.py
221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 | |
abs_to_rel(points)
#
Apply the forward homography to map absolute points to relative.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
points
|
NDArray[float64]
|
Array of shape |
required |
Returns:
| Type | Description |
|---|---|
NDArray[float64]
|
Transformed points with the same shape, in relative coordinates. |
Source code in norfair/camera_motion.py
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 | |
rel_to_abs(points)
#
Apply the inverse homography to map relative points to absolute.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
points
|
NDArray[float64]
|
Array of shape |
required |
Returns:
| Type | Description |
|---|---|
NDArray[float64]
|
Transformed points with the same shape, in absolute coordinates. |
Source code in norfair/camera_motion.py
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 | |
HomographyTransformationGetter
#
Bases: TransformationGetter
Compute a :class:HomographyTransformation from a pair of point clouds.
The camera movement is represented as a homography that maps the optical flow between the previous reference frame and the current one.
Comparing consecutive frames can make differences too small to estimate the homography reliably, often collapsing to the identity. The reference frame is therefore kept fixed as we progress through the video; once the transformation can no longer match enough points, it is reset.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
method
|
int
|
One of OpenCV's methods for finding homographies. Valid options
are |
None
|
ransac_reproj_threshold
|
int
|
Maximum allowed reprojection error to treat a point pair as an inlier. See the OpenCV docs linked below for details. |
3
|
max_iters
|
int
|
The maximum number of RANSAC iterations. See the OpenCV docs linked below for details. |
2000
|
confidence
|
float
|
Confidence level, must be between 0 and 1. See the OpenCV docs linked below for details. |
0.995
|
proportion_points_used_threshold
|
float
|
Proportion of points that must be matched; if the ratio drops below this value, the reference frame is updated. |
0.9
|
See Also
Source code in norfair/camera_motion.py
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 | |
__init__(method=None, ransac_reproj_threshold=3, max_iters=2000, confidence=0.995, proportion_points_used_threshold=0.9)
#
Store RANSAC parameters and initialize the running homography.
Source code in norfair/camera_motion.py
336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 | |
__call__(curr_pts, prev_pts)
#
Return the homography that best matches the optical flow.
Source code in norfair/camera_motion.py
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 | |
MotionEstimator
#
Camera motion estimator driven by sparse optical flow.
Uses OpenCV optical flow on a set of strong corner features to
estimate the motion of the camera from frame to frame and feeds the
result through a :class:TransformationGetter to recover a
:class:CoordinatesTransformation.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
max_points
|
int
|
Maximum number of points sampled. More points make the estimation slower but more precise. |
200
|
min_distance
|
int
|
Minimum distance between sampled points. |
15
|
block_size
|
int
|
Size of the averaging block used when finding corners. See the OpenCV link below for details. |
3
|
transformations_getter
|
TransformationGetter
|
The transformation estimator used on the sampled points. Defaults
to
|
None
|
draw_flow
|
bool
|
Draw the optical flow on the frame in place, for debugging. |
False
|
flow_color
|
tuple[int, int, int]
|
BGR color for the flow drawing. Defaults to a dark blue. |
None
|
quality_level
|
float
|
Minimum accepted quality of the image corners. |
0.01
|
Examples:
1 2 3 4 5 6 7 8 9 10 11 | |
See Also
Source code in norfair/camera_motion.py
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 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 | |
__init__(max_points=200, min_distance=15, block_size=3, transformations_getter=None, draw_flow=False, flow_color=None, quality_level=0.01)
#
Initialize sampling parameters and the transformation getter.
Source code in norfair/camera_motion.py
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 | |
update(frame, mask=None)
#
Estimate the camera motion for one frame.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
frame
|
ndarray
|
The current video frame. |
required |
mask
|
ndarray
|
Optional mask excluding regions from corner sampling. Must
have shape In general, the estimation works best when many points come from the background, so this parameter is useful for masking out detections or tracked objects and forcing the estimator to ignore moving objects. It can also be used to mask static overlays like sport scoreboards or security-camera timestamps. |
None
|
Returns:
| Type | Description |
|---|---|
CoordinatesTransformation or None
|
A coordinate transformation that can map coordinates on this
frame to absolute coordinates and vice versa, or |
Source code in norfair/camera_motion.py
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 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 | |
See also#
- Tracker — consumes the
coord_transformationsreturned here. - Drawing —
FixedCameraanddraw_absolute_gridpair withMotionEstimatorfor visualization.