41 #ifndef INCLUDE_OKVIS_TRIANGULATION_PROBABILISTICSTEREOTRIANGULATOR_HPP_
42 #define INCLUDE_OKVIS_TRIANGULATION_PROBABILISTICSTEREOTRIANGULATOR_HPP_
55 namespace triangulation {
61 template<
class CAMERA_GEOMETRY_T>
64 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
86 std::shared_ptr<okvis::MultiFrame> frameB_ptr,
87 size_t camIdA,
size_t camIdB,
89 const Eigen::Matrix<double, 6, 6>& UOplus,
90 double pixelSigma = 0.5);
101 void resetFrames(std::shared_ptr<okvis::MultiFrame> frameA_ptr,
102 std::shared_ptr<okvis::MultiFrame> frameB_ptr,
size_t camIdA,
104 const Eigen::Matrix<double, 6, 6>& UOplus);
120 Eigen::Vector4d & outHomogeneousPoint_A,
121 bool & outCanBeInitializedInaccuarate,
122 double sigmaRay = -1.0)
const;
135 Eigen::Vector4d & outHomogeneousPoint_A,
136 Eigen::Matrix3d & outPointUOplus_A,
137 bool & outCanBeInitialized,
138 double sigmaRay = -1.0)
const;
149 const Eigen::Vector4d & homogeneousPoint_A,
150 Eigen::Matrix3d& outPointUOplus_A,
151 bool & outCanBeInitialized)
const;
155 std::shared_ptr<okvis::MultiFrame>
frameA_;
178 Eigen::Matrix<double, 9, 9>
H_;
190 const std::shared_ptr<okvis::MultiFrame> &frame,
size_t camId,
191 size_t keypointId,
const Eigen::Vector4d& homogeneousPoint,
192 double& outError)
const;
The ProbabilisticStereoTriangulator class.
Definition: ProbabilisticStereoTriangulator.hpp:62
okvis::kinematics::Transformation T_AB_
Definition: ProbabilisticStereoTriangulator.hpp:167
size_t camIdB_
Camera ID for frame B.
Definition: ProbabilisticStereoTriangulator.hpp:163
~ProbabilisticStereoTriangulator()
Default destructor.
Definition: ProbabilisticStereoTriangulator.cpp:163
Header file for the PoseParameterBlock class.
Header file for the MultiFrame class.
void getUncertainty(size_t keypointIdxA, size_t keypointIdxB, const Eigen::Vector4d &homogeneousPoint_A, Eigen::Matrix3d &outPointUOplus_A, bool &outCanBeInitialized) const
Get triangulation uncertainty.
Definition: ProbabilisticStereoTriangulator.cpp:253
double sigmaRay_
Definition: ProbabilisticStereoTriangulator.hpp:154
::okvis::ceres::PoseParameterBlock poseB_
Definition: ProbabilisticStereoTriangulator.hpp:169
Eigen::Matrix< double, 6, 6 > UOplus_
Local copy of relative uncertainty.
Definition: ProbabilisticStereoTriangulator.hpp:175
Wraps the parameter block for a pose estimate.
Definition: PoseParameterBlock.hpp:52
std::shared_ptr< okvis::MultiFrame > frameA_
The multiframe A.
Definition: ProbabilisticStereoTriangulator.hpp:156
EIGEN_MAKE_ALIGNED_OPERATOR_NEW ProbabilisticStereoTriangulator(double pixelSigma=0.5)
Default constructor; make sure to call resetFrames before triangulation!
Definition: ProbabilisticStereoTriangulator.cpp:60
bool stereoTriangulate(size_t keypointIdxA, size_t keypointIdxB, Eigen::Vector4d &outHomogeneousPoint_A, bool &outCanBeInitializedInaccuarate, double sigmaRay=-1.0) const
Triangulation.
Definition: ProbabilisticStereoTriangulator.cpp:168
#define OKVIS_DEFINE_EXCEPTION(exceptionName, exceptionParent)
Macro for defining an exception with a given parent.
Definition: assert_macros.hpp:52
This file contains some useful assert macros.
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.
Definition: ProbabilisticStereoTriangulator.cpp:117
::okvis::ceres::PoseParameterBlock poseA_
Definition: ProbabilisticStereoTriangulator.hpp:168
bool computeReprojectionError4(const std::shared_ptr< okvis::MultiFrame > &frame, size_t camId, size_t keypointId, const Eigen::Vector4d &homogeneousPoint, double &outError) const
Compute the reprojection error.
Definition: ProbabilisticStereoTriangulator.cpp:359
Eigen::Matrix< double, 9, 9 > H_
Information matrix of pose and landmark.
Definition: ProbabilisticStereoTriangulator.hpp:178
::okvis::ceres::PoseParameterBlock extrinsics_
Definition: ProbabilisticStereoTriangulator.hpp:170
std::shared_ptr< okvis::MultiFrame > frameB_
The multiframe B.
Definition: ProbabilisticStereoTriangulator.hpp:158
size_t camIdA_
Camera ID for frame A.
Definition: ProbabilisticStereoTriangulator.hpp:161
This file contains useful typedefs and structs related to frames.
okvis::kinematics::Transformation T_BA_
Definition: ProbabilisticStereoTriangulator.hpp:171