Settings.h 7.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  5. * Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  6. *
  7. * ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
  8. * License as published by the Free Software Foundation, either version 3 of the License, or
  9. * (at your option) any later version.
  10. *
  11. * ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
  12. * the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  13. * GNU General Public License for more details.
  14. *
  15. * You should have received a copy of the GNU General Public License along with ORB-SLAM3.
  16. * If not, see <http://www.gnu.org/licenses/>.
  17. */
  18. #ifndef ORB_SLAM3_SETTINGS_H
  19. #define ORB_SLAM3_SETTINGS_H
  20. // Flag to activate the measurement of time in each process (track,localmap, place recognition).
  21. //#define REGISTER_TIMES
  22. #include "CameraModels/GeometricCamera.h"
  23. #include <unistd.h>
  24. #include <stdio.h>
  25. #include <stdlib.h>
  26. #include <string>
  27. namespace ORB_SLAM3 {
  28. class System;
  29. //TODO: change to double instead of float
  30. class Settings {
  31. public:
  32. /*
  33. * Enum for the different camera types implemented
  34. */
  35. enum CameraType {
  36. PinHole = 0,
  37. Rectified = 1,
  38. KannalaBrandt = 2
  39. };
  40. /*
  41. * Delete default constructor
  42. */
  43. Settings() = delete;
  44. /*
  45. * Constructor from file
  46. */
  47. Settings(const std::string &configFile, const int& sensor);
  48. /*
  49. * Ostream operator overloading to dump settings to the terminal
  50. */
  51. friend std::ostream &operator<<(std::ostream &output, const Settings &s);
  52. /*
  53. * Getter methods
  54. */
  55. CameraType cameraType() {return cameraType_;}
  56. GeometricCamera* camera1() {return calibration1_;}
  57. GeometricCamera* camera2() {return calibration2_;}
  58. cv::Mat camera1DistortionCoef() {return cv::Mat(vPinHoleDistorsion1_.size(),1,CV_32F,vPinHoleDistorsion1_.data());}
  59. cv::Mat camera2DistortionCoef() {return cv::Mat(vPinHoleDistorsion2_.size(),1,CV_32F,vPinHoleDistorsion1_.data());}
  60. Sophus::SE3f Tlr() {return Tlr_;}
  61. float bf() {return bf_;}
  62. float b() {return b_;}
  63. float thDepth() {return thDepth_;}
  64. bool needToUndistort() {return bNeedToUndistort_;}
  65. cv::Size newImSize() {return newImSize_;}
  66. float fps() {return fps_;}
  67. bool rgb() {return bRGB_;}
  68. bool needToResize() {return bNeedToResize1_;}
  69. bool needToRectify() {return bNeedToRectify_;}
  70. float noiseGyro() {return noiseGyro_;}
  71. float noiseAcc() {return noiseAcc_;}
  72. float gyroWalk() {return gyroWalk_;}
  73. float accWalk() {return accWalk_;}
  74. float imuFrequency() {return imuFrequency_;}
  75. Sophus::SE3f Tbc() {return Tbc_;}
  76. bool insertKFsWhenLost() {return insertKFsWhenLost_;}
  77. float depthMapFactor() {return depthMapFactor_;}
  78. int nFeatures() {return nFeatures_;}
  79. int nLevels() {return nLevels_;}
  80. float initThFAST() {return initThFAST_;}
  81. float minThFAST() {return minThFAST_;}
  82. float scaleFactor() {return scaleFactor_;}
  83. float keyFrameSize() {return keyFrameSize_;}
  84. float keyFrameLineWidth() {return keyFrameLineWidth_;}
  85. float graphLineWidth() {return graphLineWidth_;}
  86. float pointSize() {return pointSize_;}
  87. float cameraSize() {return cameraSize_;}
  88. float cameraLineWidth() {return cameraLineWidth_;}
  89. float viewPointX() {return viewPointX_;}
  90. float viewPointY() {return viewPointY_;}
  91. float viewPointZ() {return viewPointZ_;}
  92. float viewPointF() {return viewPointF_;}
  93. float imageViewerScale() {return imageViewerScale_;}
  94. std::string atlasLoadFile() {return sLoadFrom_;}
  95. std::string atlasSaveFile() {return sSaveto_;}
  96. float thFarPoints() {return thFarPoints_;}
  97. cv::Mat M1l() {return M1l_;}
  98. cv::Mat M2l() {return M2l_;}
  99. cv::Mat M1r() {return M1r_;}
  100. cv::Mat M2r() {return M2r_;}
  101. private:
  102. template<typename T>
  103. T readParameter(cv::FileStorage& fSettings, const std::string& name, bool& found,const bool required = true){
  104. cv::FileNode node = fSettings[name];
  105. if(node.empty()){
  106. if(required){
  107. std::cerr << name << " required parameter does not exist, aborting..." << std::endl;
  108. exit(-1);
  109. }
  110. else{
  111. std::cerr << name << " optional parameter does not exist..." << std::endl;
  112. found = false;
  113. return T();
  114. }
  115. }
  116. else{
  117. found = true;
  118. return (T) node;
  119. }
  120. }
  121. void readCamera1(cv::FileStorage& fSettings);
  122. void readCamera2(cv::FileStorage& fSettings);
  123. void readImageInfo(cv::FileStorage& fSettings);
  124. void readIMU(cv::FileStorage& fSettings);
  125. void readRGBD(cv::FileStorage& fSettings);
  126. void readORB(cv::FileStorage& fSettings);
  127. void readViewer(cv::FileStorage& fSettings);
  128. void readLoadAndSave(cv::FileStorage& fSettings);
  129. void readOtherParameters(cv::FileStorage& fSettings);
  130. void precomputeRectificationMaps();
  131. int sensor_;
  132. CameraType cameraType_; //Camera type
  133. /*
  134. * Visual stuff
  135. */
  136. GeometricCamera* calibration1_, *calibration2_; //Camera calibration
  137. GeometricCamera* originalCalib1_, *originalCalib2_;
  138. std::vector<float> vPinHoleDistorsion1_, vPinHoleDistorsion2_;
  139. cv::Size originalImSize_, newImSize_;
  140. float fps_;
  141. bool bRGB_;
  142. bool bNeedToUndistort_;
  143. bool bNeedToRectify_;
  144. bool bNeedToResize1_, bNeedToResize2_;
  145. Sophus::SE3f Tlr_;
  146. float thDepth_;
  147. float bf_, b_;
  148. /*
  149. * Rectification stuff
  150. */
  151. cv::Mat M1l_, M2l_;
  152. cv::Mat M1r_, M2r_;
  153. /*
  154. * Inertial stuff
  155. */
  156. float noiseGyro_, noiseAcc_;
  157. float gyroWalk_, accWalk_;
  158. float imuFrequency_;
  159. Sophus::SE3f Tbc_;
  160. bool insertKFsWhenLost_;
  161. /*
  162. * RGBD stuff
  163. */
  164. float depthMapFactor_;
  165. /*
  166. * ORB stuff
  167. */
  168. int nFeatures_;
  169. float scaleFactor_;
  170. int nLevels_;
  171. int initThFAST_, minThFAST_;
  172. /*
  173. * Viewer stuff
  174. */
  175. float keyFrameSize_;
  176. float keyFrameLineWidth_;
  177. float graphLineWidth_;
  178. float pointSize_;
  179. float cameraSize_;
  180. float cameraLineWidth_;
  181. float viewPointX_, viewPointY_, viewPointZ_, viewPointF_;
  182. float imageViewerScale_;
  183. /*
  184. * Save & load maps
  185. */
  186. std::string sLoadFrom_, sSaveto_;
  187. /*
  188. * Other stuff
  189. */
  190. float thFarPoints_;
  191. };
  192. };
  193. #endif //ORB_SLAM3_SETTINGS_H