The ProbabilisticStereoTriangulator class.
More...
#include <ProbabilisticStereoTriangulator.hpp>
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | ProbabilisticStereoTriangulator (double pixelSigma=0.5) |
| Default constructor; make sure to call resetFrames before triangulation! More...
|
|
| ProbabilisticStereoTriangulator (std::shared_ptr< okvis::MultiFrame > frameA_ptr, std::shared_ptr< okvis::MultiFrame > frameB_ptr, size_t camIdA, size_t camIdB, const okvis::kinematics::Transformation &T_AB, const Eigen::Matrix< double, 6, 6 > &UOplus, double pixelSigma=0.5) |
| Constructor to set frames and relative transformation. More...
|
|
void | resetFrames (std::shared_ptr< okvis::MultiFrame > frameA_ptr, std::shared_ptr< okvis::MultiFrame > frameB_ptr, size_t camIdA, size_t camIdB, const okvis::kinematics::Transformation &T_AB, const Eigen::Matrix< double, 6, 6 > &UOplus) |
| Reset frames and relative transformation. More...
|
|
| ~ProbabilisticStereoTriangulator () |
| Default destructor. More...
|
|
bool | stereoTriangulate (size_t keypointIdxA, size_t keypointIdxB, Eigen::Vector4d &outHomogeneousPoint_A, bool &outCanBeInitializedInaccuarate, double sigmaRay=-1.0) const |
| Triangulation. More...
|
|
bool | stereoTriangulate (size_t keypointIdxA, size_t keypointIdxB, Eigen::Vector4d &outHomogeneousPoint_A, Eigen::Matrix3d &outPointUOplus_A, bool &outCanBeInitialized, double sigmaRay=-1.0) const |
| Triangulation. More...
|
|
void | getUncertainty (size_t keypointIdxA, size_t keypointIdxB, const Eigen::Vector4d &homogeneousPoint_A, Eigen::Matrix3d &outPointUOplus_A, bool &outCanBeInitialized) const |
| Get triangulation uncertainty. More...
|
|
template<class CAMERA_GEOMETRY_T>
class okvis::triangulation::ProbabilisticStereoTriangulator< CAMERA_GEOMETRY_T >
The ProbabilisticStereoTriangulator class.
- Template Parameters
-
template<class CAMERA_GEOMETRY_T >
Default constructor; make sure to call resetFrames before triangulation!
- Parameters
-
pixelSigma | A (conservative) estimate of the pixel one-sigma uncertainty in the keypoint location. |
template<class CAMERA_GEOMETRY_T >
Constructor to set frames and relative transformation.
- Parameters
-
frameA_ptr | First multiframe. |
frameB_ptr | Second multiframe. |
camIdA | Camera ID for first frame. |
camIdB | Camera ID for second frame. |
T_AB | Relative transformation from frameA to frameB. |
UOplus | Oplus-type uncertainty of T_AB. |
pixelSigma | A (conservative) estimate of the pixel one-sigma uncertainty in the keypoint location. |
template<class CAMERA_GEOMETRY_T >
template<class CAMERA_GEOMETRY_T >
Compute the reprojection error.
- Parameters
-
[in] | frame | Multiframe. |
[in] | camId | Camera ID. |
[in] | keypointId | ID of keypoint to calculate error for. |
[in] | homogeneousPoint | Homogeneous coordinates of point to calculate error for |
[out] | outError | Reprojection error. |
- Returns
- True if reprojection was successful.
template<class CAMERA_GEOMETRY_T >
Get triangulation uncertainty.
- Parameters
-
[in] | keypointIdxA | Index of keypoint to be triangulated in frame A. |
[in] | keypointIdxB | Index of keypoint to be triangulated in frame B. |
[in] | homogeneousPoint_A | Input triangulated point in A-coordinates. |
[out] | outPointUOplus_A | Output uncertainty, represented w.r.t. ceres disturbance, in A-coordinates. |
[out] | outCanBeInitialized | Whether or not the triangulation can be considered initialized. |
template<class CAMERA_GEOMETRY_T >
Reset frames and relative transformation.
- Parameters
-
frameA_ptr | First multiframe. |
frameB_ptr | Second multiframe. |
camIdA | Camera ID for first frame. |
camIdB | Camera ID for second frame. |
T_AB | Relative transformation from frameA to frameB. |
UOplus | Oplus-type uncertainty of T_AB. |
template<class CAMERA_GEOMETRY_T >
Triangulation.
- Parameters
-
[in] | keypointIdxA | Index of keypoint to be triangulated in frame A. |
[in] | keypointIdxB | Index of keypoint to be triangulated in frame B. |
[out] | outHomogeneousPoint_A | Output triangulation in A-coordinates. |
[out] | outCanBeInitializedInaccuarate | This will be set to false, if it can certainly not be initialised (conservative, but inaccurate guess) |
[in] | sigmaRay | Ray uncertainty. |
- Returns
- 3-sigma consistency check result, in A-coordinates.
template<class CAMERA_GEOMETRY_T >
bool okvis::triangulation::ProbabilisticStereoTriangulator< CAMERA_GEOMETRY_T >::stereoTriangulate |
( |
size_t |
keypointIdxA, |
|
|
size_t |
keypointIdxB, |
|
|
Eigen::Vector4d & |
outHomogeneousPoint_A, |
|
|
Eigen::Matrix3d & |
outPointUOplus_A, |
|
|
bool & |
outCanBeInitialized, |
|
|
double |
sigmaRay = -1.0 |
|
) |
| const |
Triangulation.
- Parameters
-
[in] | keypointIdxA | Index of keypoint to be triangulated in frame A. |
[in] | keypointIdxB | Index of keypoint to be triangulated in frame B. |
[out] | outHomogeneousPoint_A | Output triangulation in A-coordinates. |
[out] | outPointUOplus_A | Output uncertainty, represented w.r.t. ceres disturbance, in A-coordinates. |
[out] | outCanBeInitialized | Whether or not the triangulation can be considered initialized. |
[in] | sigmaRay | Ray uncertainty. |
- Returns
- 3-sigma consistency check result.
template<class CAMERA_GEOMETRY_T>
template<class CAMERA_GEOMETRY_T>
template<class CAMERA_GEOMETRY_T>
template<class CAMERA_GEOMETRY_T>
template<class CAMERA_GEOMETRY_T>
template<class CAMERA_GEOMETRY_T>
Information matrix of pose and landmark.
template<class CAMERA_GEOMETRY_T>
template<class CAMERA_GEOMETRY_T>
template<class CAMERA_GEOMETRY_T>
template<class CAMERA_GEOMETRY_T>
template<class CAMERA_GEOMETRY_T>
template<class CAMERA_GEOMETRY_T>
Local copy of relative uncertainty.
The documentation for this class was generated from the following files: