OKVIS ROS
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
VioParametersReader.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: Jun 17, 2013
30  * Author: Stefan Leutenegger (s.leutenegger@imperial.ac.uk)
31  * Modified: Andreas Forster (an.forster@gmail.com)
32  *********************************************************************************/
33 
41 #ifndef INCLUDE_OKVIS_VIOPARAMETERSREADER_HPP_
42 #define INCLUDE_OKVIS_VIOPARAMETERSREADER_HPP_
43 
44 #include <string>
45 
46 #pragma GCC diagnostic push
47 #pragma GCC diagnostic ignored "-Wnon-virtual-dtor"
48 #include <opencv2/core/core.hpp>
49 #pragma GCC diagnostic pop
50 
51 #include <okvis/assert_macros.hpp>
52 #include <okvis/Parameters.hpp>
53 
55 namespace okvis {
56 
61  public:
62  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
63  OKVIS_DEFINE_EXCEPTION(Exception,std::runtime_error)
64 
65 
67 
72  VioParametersReader(const std::string& filename);
73 
75  virtual ~VioParametersReader() {}
76 
82  void readConfigFile(const std::string& filename);
83 
90  bool getParameters(okvis::VioParameters& parameters) const{
91  if(readConfigFile_)
92  parameters = vioParameters_;
93  return readConfigFile_;
94  }
95 
97  bool useDriver;
98 
99  std::shared_ptr<void> viSensor;
100 
101  protected:
102 
105  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
107  Eigen::Vector2d imageDimension;
108  Eigen::VectorXd distortionCoefficients;
109  Eigen::Vector2d focalLength;
110  Eigen::Vector2d principalPoint;
111  std::string distortionType;
112  };
113 
118 
126  bool parseBoolean(cv::FileNode node, bool& val) const;
127 
137  virtual bool getCameraCalibration(
138  std::vector<CameraCalibration,Eigen::aligned_allocator<CameraCalibration>> & calibrations,
139  cv::FileStorage& configurationFile);
140 
148  std::vector<CameraCalibration,Eigen::aligned_allocator<CameraCalibration>> & calibrations,
149  cv::FileNode cameraNode) const;
150 
157  std::vector<CameraCalibration,Eigen::aligned_allocator<CameraCalibration>> & calibrations) const;
158 
159 };
160 
161 }
162 
163 #endif /* INCLUDE_OKVIS_VIOPARAMETERSREADER_HPP_ */
virtual bool getCameraCalibration(std::vector< CameraCalibration, Eigen::aligned_allocator< CameraCalibration >> &calibrations, cv::FileStorage &configurationFile)
Get the camera calibration. This looks for the calibration in the configuration file first...
Definition: VioParametersReader.cpp:504
Eigen::Vector2d principalPoint
Principal point.
Definition: VioParametersReader.hpp:110
Struct that contains all the camera calibration information.
Definition: VioParametersReader.hpp:104
std::shared_ptr< void > viSensor
Definition: VioParametersReader.hpp:99
Eigen::Vector2d imageDimension
Image dimension. [pixels].
Definition: VioParametersReader.hpp:107
okvis::VioParameters vioParameters_
The parameters.
Definition: VioParametersReader.hpp:117
Eigen::VectorXd distortionCoefficients
Distortion Coefficients.
Definition: VioParametersReader.hpp:108
Eigen::Vector2d focalLength
Focal length.
Definition: VioParametersReader.hpp:109
A class that does homogeneous transformations. This relates a frame A and B: T_AB; it consists of tra...
Definition: Transformation.hpp:76
bool readConfigFile_
If readConfigFile() has been called at least once this is true.
Definition: VioParametersReader.hpp:115
#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 readConfigFile(const std::string &filename)
Read and parse a config file. To get the result call getParameters().
Definition: VioParametersReader.cpp:76
EIGEN_MAKE_ALIGNED_OPERATOR_NEW okvis::kinematics::Transformation T_SC
Transformation from camera to sensor (IMU) frame.
Definition: VioParametersReader.hpp:106
Struct to combine all parameters and settings.
Definition: Parameters.hpp:280
bool useDriver
Directly interface with driver without ROS message passing.
Definition: VioParametersReader.hpp:97
EIGEN_MAKE_ALIGNED_OPERATOR_NEW VioParametersReader()
The default constructor.
Definition: VioParametersReader.cpp:63
std::string distortionType
Distortion type. ('radialtangential' 'plumb_bob' 'equdistant')
Definition: VioParametersReader.hpp:111
bool getParameters(okvis::VioParameters &parameters) const
Get parameters.
Definition: VioParametersReader.hpp:90
bool parseBoolean(cv::FileNode node, bool &val) const
Parses booleans from a cv::FileNode. OpenCV sadly has no implementation like this.
Definition: VioParametersReader.cpp:470
bool getCalibrationViaConfig(std::vector< CameraCalibration, Eigen::aligned_allocator< CameraCalibration >> &calibrations, cv::FileNode cameraNode) const
Get the camera calibration via the configuration file.
Definition: VioParametersReader.cpp:531
This file contains struct definitions that encapsulate parameters and settings.
virtual ~VioParametersReader()
Trivial destructor.
Definition: VioParametersReader.hpp:75
bool getCalibrationViaVisensorAPI(std::vector< CameraCalibration, Eigen::aligned_allocator< CameraCalibration >> &calibrations) const
Get the camera calibrations via the visensor API.
Definition: VioParametersReader.cpp:600
This class reads and parses config file.
Definition: VioParametersReader.hpp:60