00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include <vslam_system/vslam.h>
00036 #include <cstdio>
00037
00038
00039 using namespace sba;
00040 using namespace pcl;
00041
00042 namespace vslam {
00043
00044 VslamSystem::VslamSystem(const std::string& vocab_tree_file, const std::string& vocab_weights_file,
00045 int min_keyframe_inliers, double min_keyframe_distance, double min_keyframe_angle)
00046 : frame_processor_(10),
00047 #ifdef HOWARD
00048 vo_(boost::shared_ptr<pe::PoseEstimator>(new pe::PoseEstimatorH(1000, true, 3.0, 4.0, 4.0, 0.025, 40, 17)),
00049 #else
00050 vo_(boost::shared_ptr<pe::PoseEstimator>(new pe::PoseEstimator3d(1000,true,6.0,8.0,8.0)),
00051 #endif
00052 40, 10, min_keyframe_inliers, min_keyframe_distance, min_keyframe_angle),
00053 place_recognizer_(vocab_tree_file, vocab_weights_file),
00054 pose_estimator_(5000, true, 10.0, 3.0, 3.0)
00055 {
00056 sba_.useCholmod(true);
00058 pose_estimator_.wx = 92;
00059 pose_estimator_.wy = 48;
00060
00061
00062
00063 prInliers = 200;
00064 numPRs = 0;
00065 nSkip = 20;
00066 doPointPlane = true;
00067 }
00068
00069 bool VslamSystem::addFrame(const frame_common::CamParams& camera_parameters,
00070 const cv::Mat& left, const cv::Mat& right, int nfrac,
00071 bool setPointCloud)
00072 {
00073
00074 frame_common::Frame next_frame;
00075 next_frame.setCamParams(camera_parameters);
00076 frame_processor_.setStereoFrame(next_frame, left, right, nfrac, setPointCloud);
00077 next_frame.frameId = sba_.nodes.size();
00078 #ifndef HOWARD
00079 next_frame.img = cv::Mat();
00080 next_frame.imgRight = cv::Mat();
00081 #endif
00082
00083 if (setPointCloud && pointcloud_processor_ && doPointPlane)
00084 {
00085 pointcloud_processor_->setPointcloud(next_frame, next_frame.dense_pointcloud);
00086 printf("[Pointcloud] set a pointcloud! %d\n", (int)next_frame.pointcloud.points.size());
00087 }
00088
00089
00090 bool is_keyframe = vo_.addFrame(next_frame);
00091
00092
00093 if (is_keyframe)
00094 {
00095 addKeyframe(next_frame);
00096 }
00097
00098 if (frames_.size() > 1 && vo_.pose_estimator_->inliers.size() < 40)
00099 std::cout << std::endl << "******** Bad image match: " << vo_.pose_estimator_->inliers.size()
00100 << " inliers" << std::endl << std::endl;
00101
00102 return is_keyframe;
00103 }
00104
00105 bool VslamSystem::addFrame(const frame_common::CamParams& camera_parameters,
00106 const cv::Mat& left, const cv::Mat& right,
00107 const pcl::PointCloud<PointXYZRGB>& ptcloud, int nfrac)
00108 {
00109
00110 frame_common::Frame next_frame;
00111 next_frame.setCamParams(camera_parameters);
00112 frame_processor_.setStereoFrame(next_frame, left, right, nfrac);
00113 next_frame.frameId = sba_.nodes.size();
00114 #ifndef HOWARD
00115 next_frame.img = cv::Mat();
00116 next_frame.imgRight = cv::Mat();
00117 #endif
00118 if (pointcloud_processor_ && doPointPlane)
00119 {
00120 pointcloud_processor_->setPointcloud(next_frame, ptcloud);
00121 printf("[Pointcloud] set a pointcloud! %d\n", (int)next_frame.pointcloud.points.size());
00122 }
00123
00124
00125 bool is_keyframe = vo_.addFrame(next_frame);
00126
00127
00128 if (is_keyframe)
00129 {
00130 addKeyframe(next_frame);
00131
00132 frames_.back().dense_pointcloud = ptcloud;
00133 }
00134
00135 if (frames_.size() > 1 && vo_.pose_estimator_->inliers.size() < 40)
00136 std::cout << std::endl << "******** Bad image match: " << std::endl << std::endl;
00137
00138 return is_keyframe;
00139 }
00140
00141 void VslamSystem::addKeyframe(frame_common::Frame& next_frame)
00142 {
00143 frames_.push_back(next_frame);
00144 vo_.doPointPlane = doPointPlane;
00145 vo_.transferLatestFrame(frames_, sba_);
00146
00147
00148 frame_common::Frame& transferred_frame = frames_.back();
00149
00150
00151
00152 std::vector<const frame_common::Frame*> place_matches;
00153 const size_t N = 5;
00154 place_recognizer_.findAndInsert(transferred_frame, transferred_frame.frameId, frames_, N, place_matches);
00155 printf("PLACEREC: Found %d matches\n", (int)place_matches.size());
00156
00157 for (int i = 0; i < (int)place_matches.size(); ++i)
00158 {
00159 frame_common::Frame& matched_frame = const_cast<frame_common::Frame&>(*place_matches[i]);
00160
00161
00162 if (matched_frame.frameId >= (int)frames_.size() - nSkip - 1)
00163 {
00164
00165 continue;
00166 }
00167
00168
00169 int inliers = pose_estimator_.estimate(matched_frame, transferred_frame);
00170 printf("\tMatch %d: %d inliers, frame index %d\n", i, inliers, matched_frame.frameId);
00171 if (inliers > prInliers)
00172 {
00173 numPRs++;
00174
00175 printf("\t[PlaceRec] Adding PR link between frames %d and %d\n", transferred_frame.frameId,
00176 matched_frame.frameId);
00177
00178
00179 Matrix<double,3,4> frame_to_world;
00180 Node &matched_node = sba_.nodes[matched_frame.frameId];
00181 Quaterniond fq0;
00182 fq0 = matched_node.qrot;
00183 transformF2W(frame_to_world, matched_node.trans, fq0);
00184
00185 addProjections(matched_frame, transferred_frame, frames_, sba_, pose_estimator_.inliers,
00186 frame_to_world, matched_frame.frameId, transferred_frame.frameId);
00187
00188
00189 if (pointcloud_processor_ && doPointPlane)
00190 {
00191 printf("\t[PlaceRec] Adding in point cloud projections\n");
00192 Matrix<double,3,4> f2w_transferred;
00193 Node &transferred_node = sba_.nodes[transferred_frame.frameId];
00194 transformF2W(f2w_transferred,transferred_node.trans,transferred_node.qrot);
00195 pointcloud_processor_->match(matched_frame, transferred_frame, pose_estimator_.trans, Quaterniond(pose_estimator_.rot), pointcloud_matches_);
00196 addPointCloudProjections(matched_frame, transferred_frame, sba_, pointcloud_matches_,
00197 frame_to_world, f2w_transferred, matched_frame.frameId, transferred_frame.frameId);
00198 }
00199
00200 double cst = sba_.calcRMSCost();
00201 cout << endl << "*** RMS Cost: " << cst << endl << endl;
00202
00203 if (cst > 4.0)
00204 {
00205
00206 int n = sba_.nodes.size();
00207 n = n-50;
00208 if (n < 1) n=1;
00209 sba_.nFixed = n;
00210 sba_.doSBA(3,1.0e-4, SBA_SPARSE_CHOLESKY);
00211
00212 sba_.nFixed = 1;
00213 }
00214 }
00215 }
00216 }
00217
00218 void VslamSystem::refine(int initial_runs)
00219 {
00221
00222 sba_.doSBA(initial_runs, 1.0e-4, SBA_SPARSE_CHOLESKY);
00223 if (sba_.calcRMSCost() > 4.0)
00224 sba_.doSBA(10, 1.0e-4, SBA_SPARSE_CHOLESKY);
00225 if (sba_.calcRMSCost() > 4.0)
00226 sba_.doSBA(10, 1.0e-4, SBA_SPARSE_CHOLESKY);
00227 }
00228
00229 }