Permalink
Browse files

Relax filtering of disparities

svae2

save3

x
  • Loading branch information...
1 parent 5e2d586 commit 5e40ed25f4b44103d916e6cb2b3ef4d910b483ab @oleg-alexandrov oleg-alexandrov committed Jan 29, 2014
View
5 NEWS
@@ -8,6 +8,10 @@ TOOLS
artificial discontinuities in the stereo results.
GENERAL
+
+ - Relaxed filtering of disparities, retaining more valid disparities.
+ Can be adjusted with the 'filter-mode' and related parameters.
+
- Added logging to a file for stereo and other tools.
- Triangulation:
@@ -17,6 +21,7 @@ GENERAL
North-East-Down vector rather than just its magnitude.
- Added a tutorial for processing Digital Globe Earth imagery.
+
- Improved mosacking of Digital Globe images.
- pc_align:
@@ -279,6 +279,17 @@ \section{Filtering}
\begin{description}
+\item[filter-mode \textnormal{\small{(= \emph{integer})}} (default = 1)]
+\hfill \\ This parameter sets the filter mode. Three modes are supported
+as described below. Here, by neighboring pixels for a current pixel we
+mean those pixels within the window of half-size of
+\texttt{rm-half-kernel} centered at the current pixel.
+ \begin{description}
+ \item[0] - No filtering.
+ \item[1] - Filter by discarding pixels at which disparity differs from mean disparity of neighbors by more than \texttt{max-mean-diff}.
+ \item[2] - Filter by discarding pixels at which percentage of neighboring disparities that are within \texttt{rm-threshold} of current disparity is less than \texttt{rm-min-matches}.
+ \end{description}
+
\item[rm-half-kernel \textnormal{\small{(= \emph{integer integer})}} (default = 5 5)] \hfill \\
This setting adjusts the behavior of an outlier rejection scheme
that ``erodes'' isolated regions of pixels in the disparity map that
@@ -289,17 +300,21 @@ \section{Filtering}
$5 \times 5$ half kernel would result in an $11 \times 11$ kernel
with 121 pixels in it.
+\item[max-mean-diff \textnormal{\small{(= \emph{integer})}} (default = 3)] \hfill \\
+ This parameter sets the {\em maximum difference} between the current pixel disparity and the mean of disparities of neighbors in order for a
+ given disparity value to be retained (for \texttt{filter-mode} 1).
+
\item[rm-min-matches \textnormal{\small{(= \emph{integer})}} (default = 60)] \hfill \\
This parameter sets the {\em percentage} of neighboring disparity
values that must fall within the inlier threshold in order for a
- given disparity value to be retained.
+ given disparity value to be retained (for \texttt{filter-mode} 2).
\item[rm-threshold \textnormal{\small{(= \emph{integer})}} (default = 3)] \hfill \\
This parameter sets the inlier threshold for the outlier rejection
scheme. This option works in conjunction with RM\_MIN\_MATCHES
above. A disparity value is rejected if it differs by more than
RM\_THRESHOLD disparity values from RM\_MIN\_MATCHES percent of
- pixels in the region being considered.
+ pixels in the region being considered (for \texttt{filter-mode} 2).
\item[rm-clean-passes \textnormal{\small{(= \emph{integer})}} (default = 1)] \hfill \\
Select the number of outlier removal passes that are carried out.
@@ -316,12 +331,12 @@ \section{Filtering}
%
\item[disable-fill-holes (default = false)] \hfill \\
- Normally ASP will try to fill holes in the dispartiy map (caused by
+ Normally ASP will try to fill holes in the disparity map (caused by
poor matching) with an inpainting algorithm. Inpainting is a
convolution method that takes the values at the edges of holes and
spreads those values inward.
- Use this flag inorder to disable the filling of holes to leave only
+ Use this flag in order to disable the filling of holes to leave only
true calculated results in the output.
Note: you can always use the good pixel mask image ({\tt
@@ -157,12 +157,16 @@ namespace asp {
FilteringDescription::FilteringDescription() : po::options_description("Filtering Options") {
StereoSettings& global = stereo_settings();
(*this).add_options()
+ ("filter-mode", po::value(&global.filter_mode)->default_value(1),
+ "Disparity filter mode. [0 None, 1 Use mean difference to neighbors (invalidates fewer pixels), 2 Use thresholds (invalidates more pixels)]")
("rm-half-kernel", po::value(&global.rm_half_kernel)->default_value(Vector2i(5,5), "5 5"),
"Low confidence pixel removal kernel (half sized)")
+ ("max-mean-diff", po::value(&global.max_mean_diff)->default_value(3),
+ "Maximum difference between current pixel disparity and disparity of neighbors to still keep current disparity (for filter mode 1)")
("rm-min-matches", po::value(&global.rm_min_matches)->default_value(60),
- "Minimum number of pixels to be matched to keep sample")
+ "Minimum number of pixels to be matched to keep sample (for filter mode 2)")
("rm-threshold", po::value(&global.rm_threshold)->default_value(3),
- "Maximum distance between samples to be considered still matched")
+ "Maximum distance between samples to be considered still matched (for filter mode 2)")
("rm-cleanup-passes", po::value(&global.rm_cleanup_passes)->default_value(1),
"Number of passes for cleanup during the post-processing phase")
("erode-max-size", po::value(&global.erode_max_size)->default_value(1000),
@@ -142,7 +142,9 @@ namespace asp {
int subpixel_pyramid_levels;
// Filtering Options
+ int filter_mode; // Which filter mode to use
vw::Vector2i rm_half_kernel; // Low confidence pixel removal kernel size
+ int max_mean_diff; // Max mean diff between pixel and neighbors
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
@@ -73,20 +73,21 @@ void produce_lowres_disparity( Options & opt ) {
asp::block_write_gdal_image
(opt.out_prefix + "-D_sub.tif",
- remove_outliers(stereo::pyramid_correlate
- (left_sub, right_sub,
- left_mask_sub, right_mask_sub,
- stereo::LaplacianOfGaussian(stereo_settings().slogW),
- search_range,
- stereo_settings().corr_kernel,
- stereo::CROSS_CORRELATION,
- corr_timeout, seconds_per_op,
- 2, 5),
- 1, 1, 2.0, 0.5
- ), opt,
+ rm_outliers_using_thresh
+ (stereo::pyramid_correlate
+ (left_sub, right_sub,
+ left_mask_sub, right_mask_sub,
+ stereo::LaplacianOfGaussian(stereo_settings().slogW),
+ search_range,
+ stereo_settings().corr_kernel,
+ stereo::CROSS_CORRELATION,
+ corr_timeout, seconds_per_op,
+ 2, 5),
+ 1, 1, 2.0, 0.5
+ ), opt,
TerminalProgressCallback("asp", "\t--> Low-resolution disparity:")
);
-
+
}else if ( stereo_settings().seed_mode == 2 ) {
// Use a DEM to get the low-res disparity
boost::shared_ptr<camera::CameraModel> left_camera_model, right_camera_model;
Oops, something went wrong.

0 comments on commit 5e40ed2

Please sign in to comment.