OKVIS
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
FrameNoncentralAbsoluteAdapter.hpp
Go to the documentation of this file.
1 /*********************************************************************************
2  * OKVIS - Open Keyframe-based Visual-Inertial SLAM
3  * Copyright (c) 2015, Autonomous Systems Lab / ETH Zurich
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright notice,
9  * this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright notice,
11  * this list of conditions and the following disclaimer in the documentation
12  * and/or other materials provided with the distribution.
13  * * Neither the name of Autonomous Systems Lab / ETH Zurich nor the names of
14  * its contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Created on: Mar 6, 2013
30  * Author: Stefan Leutenegger (s.leutenegger@imperial.ac.uk)
31  *********************************************************************************/
32 
39 #ifndef INCLUDE_OKVIS_OPENGV_FRAMENONCENTRALABSOLUTEADAPTER_HPP_
40 #define INCLUDE_OKVIS_OPENGV_FRAMENONCENTRALABSOLUTEADAPTER_HPP_
41 
42 #include <stdlib.h>
43 #include <vector>
44 #include <memory>
45 #include <opengv/types.hpp>
46 #include <opengv/absolute_pose/NoncentralAbsoluteAdapter.hpp>
48 #include <okvis/FrameTypedefs.hpp>
49 #include <okvis/Estimator.hpp>
51 
55 namespace opengv {
59 namespace absolute_pose {
60 
63 class FrameNoncentralAbsoluteAdapter : public AbsoluteAdapterBase {
64  private:
65  using AbsoluteAdapterBase::_t;
66  using AbsoluteAdapterBase::_R;
67 
68  public:
69  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
70  OKVIS_DEFINE_EXCEPTION(Exception,std::runtime_error)
71 
72 
73  typedef std::vector<int> matches_t;
74 
82  const okvis::Estimator & estimator,
83  const okvis::cameras::NCameraSystem & nCameraSystem,
84  std::shared_ptr<okvis::MultiFrame> frame);
85 
87  }
88 
91 
97  virtual opengv::bearingVector_t getBearingVector(size_t index) const;
98 
106  virtual opengv::translation_t getCamOffset(size_t index) const;
107 
115  virtual opengv::rotation_t getCamRotation(size_t index) const;
116 
122  virtual opengv::point_t getPoint(size_t index) const;
123 
130  virtual size_t getNumberCorrespondences() const;
131 
133 
134  // lestefan: some additional accessors
140  int camIndex(size_t index) const {return camIndices_.at(index);}
141 
147  int keypointIndex(size_t index) const {return keypointIndices_.at(index);}
148 
155  virtual double getWeight(size_t) const {
156  return 1.0;
157  } // TODO : figure out if needed...
158 
159  // custom:
165  double getSigmaAngle(size_t index);
166 
167  private:
169  opengv::bearingVectors_t bearingVectors_;
170 
172  opengv::points_t points_;
173 
175  std::vector<size_t> camIndices_;
176 
178  std::vector<size_t> keypointIndices_;
179 
181  opengv::translations_t camOffsets_;
182 
184  opengv::rotations_t camRotations_;
185 
187  std::vector<double> sigmaAngles_;
188 
189 };
190 
191 }
192 }
193 
194 #endif /* INCLUDE_OKVIS_OPENGV_FRAMENONCENTRALABSOLUTEADAPTER_HPP_ */
Header file for the NCameraSystem class.
double getSigmaAngle(size_t index)
Obtain the angular standard deviation in [rad].
Definition: FrameNoncentralAbsoluteAdapter.cpp:198
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef std::vector< int > matches_t
type for describing matches.
Definition: FrameNoncentralAbsoluteAdapter.hpp:73
opengv::bearingVectors_t bearingVectors_
The bearing vectors of the correspondences.
Definition: FrameNoncentralAbsoluteAdapter.hpp:169
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
opengv::rotations_t camRotations_
The rotation of the cameras to the viewpoint origin.
Definition: FrameNoncentralAbsoluteAdapter.hpp:184
int keypointIndex(size_t index) const
Get the keypoint index for a specific correspondence.
Definition: FrameNoncentralAbsoluteAdapter.hpp:147
std::vector< size_t > keypointIndices_
The keypoint indices of the correspondences.
Definition: FrameNoncentralAbsoluteAdapter.hpp:178
std::vector< double > sigmaAngles_
The standard deviations of the bearing vectors in [rad].
Definition: FrameNoncentralAbsoluteAdapter.hpp:187
opengv::points_t points_
The world coordinates of the correspondences.
Definition: FrameNoncentralAbsoluteAdapter.hpp:172
int camIndex(size_t index) const
Get the camera index for a specific correspondence.
Definition: FrameNoncentralAbsoluteAdapter.hpp:140
virtual opengv::bearingVector_t getBearingVector(size_t index) const
Retrieve the bearing vector of a correspondence.
Definition: FrameNoncentralAbsoluteAdapter.cpp:165
virtual size_t getNumberCorrespondences() const
Get the number of correspondences. These are keypoints that have a corresponding landmark which is ad...
Definition: FrameNoncentralAbsoluteAdapter.cpp:193
#define OKVIS_DEFINE_EXCEPTION(exceptionName, exceptionParent)
Macro for defining an exception with a given parent.
Definition: assert_macros.hpp:52
virtual opengv::point_t getPoint(size_t index) const
Retrieve the world point of a correspondence.
Definition: FrameNoncentralAbsoluteAdapter.cpp:172
Adapter for absolute pose RANSAC (3D2D) with non-central cameras, i.e. could be a multi-camera-setup...
Definition: FrameNoncentralAbsoluteAdapter.hpp:63
std::vector< size_t > camIndices_
The camera indices of the correspondences.
Definition: FrameNoncentralAbsoluteAdapter.hpp:175
Header file for the Estimator class. This does all the backend work.
Header file for the Transformation class.
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::translations_t camOffsets_
The position of the cameras seen from the viewpoint origin.
Definition: FrameNoncentralAbsoluteAdapter.hpp:181
virtual double getWeight(size_t) const
Retrieve the weight of a correspondence. The weight is supposed to reflect the quality of a correspon...
Definition: FrameNoncentralAbsoluteAdapter.hpp:155
This file contains useful typedefs and structs related to frames.