Skip to content

Commit

Permalink
Handle no-data properly when applying epipolar transform
Browse files Browse the repository at this point in the history
  • Loading branch information
oleg-alexandrov committed May 5, 2017
1 parent 026b508 commit fc527d9
Show file tree
Hide file tree
Showing 3 changed files with 50 additions and 32 deletions.
10 changes: 10 additions & 0 deletions src/vw/Camera/CameraTransform.h
Original file line number Diff line number Diff line change
Expand Up @@ -120,6 +120,16 @@ namespace camera{
};


/// Transform an image from one camera model to another, explicitly
/// specifying the edge extension and interpolation modes. Specify the size of the output image.
template <class ImageT, class SrcCameraT, class DstCameraT, class EdgeT, class InterpT>
TransformView<InterpolationView<EdgeExtensionView<ImageT, EdgeT>, InterpT>, CameraTransform<SrcCameraT, DstCameraT> >
inline camera_transform( ImageViewBase<ImageT> const& image, SrcCameraT const& src_camera, DstCameraT const& dst_camera, Vector2i size, EdgeT const& edge_func, InterpT const& interp_func )
{
CameraTransform<SrcCameraT, DstCameraT> ctx( src_camera, dst_camera );
return transform( image, ctx, size[0], size[1], edge_func, interp_func );
}

/// Transform an image from one camera model to another, explicitly
/// specifying the edge extension and interpolation modes.
template <class ImageT, class SrcCameraT, class DstCameraT, class EdgeT, class InterpT>
Expand Down
48 changes: 36 additions & 12 deletions src/vw/Camera/CameraUtilities.h
Original file line number Diff line number Diff line change
Expand Up @@ -227,7 +227,8 @@ void get_epipolar_transformed_images(std::string const& left_camera_file,
ImageInT const& left_image_in,
ImageInT const& right_image_in,
ImageOutT & left_image_out,
ImageOutT & right_image_out) {
ImageOutT & right_image_out,
ValueEdgeExtension<typename ImageOutT::pixel_type> edge_ext) {

// In the epipolar alignment case, the "camera_models" function returns the CAHVModel type!
CAHVModel* left_epipolar_cahv = dynamic_cast<CAHVModel*>(vw::camera::unadjusted_model(&(*left_cahv_camera )));
Expand All @@ -245,22 +246,34 @@ void get_epipolar_transformed_images(std::string const& left_camera_file,
if (boost::ends_with(lcase_file, ".cahvore")) {
CAHVOREModel left_cahvore (left_camera_file );
CAHVOREModel right_cahvore(right_camera_file);
left_image_out = camera_transform(left_image_in, left_cahvore, *left_epipolar_cahv );
right_image_out = camera_transform(right_image_in, right_cahvore, *right_epipolar_cahv);
left_image_out = camera_transform(left_image_in, left_cahvore, *left_epipolar_cahv,
edge_ext, BilinearInterpolation()
);
right_image_out = camera_transform(right_image_in, right_cahvore, *right_epipolar_cahv,
edge_ext, BilinearInterpolation()
);

} else if (boost::ends_with(lcase_file, ".cahvor") ||
boost::ends_with(lcase_file, ".cmod") ) {
CAHVORModel left_cahvor (left_camera_file );
CAHVORModel right_cahvor(right_camera_file);
left_image_out = camera_transform(left_image_in, left_cahvor, *left_epipolar_cahv );
right_image_out = camera_transform(right_image_in, right_cahvor, *right_epipolar_cahv);
left_image_out = camera_transform(left_image_in, left_cahvor, *left_epipolar_cahv,
edge_ext, BilinearInterpolation()
);
right_image_out = camera_transform(right_image_in, right_cahvor, *right_epipolar_cahv,
edge_ext, BilinearInterpolation()
);

} else if ( boost::ends_with(lcase_file, ".cahv") ||
boost::ends_with(lcase_file, ".pin" )) {
CAHVModel left_cahv (left_camera_file );
CAHVModel right_cahv(right_camera_file);
left_image_out = camera_transform(left_image_in, left_cahv, *left_epipolar_cahv );
right_image_out = camera_transform(right_image_in, right_cahv, *right_epipolar_cahv);
left_image_out = camera_transform(left_image_in, left_cahv, *left_epipolar_cahv,
edge_ext, BilinearInterpolation()
);
right_image_out = camera_transform(right_image_in, right_cahv, *right_epipolar_cahv,
edge_ext, BilinearInterpolation()
);

} else if ( boost::ends_with(lcase_file, ".pinhole") ||
boost::ends_with(lcase_file, ".tsai") ) {
Expand All @@ -274,8 +287,12 @@ void get_epipolar_transformed_images(std::string const& left_camera_file,
update_pinhole_for_fast_point2pixel(left_pin, left_image_size );
update_pinhole_for_fast_point2pixel(right_pin, right_image_size);

left_image_out = camera_transform(left_image_in, left_pin, *left_epipolar_cahv );
right_image_out = camera_transform(right_image_in, right_pin, *right_epipolar_cahv);
left_image_out = camera_transform(left_image_in, left_pin, *left_epipolar_cahv,
edge_ext, BilinearInterpolation()
);
right_image_out = camera_transform(right_image_in, right_pin, *right_epipolar_cahv,
edge_ext, BilinearInterpolation()
);

} else {
vw_throw(ArgumentErr() << "get_epipolar_transformed_images: unsupported camera file type.\n");
Expand Down Expand Up @@ -346,7 +363,8 @@ void get_epipolar_transformed_pinhole_images(std::string const& left_camera_file
Vector2i const& left_image_out_size,
Vector2i const& right_image_out_size,
ImageOutT & left_image_out,
ImageOutT & right_image_out) {
ImageOutT & right_image_out,
ValueEdgeExtension<typename ImageOutT::pixel_type> edge_ext) {

// Cast input camera models to Pinhole
PinholeModel* left_epipolar_pin = dynamic_cast<PinholeModel*>(vw::camera::unadjusted_model(&(*left_camera )));
Expand All @@ -364,8 +382,14 @@ void get_epipolar_transformed_pinhole_images(std::string const& left_camera_file
update_pinhole_for_fast_point2pixel(right_pin, right_image_in_size);

// Transform the images
left_image_out = camera_transform(left_image_in, left_pin, *left_epipolar_pin, left_image_out_size );
right_image_out = camera_transform(right_image_in, right_pin, *right_epipolar_pin, right_image_out_size);
left_image_out = camera_transform(left_image_in, left_pin, *left_epipolar_pin,
left_image_out_size,
edge_ext, BilinearInterpolation()
);
right_image_out = camera_transform(right_image_in, right_pin, *right_epipolar_pin,
right_image_out_size,
edge_ext, BilinearInterpolation()
);
}


Expand Down
24 changes: 4 additions & 20 deletions src/vw/tools/ipalign.cc
Original file line number Diff line number Diff line change
Expand Up @@ -258,24 +258,6 @@ void align_images( Options & opt ) {

ImageView< PixelRGB<uint8> > left_aligned2, right_aligned2;

/*
// Load both input images as CAHV models.
boost::shared_ptr<CAHVModel> left_cahv, right_cahv;
left_cahv = load_cahv_pinhole_camera_model(opt.left_image_file, opt.left_camera_file );
right_cahv = load_cahv_pinhole_camera_model(opt.right_image_file, opt.right_camera_file);
// Generate epipolar-aligned camera models
boost::shared_ptr<CAHVModel> epipolar_left_cahv (new CAHVModel);
boost::shared_ptr<CAHVModel> epipolar_right_cahv(new CAHVModel);
epipolar(*(left_cahv.get()), *(right_cahv.get()),
*(epipolar_left_cahv.get()), *(epipolar_right_cahv.get()));
get_epipolar_transformed_images(opt.left_camera_file, opt.right_camera_file,
epipolar_left_cahv, epipolar_right_cahv,
ref_image, input_image,
left_aligned2, right_aligned2);
*/

//// Load input pinhole cameras
PinholeModel left_pin (opt.left_camera_file );
PinholeModel right_pin(opt.right_camera_file);
Expand All @@ -293,12 +275,14 @@ void align_images( Options & opt ) {
epi_size1, epi_size2);


// Generate epipolar images
// Zero edge extension. Not ideal. One better create a mask or something.
PixelRGB<uint8> Zero = PixelRGB<uint8>(0);
get_epipolar_transformed_pinhole_images(opt.left_camera_file, opt.right_camera_file,
epipolar_left_pin, epipolar_right_pin,
ref_image, input_image,
epi_size1, epi_size2,
left_aligned2, right_aligned2);
left_aligned2, right_aligned2,
ValueEdgeExtension< PixelRGB<uint8> >(Zero));

std::string output_path = opt.output_prefix + "_right_image.tif";
write_image(output_path, crop(edge_extend(right_aligned2,ZeroEdgeExtension()),bounding_box(left_aligned2)),
Expand Down

0 comments on commit fc527d9

Please sign in to comment.