33 #ifndef FISHEYE_STITCHER_HPP 34 #define FISHEYE_STITCHER_HPP 42 #include <opencv2/imgcodecs.hpp> 43 #include <opencv2/imgproc.hpp> 44 #include <opencv2/highgui.hpp> 45 #include <opencv2/calib3d.hpp> 46 #include "opencv2/stitching/detail/seam_finders.hpp" 47 #include <opencv2/core/utility.hpp> 49 #define MAX_FOVD 195.0f 52 #define P1_ -7.5625e-17 53 #define P2_ 1.9589e-13 54 #define P3_ -1.8547e-10 55 #define P4_ 6.1997e-08 56 #define P5_ -6.9432e-05 66 bool enb_light_compen,
bool enb_refine_align,
67 bool save_unwarped, std::string map_path);
69 cv::Mat
stitch(
const cv::Mat& image1,
const cv::Mat& image2);
72 cv::Mat
unwarp(
const cv::Mat &in_img);
73 std::tuple<double, double>
fish2Eqt(
const double x_dest,
78 cv::Mat
deform(
const cv::Mat &in_img);
86 const std::string &img_window,
87 const bool disable_display);
89 std::tuple<std::vector<cv::Point2f>, std::vector<cv::Point2f> >
91 const cv::Point2f &matchLocRight,
const int row_start,
92 const int row_end,
const int p_wid,
const int p_x1,
93 const int p_x2,
const int p_x2_ref);
95 cv::Mat
blendRight(
const cv::Mat &bg1,
const cv::Mat &bg2);
96 cv::Mat
blendLeft(
const cv::Mat &bg1,
const cv::Mat &bg2);
97 cv::Mat
blend(
const cv::Mat &left_img,
const cv::Mat &right_img_aligned);
131 #endif // FISHEYE_STITCHER_HPP
FisheyeStitcher(int width, int height, float in_fovd, bool enb_light_compen, bool enb_refine_align, bool save_unwarped, std::string map_path)
void createMask()
Mask creation for cropping image data inside the FOVD circle.
std::tuple< std::vector< cv::Point2f >, std::vector< cv::Point2f > > createControlPoints(const cv::Point2f &matchLocLeft, const cv::Point2f &matchLocRight, const int row_start, const int row_end, const int p_wid, const int p_x1, const int p_x2, const int p_x2_ref)
Construct control points for affine2D.
void genScaleMap()
Fisheye Light Fall-off Compensation: Scale_Map Construction.
cv::Mat blendLeft(const cv::Mat &bg1, const cv::Mat &bg2)
Ramp blending on the left patch.
cv::Point2f findMatchLoc(const cv::Mat &Ref, const cv::Mat &Tmpl, const std::string &img_window, const bool disable_display)
Adaptive Alignment: Norm XCorr.
cv::Mat stitch(const cv::Mat &image1, const cv::Mat &image2)
single frame stitching
void fish2Map()
Map 2D fisheye image to 2D projected sphere.
std::tuple< double, double > fish2Eqt(const double x_dest, const double y_dest, const double W_rad)
Convert fisheye-vertical to equirectangular (reference: Panotool)
cv::Mat deform(const cv::Mat &in_img)
Rigid Moving Least Squares Interpolation.
std::vector< int > m_blend_post
cv::Mat unwarp(const cv::Mat &in_img)
Fisheye Unwarping.
void createBlendMask()
Create binary mask for blending.
cv::Mat blend(const cv::Mat &left_img, const cv::Mat &right_img_aligned)
Blending aligned images.
cv::Mat compenLightFO(const cv::Mat &in_img)
Fisheye Light Fall-off Compensation.
bool m_disable_light_compen
cv::Mat blendRight(const cv::Mat &bg1, const cv::Mat &bg2)
Ramp blending on the right patch.