39 bool enb_light_compen,
bool enb_refine_align,
40 bool save_unwarped, std::string map_path )
41 : m_ws_org(width), m_hs_org(height), m_in_fovd(195.0
f), m_inner_fovd(183.0
f),
42 m_enb_light_compen(enb_light_compen), m_enb_refine_align(enb_refine_align),
43 m_save_unwarped(save_unwarped), m_map_path(map_path)
45 CV_Assert( (width % 2 == 0) && (height % 2 == 0) );
48 m_ws =
static_cast<int>(width / 2);
50 CV_Assert( (
m_ws % 2 == 0) && (
m_hs % 2 == 0) );
56 m_hd =
static_cast<int>(std::floor(
m_wd / 2));
57 m_wd2 =
static_cast<int>(std::floor(
m_wd / 2));
58 m_hd2 =
static_cast<int>(std::floor(
m_hd / 2));
61 std::cout <<
"Initializing necessary parameters..\n";
77 cv::Mat dst(src.size(), src.type());
78 remap(src, dst,
m_map_x,
m_map_y, cv::INTER_LINEAR, cv::BORDER_CONSTANT,
87 std::tuple<double, double>
91 double phi, theta,
r,
s;
94 theta = -y_dest / W_rad + CV_PI / 2;
103 theta = CV_PI - (theta - CV_PI);
110 r =
sqrt(v[1] * v[1] + v[0] * v[0]);
111 theta = W_rad *
atan2(r, s *
cos(phi));
113 double x_src = theta * v[0] / r;
114 double y_src = theta * v[1] / r;
116 return std::make_tuple(x_src, y_src);
130 cv::Mat map_x(
m_hd,
m_wd, CV_32FC1);
131 cv::Mat map_y(
m_hd,
m_wd, CV_32FC1);
132 double w_rad =
m_wd / (2.0 * CV_PI);
135 double w2 =
static_cast<double>(
m_wd2) - 0.5;
136 double h2 =
static_cast<double>(
m_hd2) - 0.5;
137 double ws2 =
static_cast<double>(
m_ws2) - 0.5;
138 double hs2 =
static_cast<double>(
m_hs2) - 0.5;
143 y_d =
static_cast<double>(
y) - h2;
146 x_d =
static_cast<double>(
x) - w2;
149 std::tie(x_s, y_s) =
fish2Eqt(x_d, y_d, w_rad);
156 map_x.at<
float>(
y,
x) = static_cast<float>(x_s);
157 map_y.at<
float>(y,
x) = static_cast<float>(y_s);
174 cv::Mat cir_mask_ = cv::Mat(
m_hs,
m_ws, CV_8UC3);
175 cv::Mat inner_cir_mask_ = cv::Mat(
m_hs,
m_ws, CV_8UC3);
177 int wShift =
static_cast<int>(std::floor(
182 int r2 =
m_ws2 - wShift * 2;
184 cv::Scalar(255, 255, 255), -1, 8, 0);
186 cv::Scalar(255, 255, 255), -1, 8, 0);
189 cv::Mat inner_cir_mask;
190 cir_mask_.convertTo(cir_mask, CV_8UC3);
191 inner_cir_mask_.convertTo(inner_cir_mask, CV_8UC3);
205 cv::Mat dst(src.size(), src.type());
207 cv::BORDER_CONSTANT, cv::Scalar(0, 0, 0));
230 cv::Mat x_coor = cv::Mat::zeros(1, W_, CV_32F);
231 cv::Mat temp(x_coor.size(), x_coor.type());
233 for (
int i = 0; i < W_; ++i)
235 x_coor.at<
float>(0, i) = i;
243 cv::Mat R_pf = cv::Mat::zeros(x_coor.size(), x_coor.type());
244 cv::pow(x_coor, 5.0, temp);
245 R_pf = R_pf +
P1_ * temp;
246 cv::pow(x_coor, 4.0, temp);
247 R_pf = R_pf +
P2_ * temp;
248 cv::pow(x_coor, 3.0, temp);
249 R_pf = R_pf +
P3_ * temp;
250 cv::pow(x_coor, 2.0, temp);
251 R_pf = R_pf +
P4_ * temp;
252 R_pf = R_pf +
P5_ * x_coor +
P6_;
255 cv::divide(1, R_pf, R_pf);
261 cv::Mat scale_map_quad_4 = cv::Mat::zeros(H_, W_, R_pf.type());
262 float da = R_pf.at<
float>(0, W_ - 1);
266 for (x = 0; x < W_; ++x)
268 for (y = 0; y < H_; ++y)
270 r = std::floor(
sqrt(std::pow(x, 2) + std::pow(y, 2)));
273 scale_map_quad_4.at<
float>(y, x) = da;
277 a = R_pf.at<
float>(0, r);
278 if ((x < W_) && (y < H_))
279 b = R_pf.at<
float>(0, r + 1);
281 b = R_pf.at<
float>(0, r);
282 scale_map_quad_4.at<
float>(y, x) = (a + b) / 2.0f;
288 cv::Mat scale_map_quad_1(scale_map_quad_4.size(), scale_map_quad_4.type());
289 cv::Mat scale_map_quad_2(scale_map_quad_4.size(), scale_map_quad_4.type());
290 cv::Mat scale_map_quad_3(scale_map_quad_4.size(), scale_map_quad_4.type());
292 cv::flip(scale_map_quad_4, scale_map_quad_1, 0);
293 cv::flip(scale_map_quad_4, scale_map_quad_3, 1);
294 cv::flip(scale_map_quad_1, scale_map_quad_2, 1);
296 cv::Mat quad_21, quad_34;
297 cv::hconcat(scale_map_quad_2, scale_map_quad_1, quad_21);
298 cv::hconcat(scale_map_quad_3, scale_map_quad_4, quad_34);
301 cv::vconcat(quad_21, quad_34, scale_map);
316 cv::Mat rgb_ch_double[3];
317 cv::Mat out_img_double(in_img.size(), in_img.type());
318 cv::split(in_img, rgb_ch);
319 rgb_ch[0].convertTo(rgb_ch_double[0],
m_scale_map.type());
320 rgb_ch[1].convertTo(rgb_ch_double[1],
m_scale_map.type());
321 rgb_ch[2].convertTo(rgb_ch_double[2],
m_scale_map.type());
323 rgb_ch_double[0] = rgb_ch_double[0].mul(
m_scale_map);
324 rgb_ch_double[1] = rgb_ch_double[1].mul(
m_scale_map);
325 rgb_ch_double[2] = rgb_ch_double[2].mul(
m_scale_map);
326 cv::merge(rgb_ch_double, 3, out_img_double);
329 out_img_double.convertTo(out_img, CV_8U);
342 cv::Mat inner_cir_mask_n;
343 cv::Mat ring_mask, ring_mask_unwarped;
350 m_cir_mask.copyTo(ring_mask, inner_cir_mask_n);
353 std::cout <<
"Ws = " <<
m_ws <<
", Hs = " <<
m_hs <<
"\n";
354 std::cout <<
"Wd = " <<
m_wd <<
", Hd = " <<
m_hd <<
"\n";
356 cv::imwrite(
"ring_mask.jpg", ring_mask);
359 cv::remap(ring_mask, ring_mask_unwarped,
m_map_x,
m_map_y, cv::INTER_LINEAR,
360 cv::BORDER_CONSTANT, cv::Scalar(0, 0, 0));
362 cv::Mat mask_ = ring_mask_unwarped(cv::Rect(Wd2-Ws2, 0,
m_ws, m_hd));
363 mask_.convertTo(mask_, CV_8UC3);
366 cv::imwrite(
"mask_.jpg", mask_);
369 int H_ = mask_.size().height;
370 int W_ = mask_.size().width;
375 const int first_zero_col = 120;
376 const int first_zero_row = 45;
379 for( ridx=0; ridx < H_; ++ridx)
381 if( cidx < first_zero_col || cidx > W_-first_zero_col )
383 mask_.at<cv::Vec3b>(cv::Point(cidx,ridx)) = cv::Vec3b(255,255,255);
386 for( ridx=0; ridx < H_; ++ridx )
388 for( cidx=0; cidx < W_; ++cidx )
390 if( (ridx < (static_cast<int>(H_/2)) ) &&
391 (cidx > first_zero_col - 1) &&
392 (cidx < W_ - first_zero_col + 1) )
394 mask_.at<cv::Vec3b>(cv::Point(cidx,ridx)) = cv::Vec3b(0, 0, 0);
401 for( ridx=0; ridx < H_; ++ridx )
403 if( ridx > H_ - first_zero_row )
408 for( cidx=first_zero_col-10; cidx < W_/2+10; ++cidx )
410 cv::Vec3b color = mask_.at<cv::Vec3b>(cv::Point(cidx,ridx));
411 if( color == cv::Vec3b(0,0,0))
421 mask_.convertTo( binary_mask, CV_8UC3 );
425 std::cout <<
"size mask_ = " << mask_.size() <<
", type = " << mask_.type()
426 <<
", ch = " << mask_.channels() <<
"\n";
427 cv::imwrite(
"binary_mask.jpg", binary_mask);
462 cv::Mat mls_map_x, mls_map_y;
464 cv::FileStorage fs(
m_map_path, cv::FileStorage::READ);
467 fs[
"Xd"] >> mls_map_x;
468 fs[
"Yd"] >> mls_map_y;
473 CV_Error_(cv::Error::StsBadArg,
474 (
"Cannot open map file1: %s",
m_map_path.c_str()));
491 const std::string &img_window,
492 const bool disable_display )
494 cv::Point2f matchLoc;
495 double tickStart, tickEnd, runTime;
497 cv::Mat templ = Tmpl;
498 cv::Mat img_display,
result;
499 img.copyTo(img_display);
500 int result_cols = img.cols - templ.cols + 1;
501 int result_rows = img.rows - templ.rows + 1;
502 result.create(result_rows, result_cols, CV_32FC1);
505 int match_method = cv::TM_CCORR_NORMED;
508 cv::matchTemplate(img, templ, result, match_method);
509 cv::normalize(result, result, 0, 1, cv::NORM_MINMAX, -1, cv::Mat());
512 double minVal, maxVal;
513 cv::Point minLoc, maxLoc;
516 cv::minMaxLoc(result, &minVal, &maxVal, &minLoc, &maxLoc, cv::Mat());
518 if (match_method == cv::TM_SQDIFF || match_method == cv::TM_SQDIFF_NORMED)
527 if (!disable_display)
529 cv::rectangle(img_display, matchLoc,
530 cv::Point(matchLoc.x + templ.cols, matchLoc.y + templ.rows),
531 cv::Scalar(0, 255, 0), 2, 8, 0);
533 cv::hconcat(img_display, Tmpl, RefTemplCat);
534 cv::imshow(img_window, RefTemplCat);
545 std::tuple<std::vector<cv::Point2f>, std::vector<cv::Point2f> >
547 const cv::Point2f &matchLocRight,
const int row_start,
548 const int row_end,
const int p_wid,
const int p_x1,
549 const int p_x2,
const int p_x2_ref )
551 std::vector<cv::Point2f> movingPoints;
552 std::vector<cv::Point2f> fixedPoints;
554 float x1 = matchLocLeft.x;
555 float y1 = matchLocLeft.y;
556 float x2 = matchLocRight.x;
557 float y2 = matchLocRight.y;
563 movingPoints.push_back(cv::Point2f(x1, y1 + row_start));
564 movingPoints.push_back(cv::Point2f(x1 + p_wid, y1 + row_start));
565 movingPoints.push_back(cv::Point2f(x1, y1 + row_end));
566 movingPoints.push_back(cv::Point2f(x1 + p_wid, y1 + row_end));
568 movingPoints.push_back(cv::Point2f(x2 + p_x2_ref, y2 + row_start));
569 movingPoints.push_back(cv::Point2f(x2 + p_x2_ref + p_wid, y2 + row_start));
570 movingPoints.push_back(cv::Point2f(x2 + p_x2_ref, y2 + row_end));
571 movingPoints.push_back(cv::Point2f(x2 + p_x2_ref + p_wid, y2 + row_end));
577 fixedPoints.push_back(cv::Point2f(p_x1, row_start));
578 fixedPoints.push_back(cv::Point2f(p_x1 + p_wid, row_start));
579 fixedPoints.push_back(cv::Point2f(p_x1, row_end));
580 fixedPoints.push_back(cv::Point2f(p_x1 + p_wid, row_end));
582 fixedPoints.push_back(cv::Point2f(p_x2, row_start));
583 fixedPoints.push_back(cv::Point2f(p_x2 + p_wid, row_start));
584 fixedPoints.push_back(cv::Point2f(p_x2, row_end));
585 fixedPoints.push_back(cv::Point2f(p_x2 + p_wid, row_end));
587 return std::make_tuple(movingPoints, fixedPoints);
600 int h = bg1.size().height;
601 int w = bg1.size().width;
602 double wdb =
static_cast<double>(
w);
603 cv::Mat bg_ = cv::Mat::zeros(bg1.size(), CV_32F);
604 double alpha1, alpha2;
606 bg1.convertTo(bg1_, CV_32F);
607 bg2.convertTo(bg2_, CV_32F);
609 cv::Mat bgr_bg[3], bgr_bg1[3], bgr_bg2[3];
610 split(bg1_, bgr_bg1);
611 split(bg2_, bgr_bg2);
613 bgr_bg[0] = cv::Mat::zeros(bgr_bg1[1].size(), CV_32F);
614 bgr_bg[1] = cv::Mat::zeros(bgr_bg1[1].size(), CV_32F);
615 bgr_bg[2] = cv::Mat::zeros(bgr_bg1[1].size(), CV_32F);
617 for (
int r = 0;
r <
h; ++
r)
619 for (
int c = 0;
c <
w; ++
c)
621 alpha1 =
static_cast<double>(
c) / wdb;
622 alpha2 = 1.0 - alpha1;
623 bgr_bg[0].at<
float>(
r,
c) = alpha1*bgr_bg1[0].at<float>(r,
c) +
624 alpha2*bgr_bg2[0].at<
float>(r,
c);
625 bgr_bg[1].at<
float>(r,
c) = alpha1*bgr_bg1[1].at<float>(r,
c) +
626 alpha2*bgr_bg2[1].at<
float>(r,
c);
627 bgr_bg[2].at<
float>(r,
c) = alpha1*bgr_bg1[2].at<float>(r,
c) +
628 alpha2*bgr_bg2[2].at<
float>(r,
c);
632 cv::merge(bgr_bg, 3, bg);
633 bg.convertTo(bg, CV_8U);
647 int h = bg1.size().height;
648 int w = bg1.size().width;
649 double wdb =
static_cast<double>(
w);
650 cv::Mat bg_ = cv::Mat::zeros(bg1.size(), CV_32F);
651 double alpha1, alpha2;
653 bg1.convertTo(bg1_, CV_32F);
654 bg2.convertTo(bg2_, CV_32F);
656 cv::Mat bgr_bg[3], bgr_bg1[3], bgr_bg2[3];
657 split(bg1_, bgr_bg1);
658 split(bg2_, bgr_bg2);
660 bgr_bg[0] = cv::Mat::zeros(bgr_bg1[1].size(), CV_32F);
661 bgr_bg[1] = cv::Mat::zeros(bgr_bg1[1].size(), CV_32F);
662 bgr_bg[2] = cv::Mat::zeros(bgr_bg1[1].size(), CV_32F);
664 for (
int r = 0;
r <
h; ++
r)
666 for (
int c = 0;
c <
w; ++
c)
668 alpha1 = (wdb -
c + 1) / wdb;
669 alpha2 = 1.0 - alpha1;
670 bgr_bg[0].at<
float>(
r,
c) = alpha1*bgr_bg1[0].at<float>(r,
c) +
671 alpha2*bgr_bg2[0].at<
float>(r,
c);
672 bgr_bg[1].at<
float>(r,
c) = alpha1*bgr_bg1[1].at<float>(r,
c) +
673 alpha2*bgr_bg2[1].at<
float>(r,
c);
674 bgr_bg[2].at<
float>(r,
c) = alpha1*bgr_bg1[2].at<float>(r,
c) +
675 alpha2*bgr_bg2[2].at<
float>(r,
c);
679 cv::merge(bgr_bg, 3, bg);
680 bg.convertTo(bg, CV_8U);
694 const cv::Mat &right_img_aligned )
699 cv::FileStorage fs(
"./utils/post_find.yml", cv::FileStorage::READ);
700 fs[
"post_ret"] >> post;
703 cv::Mat mask = imread(
"./utils/mask_1920x1920_fovd_187.jpg", cv::IMREAD_COLOR);
709 int H = mask.size().height;
710 int W = mask.size().width;
717 int imH = left_img.size().height;
718 int imW = left_img.size().width;
719 cv::Mat left_img_cr = left_img(cv::Rect(imW / 2 + 1 - Worg / 2, 0, Worg, imH));
722 cv::Mat left_blend, right_blend;
724 for (
int r = 0;
r < H; ++
r)
727 int p = post.at<
float>(
r, 0);
736 cv::Mat lf_win_1 = left_img_cr(cv::Rect(p - sideW, r, 2 * sideW, 1));
737 cv::Mat rt_win_1 = right_img_aligned(cv::Rect(p - sideW, r, 2 * sideW, 1));
739 cv::Mat lf_win_2 = left_img_cr(cv::Rect((W - p - sideW), r, 2 * sideW, 1));
740 cv::Mat rt_win_2 = right_img_aligned(cv::Rect((W - p - sideW), r, 2 * sideW, 1));
742 cv::Mat bleft, bright;
746 bleft.copyTo(lf_win_1);
747 bleft.copyTo(rt_win_1);
749 bright.copyTo(lf_win_2);
750 bright.copyTo(rt_win_2);
754 cv::imwrite(
"left_crop_blend.jpg", left_img_cr);
755 cv::imwrite(
"right_blend.jpg", right_img_aligned);
761 cv::Mat mask_ = mask(cv::Rect(0, 0, mask.size().width,
762 mask.size().height - 2));
764 bitwise_not(mask_, mask_n);
765 bitwise_and(left_img_cr, mask_, left_img_cr);
767 cv::Mat temp1 = left_img(cv::Rect(0, 0, (imW / 2 - Worg / 2), imH));
768 cv::Mat temp2 = left_img(cv::Rect((imW / 2 + Worg / 2), 0,
769 (imW / 2 - Worg / 2), imH));
771 cv::hconcat(temp1, left_img_cr, t);
772 cv::hconcat(t, temp2, left_img);
774 bitwise_and(right_img_aligned, mask_n, right_img_aligned);
778 cv::Mat temp = pano(cv::Rect((imW / 2 - Worg / 2), 0, Worg, imH));
780 cv::bitwise_or(temp, right_img_aligned, t2);
799 cv::Mat left_unwarped, right_unwarped;
800 double tickStart, tickEnd, runTime;
803 tickStart =
static_cast<double>(cv::getTickCount());
809 cv::bitwise_and(in_img_L,
m_cir_mask, in_img_L);
810 cv::bitwise_and(in_img_R,
m_cir_mask, in_img_R);
813 tickEnd =
static_cast<double>(cv::getTickCount());
814 runTime = (tickEnd - tickStart) / cv::getTickFrequency();
816 std::cout <<
"run-time (Crop) = " << runTime <<
" (sec)" <<
"\n";
822 cv::Mat left_img_compensated(in_img_L.size(), in_img_L.type());
823 cv::Mat right_img_compensated(in_img_R.size(), in_img_R.type());
826 left_img_compensated = in_img_L;
827 right_img_compensated = in_img_R;
836 tickEnd =
static_cast<double>(cv::getTickCount());
837 runTime = (tickEnd - tickStart) / cv::getTickFrequency();
839 std::cout <<
"run-time (LightCompen) = " << runTime <<
" (sec)" <<
"\n";
845 left_unwarped =
unwarp(left_img_compensated);
846 right_unwarped =
unwarp(right_img_compensated);
849 tickEnd =
static_cast<double>(cv::getTickCount());
850 runTime = (tickEnd - tickStart) / cv::getTickFrequency();
852 std::cout <<
"run-time (Unwarp) = " << runTime <<
" (sec)" <<
"\n";
856 cv::imwrite(
"l.jpg", left_unwarped);
857 cv::imwrite(
"r.jpg", right_unwarped);
861 tickStart =
static_cast<double>(cv::getTickCount());
867 cv::Mat rightImg_crop, rightImg_mls_deformed;
868 rightImg_crop = right_unwarped(cv::Rect(
int(
m_wd / 2) - (W_in / 2), 0,
870 rightImg_mls_deformed =
deform(rightImg_crop);
873 cv::imwrite(
"r_img_crop.jpg", rightImg_crop);
874 cv::imwrite(
"r_mls_deformed.jpg",rightImg_mls_deformed);
878 tickEnd =
static_cast<double>(cv::getTickCount());
879 runTime = (tickEnd - tickStart) / cv::getTickFrequency();
881 std::cout <<
"run-time (MLS Deform) = " << runTime <<
" (sec)" <<
"\n";
887 cv::Mat temp1 = left_unwarped(cv::Rect(0, 0,
m_wd2,
m_hd - 2));
888 cv::Mat temp2 = left_unwarped(cv::Rect(
m_wd2, 0,
m_wd2,
890 cv::Mat left_unwarped_arr;
891 cv::hconcat(temp2, temp1, left_unwarped_arr);
892 cv::Mat leftImg_crop;
893 leftImg_crop = left_unwarped_arr(cv::Rect(
m_wd2 - (W_in / 2), 0,
902 uint16_t p_x1 = 90 - 15;
903 uint16_t p_x2 = 1780 - 5;
904 uint16_t p_x1_ref = 2 * crop;
905 uint16_t row_start = 590;
906 uint16_t row_end = 1320;
907 uint16_t p_x2_ref =
m_ws - 2 * crop + 1;
909 cv::Mat Ref_1, Ref_2, Tmpl_1, Tmpl_2;
910 Ref_1 = leftImg_crop(cv::Rect(0, row_start, p_x1_ref, row_end - row_start));
911 Ref_2 = leftImg_crop(cv::Rect(p_x2_ref, row_start,
m_ws - p_x2_ref, row_end - row_start));
912 Tmpl_1 = rightImg_mls_deformed(cv::Rect(p_x1, row_start, p_wid, row_end - row_start));
913 Tmpl_2 = rightImg_mls_deformed(cv::Rect(p_x2, row_start, p_wid, row_end - row_start));
916 cv::imwrite(
"l_img_crop.jpg", leftImg_crop);
917 cv::imwrite(
"Ref_1.jpg", Ref_1);
918 cv::imwrite(
"Ref_2.jpg", Ref_2);
919 cv::imwrite(
"Tmpl_1.jpg", Tmpl_1);
920 cv::imwrite(
"Tmpl_2.jpg", Tmpl_2);
926 bool disable_display = 1;
927 std::string wname1 =
"Matching On Left Boundary";
928 std::string wname2 =
"Matching On Right Boundary";
931 tickStart =
static_cast<double>(cv::getTickCount());
934 cv::Mat warpedRightImg;
937 warpedRightImg = rightImg_mls_deformed;
944 cv::Point2f matchLocLeft, matchLocRight;
945 matchLocLeft =
findMatchLoc(Ref_1, Tmpl_1, wname1, disable_display);
946 matchLocRight =
findMatchLoc(Ref_2, Tmpl_2, wname2, disable_display);
949 std::cout <<
"matchLocLeft(x=" << matchLocLeft.x
950 <<
", y=" << matchLocLeft.y
951 <<
"), matchLocRight(x=" << matchLocRight.x
952 <<
", y=" << matchLocRight.y <<
")\n";
958 std::vector<cv::Point2f> movingPoints;
959 std::vector<cv::Point2f> fixedPoints;
961 std::tie(movingPoints, fixedPoints) =
963 p_wid, p_x1, p_x2, p_x2_ref);
966 tickEnd =
static_cast<double>(cv::getTickCount());
967 runTime = (tickEnd - tickStart) / cv::getTickFrequency();
969 std::cout <<
"run-time (Xcorr & fitGeoTrans) = " << runTime <<
" (sec)" <<
"\n";
975 cv::Mat tform_refine_mat;
976 tform_refine_mat = cv::findHomography(fixedPoints, movingPoints, 0);
981 cv::warpPerspective(rightImg_mls_deformed, warpedRightImg,
982 tform_refine_mat, rightImg_mls_deformed.size(),
986 tickEnd =
static_cast<double>(cv::getTickCount());
987 runTime = (tickEnd - tickStart) / cv::getTickFrequency();
989 std::cout <<
"run-time (estimate tform_mat & warping) = " << runTime <<
" (sec)" <<
"\n";
998 pano =
blend(left_unwarped_arr, warpedRightImg);
1001 tickEnd =
static_cast<double>(cv::getTickCount());
1002 runTime = (tickEnd - tickStart) / cv::getTickFrequency();
1003 tickStart = tickEnd;
1004 std::cout <<
"run-time (Blending) = " << runTime <<
" (sec)" <<
"\n";
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.
cv::Mat blendRight(const cv::Mat &bg1, const cv::Mat &bg2)
Ramp blending on the right patch.