Skip to content

Commit

Permalink
uninportant changes
Browse files Browse the repository at this point in the history
  • Loading branch information
Loeing committed Mar 21, 2016
1 parent f666938 commit f671bc9
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 9 deletions.
4 changes: 2 additions & 2 deletions include/ProbabilityMapping.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ class ProbabilityMapping {
float depth;
float sigma;

depthHo():depth(NULL),sigma(NULL) {}
depthHo():depth(0),sigma(0) {}
};

ProbabilityMapping();
Expand All @@ -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<depthHo> H, depthHo* dist):
* * get the parameters of depth hypothesis distrubution from list of depth hypotheses */
void InverseDepthHypothesisFusion(const std::vector<depthHo*>& h, depthHo* dist);
void InverseDepthHypothesisFusion(const std::vector<depthHo>& h, depthHo* dist);
/* * \brief void intraKeyFrameDepthChecking(std::vector<std::vector<depthHo> > h, int imrows, int imcols): intra-keyframe depth-checking, smoothing, and growing. */
void IntraKeyFrameDepthChecking(std::vector<std::vector<depthHo> >& ho, int imrows, int imcols);
/* * \brief void interKeyFrameDepthChecking(ORB_SLAM::KeyFrame* currentKF, std::vector<std::vector<depthHo> > h, int imrows, int imcols):
Expand Down
14 changes: 7 additions & 7 deletions src/ProbabilityMapping.cc
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ void ProbabilityMapping::FirstLoop(ORB_SLAM::KeyFrame *kf, std::vector<std::vect
cout << "Got it!\n";
cout << "Generating Depth Hypotheses...\n";

std::vector<depthHo*> depth_ho;
std::vector<depthHo> depth_ho;

std::vector<std::vector<depthHo> > temp_ho (image.rows, std::vector<depthHo>(image.cols, depthHo()) );
for(int x = 0; x < image.rows; x++){
Expand All @@ -70,10 +70,10 @@ void ProbabilityMapping::FirstLoop(ORB_SLAM::KeyFrame *kf, std::vector<std::vect
ORB_SLAM::KeyFrame* kf2 = closestMatches[i];

depthHo* dh = new depthHo();
EpipolarSearch(kf, kf2, x, y, gradx, grady, grad, min_depth, max_depth, *dh);
EpipolarSearch(kf, kf2, x, y, gradx, grady, grad, min_depth, max_depth, dh);
cout << "Depth: " << dh->depth << "\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);
Expand All @@ -82,9 +82,9 @@ void ProbabilityMapping::FirstLoop(ORB_SLAM::KeyFrame *kf, std::vector<std::vect
cout << "Calculating Inverse Depth Hypothesis\n";
InverseDepthHypothesisFusion(depth_ho, dh);
temp_ho[x][y] = *dh;
} else {
temp_ho[x][y] = NULL;
}
}// else {
// temp_ho[x][y] = NULL;
//}
}
}
ho = temp_ho;
Expand Down Expand Up @@ -277,7 +277,7 @@ void ProbabilityMapping::IntraKeyFrameDepthChecking(std::vector<std::vector<dept
}
}

void ProbabilityMapping::InverseDepthHypothesisFusion(const std::vector<depthHo*>& h, depthHo* dist) {
void ProbabilityMapping::InverseDepthHypothesisFusion(const std::vector<depthHo>& h, depthHo* dist) {
dist->depth = 0;
dist->sigma = 0;

Expand Down

0 comments on commit f671bc9

Please sign in to comment.