39 #ifndef INCLUDE_OKVIS_OPENGV_FRAMEABSOLUTEPOSESACPROBLEM_HPP_ 
   40 #define INCLUDE_OKVIS_OPENGV_FRAMEABSOLUTEPOSESACPROBLEM_HPP_ 
   42 #include <opengv/types.hpp> 
   43 #include <opengv/absolute_pose/methods.hpp> 
   44 #pragma GCC diagnostic push 
   45 #pragma GCC diagnostic ignored "-Wunused-parameter" 
   46 #include <opengv/sac_problems/absolute_pose/AbsolutePoseSacProblem.hpp> 
   47 #pragma GCC diagnostic pop 
   58 namespace sac_problems {
 
   62 namespace absolute_pose {
 
   74   typedef AbsolutePoseSacProblem 
base_t;
 
   77   using base_t::adapter_t;
 
   79   using base_t::algorithm_t;
 
   81   using base_t::model_t;
 
   90       : base_t(adapter, algorithm),
 
   92             *static_cast<opengv::absolute_pose::FrameNoncentralAbsoluteAdapter*>(&_adapter)) {
 
   95         dynamic_cast<opengv::absolute_pose::FrameNoncentralAbsoluteAdapter*>(&_adapter),
 
   96         "only opengv::absolute_pose::FrameNoncentralAbsoluteAdapter supported");
 
  108                               const std::vector<int> & indices)
 
  109       : 
base_t(adapter, algorithm, indices),
 
  111             *static_cast<opengv::absolute_pose::FrameNoncentralAbsoluteAdapter*>(&_adapter)) {
 
  114         dynamic_cast<opengv::absolute_pose::FrameNoncentralAbsoluteAdapter*>(&_adapter),
 
  115         "only opengv::absolute_pose::FrameNoncentralAbsoluteAdapter supported");
 
  130                                            const std::vector<int> & indices,
 
  131                                            std::vector<double> & scores)
 const {
 
  135     model_t inverseSolution;
 
  136     inverseSolution.block<3, 3>(0, 0) = model.block<3, 3>(0, 0).transpose();
 
  137     inverseSolution.col(3) = -inverseSolution.block<3, 3>(0, 0) * model.col(3);
 
  139     Eigen::Matrix<double, 4, 1> p_hom;
 
  142     for (
size_t i = 0; i < indices.size(); i++) {
 
  148       point_t bodyReprojection = inverseSolution * p_hom;
 
  152       reprojection = reprojection / reprojection.norm();
 
  155       point_t error = (reprojection
 
  157       double error_squared = error.transpose() * error;
 
double getSigmaAngle(size_t index)
Obtain the angular standard deviation in [rad]. 
Definition: FrameNoncentralAbsoluteAdapter.cpp:198
virtual ~FrameAbsolutePoseSacProblem()
Definition: FrameAbsolutePoseSacProblem.hpp:118
virtual opengv::rotation_t getCamRotation(size_t index) const 
Retrieve the rotation from a camera of a correspondence to the viewpoint origin. 
Definition: FrameNoncentralAbsoluteAdapter.cpp:185
Header file for the FrameNoncentralAbsoluteAdapter class. 
virtual opengv::bearingVector_t getBearingVector(size_t index) const 
Retrieve the bearing vector of a correspondence. 
Definition: FrameNoncentralAbsoluteAdapter.cpp:165
#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. 
virtual opengv::point_t getPoint(size_t index) const 
Retrieve the world point of a correspondence. 
Definition: FrameNoncentralAbsoluteAdapter.cpp:172
virtual void getSelectedDistancesToModel(const model_t &model, const std::vector< int > &indices, std::vector< double > &scores) const 
Compute the distances of all samples whith respect to given model coefficients. 
Definition: FrameAbsolutePoseSacProblem.hpp:129
Adapter for absolute pose RANSAC (3D2D) with non-central cameras, i.e. could be a multi-camera-setup...
Definition: FrameNoncentralAbsoluteAdapter.hpp:63
FrameAbsolutePoseSacProblem(adapter_t &adapter, algorithm_t algorithm, const std::vector< int > &indices)
Constructor. 
Definition: FrameAbsolutePoseSacProblem.hpp:107
AbsolutePoseSacProblem base_t
Definition: FrameAbsolutePoseSacProblem.hpp:74
virtual opengv::translation_t getCamOffset(size_t index) const 
Retrieve the position of a camera of a correspondence seen from the viewpoint origin. 
Definition: FrameNoncentralAbsoluteAdapter.cpp:179
opengv::absolute_pose::FrameNoncentralAbsoluteAdapter & adapterDerived_
The adapter holding the bearing, correspondences etc. 
Definition: FrameAbsolutePoseSacProblem.hpp:165
Provides functions for fitting an absolute-pose model to a set of bearing-vector to point corresponde...
Definition: FrameAbsolutePoseSacProblem.hpp:70
#define OKVIS_ASSERT_TRUE(exceptionType, condition, message)
Definition: assert_macros.hpp:111