Params.cpp
Go to the documentation of this file.
00001 /*
00002  * Params.cpp
00003  *
00004  *  Created on: Sep 17, 2010
00005  *      Author: asl
00006  */
00007 
00008 #include <ptam/Params.h>
00009 
00010 
00011 void FixParams::readFixParams()
00012 {
00013   ros::NodeHandle nh("~");
00014 
00015   // kill program, if we don't have a camera calibration
00016   bool have_calibration = true;
00017   have_calibration = have_calibration && nh.getParam("Cam_fx", Cam_fx);
00018   have_calibration = have_calibration && nh.getParam("Cam_fy", Cam_fy);
00019   have_calibration = have_calibration && nh.getParam("Cam_cx", Cam_cx);
00020   have_calibration = have_calibration && nh.getParam("Cam_cy", Cam_cy);
00021   have_calibration = have_calibration && nh.getParam("Cam_s", Cam_s);
00022 
00023   if (!have_calibration)
00024   {
00025     ROS_ERROR("Camera calibration is missing!");
00026     //    ROS_BREAK();
00027   }
00028 
00029   nh.param("ImageSizeX", ImageSizeX, 640);
00030   nh.param("ImageSizeY", ImageSizeY, 480);
00031   nh.param("ARBuffer_width", ARBuffer_width, 1200);
00032   nh.param("ARBuffer_height", ARBuffer_height, 900);
00033   nh.param("WiggleScale", WiggleScale, 0.1);
00034   nh.param("BundleMEstimator", BundleMEstimator, std::string("Tukey"));
00035   nh.param("TrackerMEstimator", TrackerMEstimator, std::string("Tukey"));
00036   nh.param("MinTukeySigma", MinTukeySigma, 0.4);
00037   nh.param("CandidateMinSTScore", CandidateMinSTScore, 70);
00038   //    nh.param("Cam_fx", Cam_fx,0.392);
00039   //    nh.param("Cam_fy", Cam_fy,0.613);
00040   //    nh.param("Cam_cx", Cam_cx,0.484);
00041   //    nh.param("Cam_cy", Cam_cy,0.476);
00042   //    nh.param("Cam_s", Cam_s,0.967);
00043   nh.param("Calibrator_BlurSigma", Calibrator_BlurSigma, 1.0);
00044   nh.param("Calibrator_MeanGate", Calibrator_MeanGate, 10.0);
00045   nh.param("Calibrator_MinCornersForGrabbedImage", Calibrator_MinCornersForGrabbedImage, 20);
00046   nh.param("Calibrator_Optimize", Calibrator_Optimize, false);
00047   nh.param("Calibrator_Show", Calibrator_Show, false);
00048   nh.param("Calibrator_NoDistortion", Calibrator_NoDistortion, false);
00049   nh.param("CameraCalibrator_MaxStepDistFraction", CameraCalibrator_MaxStepDistFraction, 0.3);
00050   nh.param("CameraCalibrator_CornerPatchSize", CameraCalibrator_CornerPatchSize, 20);
00051   nh.param("GLWindowMenu_Enable", GLWindowMenu_Enable, true);
00052   nh.param("GLWindowMenu_mgvnMenuItemWidth", GLWindowMenu_mgvnMenuItemWidth, 90);
00053   nh.param("GLWindowMenu_mgvnMenuTextOffset", GLWindowMenu_mgvnMenuTextOffset, 20);
00054   nh.param("InitLevel", InitLevel, 1);
00055   nh.param("parent_frame", parent_frame, std::string("world"));
00056   nh.param("gui", gui, false);
00057   nh.param("MaxFoV", MaxFoV, 130.0);
00058 }
00059 ;
00060 PtamParameters* PtamParameters::inst_ = NULL;


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