Skip to content

Commit

Permalink
nothing
Browse files Browse the repository at this point in the history
  • Loading branch information
Loeing committed Mar 21, 2016
2 parents f671bc9 + 6056fc3 commit ce46264
Show file tree
Hide file tree
Showing 2 changed files with 113 additions and 108 deletions.
9 changes: 4 additions & 5 deletions include/ProbabilityMapping.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,8 @@ class ProbabilityMapping {
struct depthHo {
float depth;
float sigma;

depthHo():depth(0),sigma(0) {}
bool supported;
depthHo():depth(0),sigma(0),supported(false) {}
};

ProbabilityMapping();
Expand All @@ -62,7 +62,7 @@ class ProbabilityMapping {
/* * \brief void stereo_search_constraints(): return min, max inverse depth */
void StereoSearchConstraints(ORB_SLAM::KeyFrame* kf, float* min_depth, float* max_depth);
/* * \brief void epipolar_search(): return distribution of inverse depths/sigmas for each pixel */
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);
void EpipolarSearch(ORB_SLAM::KeyFrame *kf1, ORB_SLAM::KeyFrame *kf2, int x, int y, float pixel, 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);
Expand All @@ -77,10 +77,9 @@ class ProbabilityMapping {
void GetTR(ORB_SLAM::KeyFrame* kf, cv::Mat* t, cv::Mat* r);
void GetXp(const cv::Mat& K, int x, int y, cv::Mat* Xp);
void GetParameterization(const cv::Mat& F12, const int x, const int y, float* a, float* b, float* c);
void ComputeInvDepthHypothesis(ORB_SLAM::KeyFrame* kf, int pixel, float ustar, float ustar_var, float a, float b, float c, depthHo &dh);
void ComputeInvDepthHypothesis(ORB_SLAM::KeyFrame* kf, int pixel, float ustar, float ustar_var, float a, float b, float c, depthHo *dh);
void GetImageGradient(const cv::Mat& image, cv::Mat* gradx, cv::Mat* grady, cv::Mat* grad);
void GetInPlaneRotation(ORB_SLAM::KeyFrame* k1, ORB_SLAM::KeyFrame* k2, float* th);
void GetIntensityGradient(cv::Mat im, float* g);
void PixelNeighborSupport(std::vector<std::vector<depthHo> > H, int x, int y, std::vector<depthHo>& support);
void PixelNeighborNeighborSupport(std::vector<std::vector<depthHo> > H, int px, int py, std::vector<std::vector<depthHo> >& support);
void GetIntensityGradient_D(const cv::Mat& ImGrad, float a, float b, float c, int px, float* q);
Expand Down
Loading

0 comments on commit ce46264

Please sign in to comment.