diff --git a/include/ProbabilityMapping.h b/include/ProbabilityMapping.h index da937e8b..12db53a3 100644 --- a/include/ProbabilityMapping.h +++ b/include/ProbabilityMapping.h @@ -53,7 +53,7 @@ class ProbabilityMapping { float depth; float sigma; - depthHo():depth(NULL),sigma(NULL) {} + depthHo():depth(0),sigma(0) {} }; ProbabilityMapping(); @@ -65,7 +65,7 @@ class ProbabilityMapping { void EpipolarSearch(ORB_SLAM::KeyFrame *kf1, ORB_SLAM::KeyFrame *kf2, int x, int y, cv::Mat gradx, cv::Mat grady, cv::Mat grad, float min_depth, float max_depth, depthHo &dh); /* * \brief void inverse_depth_hypothesis_fusion(const vector H, depthHo* dist): * * get the parameters of depth hypothesis distrubution from list of depth hypotheses */ - void InverseDepthHypothesisFusion(const std::vector& h, depthHo* dist); + void InverseDepthHypothesisFusion(const std::vector& h, depthHo* dist); /* * \brief void intraKeyFrameDepthChecking(std::vector > h, int imrows, int imcols): intra-keyframe depth-checking, smoothing, and growing. */ void IntraKeyFrameDepthChecking(std::vector >& ho, int imrows, int imcols); /* * \brief void interKeyFrameDepthChecking(ORB_SLAM::KeyFrame* currentKF, std::vector > h, int imrows, int imcols): diff --git a/src/ProbabilityMapping.cc b/src/ProbabilityMapping.cc index add65781..1694769f 100644 --- a/src/ProbabilityMapping.cc +++ b/src/ProbabilityMapping.cc @@ -54,7 +54,7 @@ void ProbabilityMapping::FirstLoop(ORB_SLAM::KeyFrame *kf, std::vector depth_ho; + std::vector depth_ho; std::vector > temp_ho (image.rows, std::vector(image.cols, depthHo()) ); for(int x = 0; x < image.rows; x++){ @@ -70,10 +70,10 @@ void ProbabilityMapping::FirstLoop(ORB_SLAM::KeyFrame *kf, std::vectordepth << "\n"; if (dh != NULL) - depth_ho.push_back(dh); + depth_ho.push_back(*dh); } printf("FirstLoop: found a set of %d hypotheseses for pixel %d,%d\n", (int)(depth_ho.size()), x, y); @@ -82,9 +82,9 @@ void ProbabilityMapping::FirstLoop(ORB_SLAM::KeyFrame *kf, std::vector& h, depthHo* dist) { +void ProbabilityMapping::InverseDepthHypothesisFusion(const std::vector& h, depthHo* dist) { dist->depth = 0; dist->sigma = 0;