Skip to content

HTTPS clone URL

Subversion checkout URL

You can clone with
or
.
Download ZIP
Browse files

Stereo in a region

  • Loading branch information...
commit d698455c47d0c37bca57cd1eaaaa50b5bf3537c6 1 parent b9aea2a
@oleg-alexandrov oleg-alexandrov authored
View
2  src/asp/Core/StereoSettings.cc
@@ -74,7 +74,7 @@ namespace asp {
("xcorr-threshold", po::value(&global.xcorr_threshold)->default_value(2),
"L-R vs R-L agreement threshold in pixels.")
("corr-kernel", po::value(&global.kernel)->default_value(Vector2i(21,21),"21,21"),
- "Kernel sized used for integer correlator.")
+ "Kernel size used for integer correlator.")
("corr-search", po::value(&global.search_range)->default_value(BBox2i(0,0,0,0), "auto"),
"Disparity search range. Specify in format: hmin,vmin,hmax,vmax.")
("corr-max-levels", po::value(&global.corr_max_levels)->default_value(5),
View
23 src/asp/Tools/stereo.cc
@@ -36,8 +36,9 @@ namespace asp {
po::options_description general_options_sub("");
general_options_sub.add_options()
("session-type,t", po::value(&opt.stereo_session_string), "Select the stereo session type to use for processing. [options: pinhole isis dg rpc]")
- ("stereo-file,s", po::value(&opt.stereo_default_filename)->default_value("./stereo.default"), "Explicitly specify the stereo.default file to use. [default: ./stereo.default]");
-
+ ("stereo-file,s", po::value(&opt.stereo_default_filename)->default_value("./stereo.default"), "Explicitly specify the stereo.default file to use. [default: ./stereo.default]")
+ ("left-image-crop-win", po::value(&opt.left_image_crop_win)->default_value(BBox2i(0, 0, 0, 0),""), "Do stereo in this region [xoff yoff xsize ysize] of the left image [default: use the entire image].");
+
// We distinguish between all_general_options, which is all the
// options we must parse, even if we don't need some of them, and
// general_options, which are the options specifically used by the
@@ -132,6 +133,24 @@ namespace asp {
( opt.out_prefix.empty() || opt.cam_file2.empty() ) )
vw_throw( ArgumentErr() << "\nMissing output-prefix or right camera model.\n" );
+ // Interpret the the last two coordinates of left_image_crop_win as
+ // width and height rather than max_x and max_y
+ BBox2i b = opt.left_image_crop_win;
+ opt.left_image_crop_win = BBox2i(b.min().x(), b.min().y(), b.max().x(), b.max().y());
+ // By default, we do stereo in the entire image
+ DiskImageView<PixelGray<float> > left_image(opt.in_file1);
+ BBox2i full_box = BBox2i(0, 0, left_image.cols(), left_image.rows());
+ if (opt.left_image_crop_win == BBox2i(0, 0, 0, 0)){
+ opt.left_image_crop_win = full_box;
+ }
+ // Ensure that the region is inside the maximum theoretical region
+ opt.left_image_crop_win.crop(full_box);
+ // Sanity check
+ if (opt.left_image_crop_win.width() <= 0 || opt.left_image_crop_win.height() <= 0 ){
+ vw_throw( ArgumentErr() << "Invalid region for doing stereo.\n\n"
+ << usage << general_options );
+ }
+
fs::path out_prefix_path(opt.out_prefix);
if (out_prefix_path.has_parent_path()) {
if (!fs::is_directory(out_prefix_path.parent_path())) {
View
3  src/asp/Tools/stereo.h
@@ -70,7 +70,8 @@ struct Options : asp::BaseOptions {
// Settings
std::string stereo_session_string, stereo_default_filename;
- boost::shared_ptr<asp::StereoSession> session; // Used to extract cameras
+ boost::shared_ptr<asp::StereoSession> session; // Used to extract cameras
+ vw::BBox2i left_image_crop_win; // Used to do stereo in a region
// Output
std::string out_prefix;
View
45 src/asp/Tools/stereo_corr.cc
@@ -51,6 +51,7 @@ class SeededCorrelatorView : public ImageViewBase<SeededCorrelatorView<Image1T,
// Settings
Vector2f m_upscale_factor;
BBox2i m_seed_bbox;
+ BBox2i m_left_image_crop_win;
stereo::CostFunctionType m_cost_mode;
public:
@@ -60,11 +61,12 @@ class SeededCorrelatorView : public ImageViewBase<SeededCorrelatorView<Image1T,
ImageViewBase<Mask2T> const& right_mask,
ImageViewBase<SeedDispT> const& source_disp,
stereo::PreFilterBase<PProcT> const& filter,
+ BBox2i left_image_crop_win,
stereo::CostFunctionType cost_mode ) :
m_left_image(left_image.impl()), m_right_image(right_image.impl()),
m_left_mask(left_mask.impl()), m_right_mask(right_mask.impl()),
m_source_disparity( source_disp.impl() ),
- m_preproc_func( filter.impl() ), m_cost_mode( cost_mode ) {
+ m_preproc_func( filter.impl() ), m_left_image_crop_win(left_image_crop_win), m_cost_mode(cost_mode) {
m_upscale_factor[0] = float(m_left_image.cols()) / float(m_source_disparity.cols());
m_upscale_factor[1] = float(m_left_image.rows()) / float(m_source_disparity.rows());
m_seed_bbox = bounding_box( m_source_disparity );
@@ -88,6 +90,33 @@ class SeededCorrelatorView : public ImageViewBase<SeededCorrelatorView<Image1T,
typedef CropView<ImageView<pixel_type> > prerasterize_type;
inline prerasterize_type prerasterize(BBox2i const& bbox) const {
+
+ // We do stereo only in m_left_image_crop_win. Skip the current tile if
+ // it does not intersect this region.
+ BBox2i intersection = bbox; intersection.crop(m_left_image_crop_win);
+ if (intersection.empty()){
+ return prerasterize_type(ImageView<pixel_type>(bbox.width(),
+ bbox.height()),
+ -bbox.min().x(), -bbox.min().y(),
+ cols(), rows() );
+ }
+
+ CropView<ImageView<pixel_type> > disparity = prerasterize_helper(bbox);
+
+ // Set to invalid the disparity outside m_left_image_crop_win.
+ for (int col = bbox.min().x(); col < bbox.max().x(); col++){
+ for (int row = bbox.min().y(); row < bbox.max().y(); row++){
+ if (!m_left_image_crop_win.contains(Vector2(col, row))){
+ disparity(col, row) = pixel_type();
+ }
+ }
+ }
+
+ return disparity;
+ }
+
+ inline prerasterize_type prerasterize_helper(BBox2i const& bbox) const {
+
// User strategies
if ( stereo_settings().seed_option == 1 ) {
BBox2i seed_bbox( elem_quot(bbox.min(), m_upscale_factor),
@@ -148,10 +177,11 @@ seeded_correlation( ImageViewBase<Image1T> const& left,
ImageViewBase<Mask2T> const& rmask,
ImageViewBase<SeedDispT> const& sdisp,
stereo::PreFilterBase<PProcT> const& filter,
+ BBox2i left_image_crop_win,
stereo::CostFunctionType cost_type ) {
typedef SeededCorrelatorView<Image1T, Image2T, Mask1T, Mask2T, SeedDispT, PProcT> return_type;
return return_type( left.impl(), right.impl(), lmask.impl(), rmask.impl(),
- sdisp.impl(), filter.impl(), cost_type );
+ sdisp.impl(), filter.impl(), left_image_crop_win, cost_type );
}
// approximate search range
@@ -454,21 +484,22 @@ void stereo_correlation( Options& opt ) {
vw_out() << "\t--> Using LOG pre-processing filter with "
<< stereo_settings().slogW << " sigma blur.\n";
disparity_map =
- seeded_correlation( left_disk_image, right_disk_image, Lmask, Rmask, sub_disparity,
- stereo::LaplacianOfGaussian(stereo_settings().slogW),
+ seeded_correlation( left_disk_image, right_disk_image, Lmask, Rmask, sub_disparity,
+ stereo::LaplacianOfGaussian(stereo_settings().slogW), opt.left_image_crop_win,
cost_mode );
} else if ( stereo_settings().pre_filter_mode == 1 ) {
vw_out() << "\t--> Using Subtracted Mean pre-processing filter with "
<< stereo_settings().slogW << " sigma blur.\n";
disparity_map =
seeded_correlation( left_disk_image, right_disk_image, Lmask, Rmask, sub_disparity,
- stereo::SubtractedMean(stereo_settings().slogW),
+ stereo::SubtractedMean(stereo_settings().slogW), opt.left_image_crop_win,
cost_mode );
} else {
vw_out() << "\t--> Using NO pre-processing filter." << std::endl;
disparity_map =
- seeded_correlation( left_disk_image, right_disk_image, Lmask, Rmask, sub_disparity,
- stereo::NullOperation(), cost_mode );
+ seeded_correlation( left_disk_image, right_disk_image, Lmask, Rmask, sub_disparity,
+ stereo::NullOperation(), opt.left_image_crop_win,
+ cost_mode );
}
asp::block_write_gdal_image( opt.out_prefix + "-D.tif",
View
5 src/asp/Tools/stereo_tri.cc
@@ -426,10 +426,9 @@ void stereo_triangulation( Options const& opt ) {
}
if (stereo_settings().compute_error_vector)
- save_point_cloud(point_cloud, opt);
+ save_point_cloud(crop(point_cloud, opt.left_image_crop_win), opt);
else
- save_point_cloud(point_and_error_norm(point_cloud), opt);
-
+ save_point_cloud(point_and_error_norm(crop(point_cloud, opt.left_image_crop_win)), opt);
} catch (IOErr const& e) {
vw_throw( ArgumentErr() << "\nUnable to start at point cloud stage -- could not read input files.\n"
Please sign in to comment.
Something went wrong with that request. Please try again.