Permalink
Browse files

Forcing my will upon ASP. Preprocessing filter selection has changed.…

… Stereo factor.
  • Loading branch information...
1 parent 378d44a commit e46bfaa3029fe9b909457456f9c24706d4dfb04a Zack Moratto committed Aug 21, 2009
Showing with 202 additions and 184 deletions.
  1. +4 −1 src/Isis/StereoSessionIsis.cc
  2. +10 −10 src/StereoSettings.cc
  3. +39 −26 src/StereoSettings.h
  4. +141 −143 src/stereo.cc
  5. +8 −4 stereo.default.example
@@ -327,7 +327,8 @@ void StereoSessionIsis::pre_filtering_hook(std::string const& input_file, std::s
ImageViewRef<PixelDisparity<float> > disparity_map = disparity::mask(disparity_disk_image, Lmask, Rmask);
DiskImageResourceOpenEXR disparity_map_rsrc(output_file, disparity_map.format() );
- disparity_map_rsrc.set_tiled_write(std::min(512,disparity_map.cols()),std::min(512, disparity_map.rows()));
+ disparity_map_rsrc.set_tiled_write(std::min(512,disparity_map.cols()),
+ std::min(512,disparity_map.rows()));
block_write_image( disparity_map_rsrc, disparity_map, TerminalProgressCallback(InfoMessage, "\t--> Saving Mask :") );
}
}
@@ -358,6 +359,8 @@ void StereoSessionIsis::pre_pointcloud_hook(std::string const& input_file, std::
result = stereo::disparity::remove_invalid_pixels(result, right_disk_image.cols(), right_disk_image.rows());
DiskImageResourceOpenEXR disparity_corrected_rsrc(output_file, result.format() );
+ disparity_corrected_rsrc.set_tiled_write(std::min(512,disparity_map.cols()),
+ std::min(512,disparity_map.rows()));
block_write_image( disparity_corrected_rsrc, result,
TerminalProgressCallback(InfoMessage, "\t Processing:"));
}
View
@@ -27,6 +27,7 @@
#include "StereoSettings.h"
#include <vw/Core/Thread.h>
+#include <vw/Core/Log.h>
#include <fstream>
// ---------------------------------------------------
@@ -100,11 +101,10 @@ StereoSettings::StereoSettings() {
ASSOC_INT("INTERESTPOINT_ALIGNMENT_SUBSAMPLING", keypoint_align_subsampling, 1, "Image sub-sampling factor for keypoint alignment.");
ASSOC_INT("DO_INDIVIDUAL_NORMALIZATION", individually_normalize, 0, "Normalize each image individually before processsing.");
ASSOC_INT("FORCE_USE_ENTIRE_RANGE", force_max_min, 0, "Use images entire values, otherwise compress image range to -+2.5 sigmas around mean.");
+ ASSOC_INT("PREPROCESSING_FILTER_MODE", pre_filter_mode, 3, "selects the preprocessing filter");
+ ASSOC_FLOAT("SLOG_KERNEL_WIDTH", slogW, 1.5, "SIGMA for the gaussian blure in LOG and SLOG");
// Correlation Options
- ASSOC_INT("DO_SLOG", slog, 1, "perform an slog (relpace the emboss)");
- ASSOC_INT("DO_LOG", log, 0, "perform a log (laplacian of gaussian)");
- ASSOC_FLOAT("SLOG_KERNEL_WIDTH", slogW, 1.5, "SIGMA for the gaussian blure in LOG and SLOG");
ASSOC_INT("H_KERNEL", h_kern, 25, "kernel width");
ASSOC_INT("V_KERNEL", v_kern, 25, "kernel height");
ASSOC_INT("SUBPIXEL_H_KERNEL", subpixel_h_kern, 35, "subpixel kernel width");
@@ -116,16 +116,16 @@ StereoSettings::StereoSettings() {
ASSOC_INT("DO_H_SUBPIXEL", do_h_subpixel, 1, "Do vertical subpixel interpolation.");
ASSOC_INT("DO_V_SUBPIXEL", do_v_subpixel, 1, "Do horizontal subpixel interpolation.");
ASSOC_INT("SUBPIXEL_MODE", subpixel_mode, 0, "Use the affine adaptive subpixel correlator (slower, but more accurate)");
- ASSOC_FLOAT("XCORR_THRESHOLD", xcorr_treshold, 2.0, "");
- ASSOC_FLOAT("CORRSCORE_REJECTION_THRESHOLD", corrscore_rejection_treshold, 1.1, "");
+ ASSOC_FLOAT("XCORR_THRESHOLD", xcorr_threshold, 2.0, "");
+ ASSOC_FLOAT("CORRSCORE_REJECTION_THRESHOLD", corrscore_rejection_threshold, 1.1, "");
ASSOC_INT("COST_BLUR", cost_blur, 1, "");
ASSOC_INT("COST_MODE", cost_mode, 0, "");
// Filtering Options
ASSOC_INT("RM_H_HALF_KERN", rm_h_half_kern, 5, "low conf pixel removal kernel half size");
ASSOC_INT("RM_V_HALF_KERN", rm_v_half_kern, 5, "");
ASSOC_INT("RM_MIN_MATCHES", rm_min_matches, 60, "min # of pxls to be matched to keep pxl");
- ASSOC_INT("RM_TRESHOLD", rm_treshold, 3, "rm_treshold > disp[n]-disp[m] pixels are not matching");
+ ASSOC_INT("RM_TRESHOLD", rm_threshold, 3, "rm_treshold > disp[n]-disp[m] pixels are not matching");
ASSOC_INT("RM_CLEANUP_PASSES", rm_cleanup_passes, 1, "number of passes for cleanup during the post-processing phase");
ASSOC_INT("FILL_HOLES_NURBS", fill_holes_NURBS, 1, "fill holes using Larry's NURBS code");
ASSOC_INT("MASK_FLATFIELD", mask_flatfield, 0, "mask pixels that are less than 0. (for use with apollo metric camera only!)");
@@ -153,8 +153,8 @@ void StereoSettings::read(std::string const& filename) {
exit(EXIT_FAILURE);
}
- std::cout << "*************************************************************\n";
- std::cout << "Reading Stereo Settings file: " << filename << "\n";
+ vw::vw_out(0) << "*************************************************************\n";
+ vw::vw_out(0) << "Reading Stereo Settings file: " << filename << "\n";
std::string name, value, line;
int c;
@@ -170,14 +170,14 @@ void StereoSettings::read(std::string const& filename) {
try {
po::store(po::parse_config_file(ss, m_desc), m_vm);
} catch (boost::program_options::unknown_option &e) {
- std::cout << "\tWARNING --> Unknown stereo settings option: " << line << "\n";
+ vw::vw_out(0) << "\tWARNING --> Unknown stereo settings option: " << line << "\n";
}
}
ignoreline(fp);
}
po::notify(m_vm);
- std::cout << "*************************************************************\n";
+ vw::vw_out(0) << "*************************************************************\n";
fp.close();
}
View
@@ -43,44 +43,57 @@ class StereoSettings {
// ----------------
// Preprocessing options
- int epipolar_alignment; /* Align images using the epipolar constraints */
- int keypoint_alignment; /* Align images using the keypoint alignment method */
- int keypoint_align_subsampling; // if > 1, image sub-sampling factor for keypoint aligment (to speed things up)
- int individually_normalize; // if > 1, normalize the images individually with their own hi's and low
+ int epipolar_alignment; /* Align images using the
+ epipolar constraints */
+ int keypoint_alignment; /* Align images using the
+ keypoint alignment method */
+ int keypoint_align_subsampling; /* if > 1, image sub-sampling factor
+ for keypoint aligment (to speed
+ things up) */
+ int individually_normalize; /* if > 1, normalize the images
+ individually with their
+ own hi's and low */
int force_max_min; // Use entire dynamic range of image..
+ int pre_filter_mode; /* 0 = None
+ 1 = Gaussian Blur
+ 2 = Log Filter
+ 3 = SLog Filter */
+ float slogW; // Preprocessing filter width
// Correlation Options
- int slog; /* perform an slog (relpace the emboss) */
- int log; /* perform a log (laplacian of the gaussian blur) */
- float slogW;
- int h_kern; /* kernel width first pass */
- int v_kern; /* kernel height first pass*/
- int subpixel_h_kern; /* kernel width first pass */
- int subpixel_v_kern; /* kernel height first pass*/
- int h_corr_max; /* correlation window max x */
- int h_corr_min; /* correlation window min x */
- int v_corr_max; /* correlation window max y */
- int v_corr_min; /* correlation window min y */
- int do_h_subpixel;
+ int h_kern; /* kernel width first pass */
+ int v_kern; /* kernel height first pass*/
+ int subpixel_h_kern; /* kernel width first pass */
+ int subpixel_v_kern; /* kernel height first pass*/
+ int h_corr_max; /* correlation window max x */
+ int h_corr_min; /* correlation window min x */
+ int v_corr_max; /* correlation window max y */
+ int v_corr_min; /* correlation window min y */
+ int do_h_subpixel; /* Both of these must on */
int do_v_subpixel;
- int subpixel_mode; /* Use the affine adaptive subpixel correlator (slow!) */
- float xcorr_treshold;
- float corrscore_rejection_treshold;
+ int subpixel_mode; /* 0 = parabola fitting
+ 1 = affine, robust weighting
+ 2 = affine, bayes weighting
+ 3 = affine, bayes EM weighting */
+ float xcorr_threshold;
+ float corrscore_rejection_threshold;
int cost_blur;
int cost_mode;
// Filtering Options
- int rm_h_half_kern; /* low confidence pixel removal kernel size */
+ int rm_h_half_kern; /* low confidence pixel removal kernel size */
int rm_v_half_kern;
- int rm_min_matches; /* min # of pxl to be matched to keep pxl */
- int rm_treshold; /* rm_treshold < disp[n]-disp[m] reject pxl */
- int rm_cleanup_passes; /* number of times to perform cleanup in the post-processing phase */
+ int rm_min_matches; /* min # of pxl to be matched to keep pxl */
+ int rm_threshold; /* rm_treshold < disp[n]-disp[m] reject pxl */
+ int rm_cleanup_passes; /* number of times to perform cleanup
+ in the post-processing phase */
int fill_holes_NURBS;
- int mask_flatfield; // Masks pixels in the input images that are less than 0. (For use with apollo metric camera...)
+ int mask_flatfield; /* Masks pixels in the input images that are less
+ than 0. (For use with apollo metric camera...) */
// Triangulation Options
- float near_universe_radius; /* radius of the universe in meters */
- float far_universe_radius; /* radius of the universe in meters */
+ float near_universe_radius; /* radius of the universe in meters */
+ float far_universe_radius; /* radius of the universe in meters */
};
/// Return the singleton instance of the stereo setting structure.
Oops, something went wrong.

0 comments on commit e46bfaa

Please sign in to comment.