Permalink
Browse files

stereo: Produce lowres is no longer used in multiple places

Thus produce lowres should no longer be inside stereo.{cc,h}.
  • Loading branch information...
Zack Moratto
Zack Moratto committed Mar 6, 2013
1 parent 1b041d8 commit 01fa4766ed0f2c38a0309ba5e6f294dcf436c4d6
Showing with 149 additions and 155 deletions.
  1. +0 −149 src/asp/Tools/stereo.cc
  2. +0 −6 src/asp/Tools/stereo.h
  3. +149 −0 src/asp/Tools/stereo_corr.cc
View
@@ -31,8 +31,6 @@
#include <boost/accumulators/accumulators.hpp>
#include <boost/accumulators/statistics.hpp>
-#include <asp/Core/DemDisparity.h>
-
using namespace vw;
using namespace vw::cartography;
@@ -325,153 +323,6 @@ namespace asp {
}
- void lowres_correlation( Options & opt ) {
-
- vw_out() << "\n[ " << current_posix_time_string()
- << " ] : Stage 1 --> LOW-RESOLUTION CORRELATION \n";
-
- // Working out search range if need be
- if (stereo_settings().is_search_defined()) {
- vw_out() << "\t--> Using user-defined search range.\n";
- } else {
-
- // Match file between the input files
- std::string match_filename
- = ip::match_filename(opt.out_prefix, opt.in_file1, opt.in_file2);
-
- if (!fs::exists(match_filename)) {
- // If there is not any match files for the input image. Let's
- // gather some IP quickly from the low resolution images. This
- // routine should only run for:
- // Pinhole + Epipolar
- // Pinhole + None
- // DG + None
- // Everything else should gather IP's all the time.
- float sub_scale =
- sum(elem_quot( Vector2f(file_image_size( opt.out_prefix+"-L_sub.tif" )),
- Vector2f(file_image_size( opt.out_prefix+"-L.tif" ) ) )) +
- sum(elem_quot( Vector2f(file_image_size( opt.out_prefix+"-R_sub.tif" )),
- Vector2f(file_image_size( opt.out_prefix+"-R.tif" ) ) ));
- sub_scale /= 4.0f;
-
- stereo_settings().search_range =
- approximate_search_range(opt.out_prefix,
- opt.out_prefix+"-L_sub.tif",
- opt.out_prefix+"-R_sub.tif",
- sub_scale );
- } else {
- // There exists a matchfile out there.
- std::vector<ip::InterestPoint> ip1, ip2;
- ip::read_binary_match_file( match_filename, ip1, ip2 );
-
- Matrix<double> align_matrix = math::identity_matrix<3>();
- if ( fs::exists(opt.out_prefix+"-align.exr") )
- read_matrix(align_matrix, opt.out_prefix + "-align.exr");
-
- BBox2 search_range;
- for ( size_t i = 0; i < ip1.size(); i++ ) {
- Vector3 r = align_matrix * Vector3(ip2[i].x,ip2[i].y,1);
- r /= r[2];
- search_range.grow( subvector(r,0,2) - Vector2(ip1[i].x,ip1[i].y) );
- }
- stereo_settings().search_range = grow_bbox_to_int( search_range );
- }
- vw_out() << "\t--> Detected search range: " << stereo_settings().search_range << "\n";
- }
-
- DiskImageView<vw::uint8> Lmask(opt.out_prefix + "-lMask.tif"),
- Rmask(opt.out_prefix + "-rMask.tif");
-
- // Performing disparity on sub images
- if ( stereo_settings().seed_mode > 0 ) {
- // Reuse prior existing D_sub if it exists
- bool rebuild = false;
-
- try {
- vw_log().console_log().rule_set().add_rule(-1,"fileio");
- DiskImageView<PixelMask<Vector2i> > test(opt.out_prefix+"-D_sub.tif");
- vw_settings().reload_config();
- } catch (vw::IOErr const& e) {
- vw_settings().reload_config();
- rebuild = true;
- } catch (vw::ArgumentErr const& e ) {
- // Throws on a corrupted file.
- vw_settings().reload_config();
- rebuild = true;
- }
-
- if ( rebuild )
- produce_lowres_disparity( opt );
- }
-
- vw_out() << "\n[ " << current_posix_time_string()
- << " ] : LOW-RESOLUTION CORRELATION FINISHED \n";
- }
-
- void produce_lowres_disparity( Options & opt ) {
-
- DiskImageView<vw::uint8> Lmask(opt.out_prefix + "-lMask.tif"),
- Rmask(opt.out_prefix + "-rMask.tif");
-
- DiskImageView<PixelGray<float> > left_sub( opt.out_prefix+"-L_sub.tif" ),
- right_sub( opt.out_prefix+"-R_sub.tif" );
-
- Vector2f downsample_scale( float(left_sub.cols()) / float(Lmask.cols()),
- float(left_sub.rows()) / float(Lmask.rows()) );
-
- DiskImageView<uint8> left_mask_sub( opt.out_prefix+"-lMask_sub.tif" ),
- right_mask_sub( opt.out_prefix+"-rMask_sub.tif" );
-
- BBox2i search_range( floor(elem_prod(downsample_scale,stereo_settings().search_range.min())),
- ceil(elem_prod(downsample_scale,stereo_settings().search_range.max())) );
-
- if ( stereo_settings().seed_mode == 1 ) {
-
- // Use low-res correlation to get the low-res disparity
- Vector2i expansion( search_range.width(),
- search_range.height() );
- expansion *= stereo_settings().seed_percent_pad / 2.0f;
- // Expand by the user selected amount. Default is 25%.
- search_range.min() -= expansion;
- search_range.max() += expansion;
- VW_OUT(DebugMessage,"asp") << "D_sub search range: "
- << search_range << " px\n";
- // Below we use on purpose stereo::CROSS_CORRELATION instead of
- // user's choice of correlation method, since this is the most
- // accurate, as well as reasonably fast for subsapled images.
- 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, 2
- ),
- 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;
- opt.session->camera_models(left_camera_model, right_camera_model);
- produce_dem_disparity(opt, left_camera_model, right_camera_model);
- }
-
- ImageView<PixelMask<Vector2i> > lowres_disparity;
- read_image( lowres_disparity, opt.out_prefix + "-D_sub.tif" );
- search_range =
- stereo::get_disparity_range( lowres_disparity );
- VW_OUT(DebugMessage,"asp") << "D_sub resolved search range: "
- << search_range << " px\n";
- search_range.min() = floor(elem_quot(search_range.min(),downsample_scale));
- search_range.max() = ceil(elem_quot(search_range.max(),downsample_scale));
- stereo_settings().search_range = search_range;
- }
-
// approximate search range
// Find interest points and grow them into a search range
BBox2i
View
@@ -79,12 +79,6 @@ namespace asp {
// Checks for obvious user mistakes
void user_safety_check(Options const& opt);
- // Low-res correlation
- void lowres_correlation( Options & opt );
-
- // Produces D_sub
- void produce_lowres_disparity( Options & opt );
-
// Approximate search range by looking at interest point match file
vw::BBox2i approximate_search_range(std::string const& out_prefix,
std::string const& left_sub_file,
@@ -27,13 +27,162 @@
#include <vw/Stereo/CorrelationView.h>
#include <vw/Stereo/CostFunctions.h>
+#include <asp/Core/DemDisparity.h>
+
using namespace vw;
using namespace asp;
namespace vw {
template<> struct PixelFormatID<PixelMask<Vector<float, 5> > > { static const PixelFormatEnum value = VW_PIXEL_GENERIC_6_CHANNEL; };
}
+void produce_lowres_disparity( Options & opt ) {
+
+ DiskImageView<vw::uint8> Lmask(opt.out_prefix + "-lMask.tif"),
+ Rmask(opt.out_prefix + "-rMask.tif");
+
+ DiskImageView<PixelGray<float> > left_sub( opt.out_prefix+"-L_sub.tif" ),
+ right_sub( opt.out_prefix+"-R_sub.tif" );
+
+ Vector2f downsample_scale( float(left_sub.cols()) / float(Lmask.cols()),
+ float(left_sub.rows()) / float(Lmask.rows()) );
+
+ DiskImageView<uint8> left_mask_sub( opt.out_prefix+"-lMask_sub.tif" ),
+ right_mask_sub( opt.out_prefix+"-rMask_sub.tif" );
+
+ BBox2i search_range( floor(elem_prod(downsample_scale,stereo_settings().search_range.min())),
+ ceil(elem_prod(downsample_scale,stereo_settings().search_range.max())) );
+
+ if ( stereo_settings().seed_mode == 1 ) {
+
+ // Use low-res correlation to get the low-res disparity
+ Vector2i expansion( search_range.width(),
+ search_range.height() );
+ expansion *= stereo_settings().seed_percent_pad / 2.0f;
+ // Expand by the user selected amount. Default is 25%.
+ search_range.min() -= expansion;
+ search_range.max() += expansion;
+ VW_OUT(DebugMessage,"asp") << "D_sub search range: "
+ << search_range << " px\n";
+ // Below we use on purpose stereo::CROSS_CORRELATION instead of
+ // user's choice of correlation method, since this is the most
+ // accurate, as well as reasonably fast for subsapled images.
+ 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, 2
+ ),
+ 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;
+ opt.session->camera_models(left_camera_model, right_camera_model);
+ produce_dem_disparity(opt, left_camera_model, right_camera_model);
+ }
+
+ ImageView<PixelMask<Vector2i> > lowres_disparity;
+ read_image( lowres_disparity, opt.out_prefix + "-D_sub.tif" );
+ search_range =
+ stereo::get_disparity_range( lowres_disparity );
+ VW_OUT(DebugMessage,"asp") << "D_sub resolved search range: "
+ << search_range << " px\n";
+ search_range.min() = floor(elem_quot(search_range.min(),downsample_scale));
+ search_range.max() = ceil(elem_quot(search_range.max(),downsample_scale));
+ stereo_settings().search_range = search_range;
+}
+
+void lowres_correlation( Options & opt ) {
+
+ vw_out() << "\n[ " << current_posix_time_string()
+ << " ] : Stage 1 --> LOW-RESOLUTION CORRELATION \n";
+
+ // Working out search range if need be
+ if (stereo_settings().is_search_defined()) {
+ vw_out() << "\t--> Using user-defined search range.\n";
+ } else {
+
+ // Match file between the input files
+ std::string match_filename
+ = ip::match_filename(opt.out_prefix, opt.in_file1, opt.in_file2);
+
+ if (!fs::exists(match_filename)) {
+ // If there is not any match files for the input image. Let's
+ // gather some IP quickly from the low resolution images. This
+ // routine should only run for:
+ // Pinhole + Epipolar
+ // Pinhole + None
+ // DG + None
+ // Everything else should gather IP's all the time.
+ float sub_scale =
+ sum(elem_quot( Vector2f(file_image_size( opt.out_prefix+"-L_sub.tif" )),
+ Vector2f(file_image_size( opt.out_prefix+"-L.tif" ) ) )) +
+ sum(elem_quot( Vector2f(file_image_size( opt.out_prefix+"-R_sub.tif" )),
+ Vector2f(file_image_size( opt.out_prefix+"-R.tif" ) ) ));
+ sub_scale /= 4.0f;
+
+ stereo_settings().search_range =
+ approximate_search_range(opt.out_prefix,
+ opt.out_prefix+"-L_sub.tif",
+ opt.out_prefix+"-R_sub.tif",
+ sub_scale );
+ } else {
+ // There exists a matchfile out there.
+ std::vector<ip::InterestPoint> ip1, ip2;
+ ip::read_binary_match_file( match_filename, ip1, ip2 );
+
+ Matrix<double> align_matrix = math::identity_matrix<3>();
+ if ( fs::exists(opt.out_prefix+"-align.exr") )
+ read_matrix(align_matrix, opt.out_prefix + "-align.exr");
+
+ BBox2 search_range;
+ for ( size_t i = 0; i < ip1.size(); i++ ) {
+ Vector3 r = align_matrix * Vector3(ip2[i].x,ip2[i].y,1);
+ r /= r[2];
+ search_range.grow( subvector(r,0,2) - Vector2(ip1[i].x,ip1[i].y) );
+ }
+ stereo_settings().search_range = grow_bbox_to_int( search_range );
+ }
+ vw_out() << "\t--> Detected search range: " << stereo_settings().search_range << "\n";
+ }
+
+ DiskImageView<vw::uint8> Lmask(opt.out_prefix + "-lMask.tif"),
+ Rmask(opt.out_prefix + "-rMask.tif");
+
+ // Performing disparity on sub images
+ if ( stereo_settings().seed_mode > 0 ) {
+ // Reuse prior existing D_sub if it exists
+ bool rebuild = false;
+
+ try {
+ vw_log().console_log().rule_set().add_rule(-1,"fileio");
+ DiskImageView<PixelMask<Vector2i> > test(opt.out_prefix+"-D_sub.tif");
+ vw_settings().reload_config();
+ } catch (vw::IOErr const& e) {
+ vw_settings().reload_config();
+ rebuild = true;
+ } catch (vw::ArgumentErr const& e ) {
+ // Throws on a corrupted file.
+ vw_settings().reload_config();
+ rebuild = true;
+ }
+
+ if ( rebuild )
+ produce_lowres_disparity( opt );
+ }
+
+ vw_out() << "\n[ " << current_posix_time_string()
+ << " ] : LOW-RESOLUTION CORRELATION FINISHED \n";
+}
+
// This correlator takes a low resolution disparity image as an input
// so that it may narrow its search range for each tile that is
// processed.

0 comments on commit 01fa476

Please sign in to comment.