#include <fisheye_stitcher.hpp>
| Public Member Functions | |
| FisheyeStitcher (int width, int height, float in_fovd, bool enb_light_compen, bool enb_refine_align, bool save_unwarped, std::string map_path) | |
| cv::Mat | stitch (const cv::Mat &image1, const cv::Mat &image2, uint16_t p_wid, uint16_t p_x1, uint16_t p_x2, uint16_t row_start, uint16_t row_end) | 
| single frame stitching  More... | |
| ~FisheyeStitcher () | |
| Private Member Functions | |
| cv::Mat | blend (const cv::Mat &left_img, const cv::Mat &right_img_aligned) | 
| Blending aligned images.  More... | |
| cv::Mat | blendLeft (const cv::Mat &bg1, const cv::Mat &bg2) | 
| Ramp blending on the left patch.  More... | |
| cv::Mat | blendRight (const cv::Mat &bg1, const cv::Mat &bg2) | 
| Ramp blending on the right patch.  More... | |
| cv::Mat | compenLightFO (const cv::Mat &in_img) | 
| Fisheye Light Fall-off Compensation.  More... | |
| void | createBlendMask () | 
| Create binary mask for blending.  More... | |
| 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.  More... | |
| void | createMask () | 
| Mask creation for cropping image data inside the FOVD circle.  More... | |
| cv::Mat | deform (const cv::Mat &in_img) | 
| Rigid Moving Least Squares Interpolation.  More... | |
| cv::Point2f | findMatchLoc (const cv::Mat &Ref, const cv::Mat &Tmpl, const std::string &img_window, const bool disable_display) | 
| Adaptive Alignment: Norm XCorr.  More... | |
| std::tuple< double, double > | fish2Eqt (const double x_dest, const double y_dest, const double W_rad) | 
| Convert fisheye-vertical to equirectangular (reference: Panotool)  More... | |
| void | fish2Map () | 
| Map 2D fisheye image to 2D projected sphere.  More... | |
| void | genScaleMap () | 
| Fisheye Light Fall-off Compensation: Scale_Map Construction.  More... | |
| void | init () | 
| cv::Mat | unwarp (const cv::Mat &in_img) | 
| Fisheye Unwarping.  More... | |
| Private Attributes | |
| cv::Mat | m_binary_mask | 
| std::vector< int > | m_blend_post | 
| cv::Mat | m_cir_mask | 
| bool | m_disable_light_compen | 
| bool | m_enb_light_compen | 
| bool | m_enb_refine_align | 
| int | m_hd | 
| int | m_hd2 | 
| int | m_hs | 
| int | m_hs2 | 
| int | m_hs_org | 
| float | m_in_fovd | 
| cv::Mat | m_inner_cir_mask | 
| float | m_inner_fovd | 
| std::string | m_map_path | 
| cv::Mat | m_map_x | 
| cv::Mat | m_map_y | 
| cv::Mat | m_mls_map_x | 
| cv::Mat | m_mls_map_y | 
| bool | m_save_unwarped | 
| cv::Mat | m_scale_map | 
| int | m_wd | 
| int | m_wd2 | 
| int | m_ws | 
| int | m_ws2 | 
| int | m_ws_org | 
Definition at line 62 of file fisheye_stitcher.hpp.
| stitcher::FisheyeStitcher::FisheyeStitcher | ( | int | width, | 
| int | height, | ||
| float | in_fovd, | ||
| bool | enb_light_compen, | ||
| bool | enb_refine_align, | ||
| bool | save_unwarped, | ||
| std::string | map_path | ||
| ) | 
Definition at line 38 of file fisheye_stitcher.cpp.
| stitcher::FisheyeStitcher::~FisheyeStitcher | ( | ) | 
Definition at line 65 of file fisheye_stitcher.cpp.
| 
 | private | 
Blending aligned images.
| left_img | left unwarped image | 
| right_img_aligned | aligned right image | 
| return | blended image | 
Definition at line 693 of file fisheye_stitcher.cpp.
| 
 | private | 
Ramp blending on the left patch.
| bg1 | first patch | 
| bg2 | second patch | 
| return | blended patch | 
Definition at line 645 of file fisheye_stitcher.cpp.
| 
 | private | 
Ramp blending on the right patch.
| bg1 | first patch | 
| bg2 | second patch | 
| return | blended patch | 
Definition at line 598 of file fisheye_stitcher.cpp.
| 
 | private | 
Fisheye Light Fall-off Compensation.
| in_img | LFO-uncompensated image | 
| return | LFO-compensated image | 
Definition at line 313 of file fisheye_stitcher.cpp.
| 
 | private | 
Create binary mask for blending.
Update member masks.
Definition at line 340 of file fisheye_stitcher.cpp.
| 
 | private | 
Construct control points for affine2D.
| movingPoints | return match points of template on reference | 
| fixedPoints | return match points of template on template | 
Definition at line 546 of file fisheye_stitcher.cpp.
| 
 | private | 
Mask creation for cropping image data inside the FOVD circle.
Update member m_cir_mask (circular mask), inner_cir_mask (circular mask for the inner circle).
Definition at line 172 of file fisheye_stitcher.cpp.
| 
 | private | 
Rigid Moving Least Squares Interpolation.
| src | source image | 
| return | deformed image | 
Definition at line 203 of file fisheye_stitcher.cpp.
| 
 | private | 
Adaptive Alignment: Norm XCorr.
| Ref | reference image | 
| Tmpl | template image | 
| return | matching location | 
Definition at line 489 of file fisheye_stitcher.cpp.
| 
 | private | 
Convert fisheye-vertical to equirectangular (reference: Panotool)
Definition at line 88 of file fisheye_stitcher.cpp.
| 
 | private | 
Map 2D fisheye image to 2D projected sphere.
| map_x | map for x element. | 
| map_y | map for y element. | 
Update member grid maps m_map_x, m_map_y
Definition at line 128 of file fisheye_stitcher.cpp.
| 
 | private | 
Fisheye Light Fall-off Compensation: Scale_Map Construction.
| R_pf | everse profile model Update member m_scale_map | 
Definition at line 219 of file fisheye_stitcher.cpp.
| 
 | private | 
Definition at line 436 of file fisheye_stitcher.cpp.
| cv::Mat stitcher::FisheyeStitcher::stitch | ( | const cv::Mat & | in_img_L, | 
| const cv::Mat & | in_img_R, | ||
| uint16_t | p_wid, | ||
| uint16_t | p_x1, | ||
| uint16_t | p_x2, | ||
| uint16_t | row_start, | ||
| uint16_t | row_end | ||
| ) | 
single frame stitching
| in_img_L | left image | 
| in_img_R | right image | 
| return | stitched image | 
Definition at line 795 of file fisheye_stitcher.cpp.
| 
 | private | 
Fisheye Unwarping.
Unwarp source fisheye -> 360x180 equirectangular
Definition at line 75 of file fisheye_stitcher.cpp.
| 
 | private | 
Definition at line 126 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 127 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 124 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 118 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 117 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 119 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 111 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 114 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 108 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 110 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 105 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 115 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 125 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 116 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 121 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 122 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 123 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 129 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 130 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 120 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 128 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 112 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 113 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 107 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 109 of file fisheye_stitcher.hpp.
| 
 | private | 
Definition at line 106 of file fisheye_stitcher.hpp.