[−][src]Crate cv_geom
This module contains functions to perform various geometric algorithms.
Triangulation of a point with a given camera transformation
In this problem we have a RelativeCameraPose
and two Bearing
.
We want to find the point of intersection from the two cameras in camera A's space.
p
the point we are trying to triangulatea
the normalized keypoint on camera Ab
the normalized keypoint on camera BO
the optical center of a camera@
the virtual image plane
@
@
p--------b--------O
/ @
/ @
/ @
/ @
@@@@@@@a@@@@@
/
/
/
O
//! Solutions to this problem:
- [
make_one_pose_dlt_triangulator
]
Translation along a bearing given one prior depth
This problem consumes a direction to translate along, a from
CameraPoint
,
and a to
Bearing
coordinate.
t
thetranslation
bearing vectora
thefrom
pointb
theto
epipolar pointO
the optical center@
the virtual image plane
t<---a
/
/
@@@b@@@/@@@@@
| /
| /
|/
O
The from
coordinate is the relative 3d coordinate in camera space before translation.
The to
coordinate is just a normalized keypoint that we wish to find the optimal translation
to reproject as close as possible to.
The translation
is a vector which will be scaled (multiplied) by the return value to
get the actual 3d translation to move from from
to to
in 3d space.
Solutions to this problem:
- [
triangulate_bearing_intersection
] - [
triangulate_bearing_reproject
]
It is recommended to use [triangulate_bearing_reproject
], as it is incredibly cheap to compute.
Triangulation from variable number of camera poses
In this problem you have several camera poses and bearing pairs, where each bearing is an observation on the image produced from the corresponding camera pose. The desired output is a triangulated point.
- [
triangulate_least_square_reprojection_error
]
Structs
BearingIntersectionTriangulator | This solves the translation along a bearing triangulation assuming that there is a perfect intersection. |
BearingMinimizeReprojectionErrorTriangulator | This solves the translation along a bearing triangulation by minimizing the reprojection error. |
MinimalSquareReprojectionErrorTriangulator | This solves triangulation problems by simply minimizing the squared reprojection error of all observances. |
RelativeDltTriangulator | Based on algorithm 12 from "Multiple View Geometry in Computer Vision, Second Edition" |