Params.h
Go to the documentation of this file.
00001 /*
00002  * Params.h
00003  *
00004  *  Created on: Jul 21, 2010
00005  *      Author: sweiss
00006  */
00007 
00008 #ifndef PARAMS_H_
00009 #define PARAMS_H_
00010 
00011 #include <ptam/PtamParamsConfig.h>
00012 #include <string.h>
00013 #include <ros/ros.h>
00014 #include <XmlRpcValue.h>
00015 
00016 #include <dynamic_reconfigure/server.h>
00017 #include <ptam/Params.h>
00018 
00019 typedef dynamic_reconfigure::Server<ptam::PtamParamsConfig> PtamParamsReconfigureServer;
00020 typedef ptam::PtamParamsConfig VarParams;
00021 
00022 class FixParams
00023 {
00024 public:
00025   int ImageSizeX;
00026   int ImageSizeY;
00027   int ARBuffer_width;
00028   int ARBuffer_height;
00029   double WiggleScale;
00030   std::string BundleMEstimator;
00031   std::string TrackerMEstimator;
00032   double MinTukeySigma;
00033   int CandidateMinSTScore;
00034   double Cam_fx;
00035   double Cam_fy;
00036   double Cam_cx;
00037   double Cam_cy;
00038   double Cam_s;
00039   double MaxFoV;
00040   double Calibrator_BlurSigma;
00041   double Calibrator_MeanGate;
00042   int Calibrator_MinCornersForGrabbedImage;
00043   bool Calibrator_Optimize;
00044   bool Calibrator_Show;
00045   bool Calibrator_NoDistortion;
00046   double CameraCalibrator_MaxStepDistFraction;
00047   int CameraCalibrator_CornerPatchSize;
00048   bool GLWindowMenu_Enable;
00049   int GLWindowMenu_mgvnMenuItemWidth;
00050   int GLWindowMenu_mgvnMenuTextOffset;
00051   int InitLevel;
00052   std::string parent_frame;
00053   bool gui;
00054   void readFixParams();
00055 };
00056 
00057 class PtamParameters{
00058 private:
00059   ptam::PtamParamsConfig mVarParams;
00060   FixParams mFixParams;
00061 
00062   PtamParamsReconfigureServer *mpPtamParamsReconfigureServer;
00063 
00064   void ptamParamsConfig(ptam::PtamParamsConfig & config, uint32_t level){
00065     mVarParams = config;
00066   };
00067   static PtamParameters* inst_;
00068   PtamParameters()
00069   {
00070     mpPtamParamsReconfigureServer = new PtamParamsReconfigureServer(ros::NodeHandle("~"));
00071     PtamParamsReconfigureServer::CallbackType PtamParamCall = boost::bind(&PtamParameters::ptamParamsConfig, this, _1, _2);
00072     mpPtamParamsReconfigureServer->setCallback(PtamParamCall);
00073 
00074     mFixParams.readFixParams();
00075   }
00076   ~PtamParameters(){
00077     delete inst_;
00078     inst_ = NULL;
00079   }
00080 public:
00081   static const ptam::PtamParamsConfig& varparams(){
00082     if(!inst_){
00083       inst_ = new PtamParameters;
00084     }
00085     return inst_->mVarParams;
00086   }
00087   static const FixParams& fixparams(){
00088     if(!inst_){
00089       inst_ = new PtamParameters;
00090     }
00091     return inst_->mFixParams;
00092   }
00093 };
00094 
00095 #endif /* PARAMS_H_ */


ptam
Author(s): Stephan Weiss, Markus Achtelik, Simon Lynen
autogenerated on Tue Jan 7 2014 11:12:22