00001 #ifndef VSLAM_SYSTEM_VSLAM_H
00002 #define VSLAM_SYSTEM_VSLAM_H
00003
00004 #include <vslam_system/vo.h>
00005 #include <vslam_system/place_recognizer.h>
00006 #include <posest/pe3d.h>
00007 #include <posest/peh.h>
00008 #include <sba/sba.h>
00009 #include <frame_common/frame.h>
00010
00011 namespace vslam {
00012
00015 class VslamSystem
00016 {
00017 public:
00018 frame_common::FrameProc frame_processor_;
00019
00020 std::vector<frame_common::Frame, Eigen::aligned_allocator<frame_common::Frame> > frames_;
00021 sba::SysSBA sba_;
00022 vslam::voSt vo_;
00023 vslam::PlaceRecognizer place_recognizer_;
00024 pe::PoseEstimator3d pose_estimator_;
00025
00027 boost::shared_ptr<frame_common::PointcloudProc> pointcloud_processor_;
00029 std::vector<cv::DMatch> pointcloud_matches_;
00030 bool doPointPlane;
00031
00032 public:
00039 VslamSystem(const std::string& vocab_tree_file, const std::string& vocab_weights_file,
00040 int min_keyframe_inliers=0, double min_keyframe_distance=0.2,
00041 double min_keyframe_angle=0.1);
00042
00050 bool addFrame(const frame_common::CamParams& camera_parameters,
00051 const cv::Mat& left, const cv::Mat& right, int nfrac = 0,
00052 bool setPointCloud = false);
00053
00061 bool addFrame(const frame_common::CamParams& camera_parameters,
00062 const cv::Mat& left, const cv::Mat& right,
00063 const pcl::PointCloud<pcl::PointXYZRGB>& ptcloud, int nfrac = 0);
00064
00065 void addKeyframe(frame_common::Frame& next_frame);
00066
00069 void refine(int initial_runs=3);
00070
00071 int prInliers;
00072 int numPRs;
00073 int nSkip;
00074
00075
00076 void setPlaceInliers(int n) { prInliers = n; };
00077 void setPRSkip(int n) { nSkip = n; };
00078 void setKeyInliers(int n) { vo_.mininls = n; };
00079 void setKeyDist(double n) { vo_.mindist = n; };
00080 void setKeyAngle(double n) { vo_.minang = n; };
00081 void setNDisp(int n) { frame_processor_.ndisp = n; };
00082 void setPRRansacIt(int n) { pose_estimator_.numRansac = n; };
00083 void setPRPolish(bool n) { pose_estimator_.polish = n; };
00084 void setVORansacIt(int n) { vo_.pose_estimator_->numRansac = n; };
00085 void setVOPolish(bool n) { vo_.pose_estimator_->polish = n; };
00086 void setPRWindow(int x, int y) { pose_estimator_.wx = x; pose_estimator_.wy = y; };
00087 void setVOWindow(int x, int y) { vo_.pose_estimator_->wx = x; vo_.pose_estimator_->wy = y; };
00088 void setHuber(double x) { sba_.huber = x; vo_.sba.huber = x; }
00089
00090
00091
00093 void setPointcloudProc(boost::shared_ptr<frame_common::PointcloudProc> proc)
00094 {
00095 pointcloud_processor_ = proc;
00096 vo_.pointcloud_proc_ = proc;
00097 }
00098 };
00099
00100 }
00101
00102 #endif