30 #ifndef IMAGE_UTIL_IMAGE_WARP_UTIL_H_ 31 #define IMAGE_UTIL_IMAGE_WARP_UTIL_H_ 36 #include <boost/circular_buffer.hpp> 42 #include <opencv2/core/core.hpp> 43 #include <opencv2/highgui/highgui.hpp> 44 #include <opencv2/features2d/features2d.hpp> 45 #include <opencv2/calib3d/calib3d.hpp> 46 #include <opencv2/stitching/detail/warpers.hpp> 53 cv::Mat
WarpImage(
const cv::Mat& image,
double roll,
double pitch);
67 const cv::Size& image_size,
68 const cv::Mat& pts_in,
83 const cv::Size& image_size,
84 const std::vector<cv::KeyPoint>& pts_in,
85 std::vector<cv::KeyPoint>& pts_out);
97 cv::Mat
GetR(
double pitch,
double roll,
double yaw = 0.0);
121 double& nominal_roll,
122 bool show_image_diff =
false);
132 const cv::Mat& points2,
133 const cv::Size& image_size,
134 double& nominal_pitch,
135 double& nominal_roll);
144 std::vector<cv::KeyPoint>
kp1_;
145 std::vector<cv::KeyPoint>
kp2_;
192 const cv::Mat& pts_in,
203 const cv::Mat& pts_in,
227 void SetBufferSize(int32_t buff_size = 50);
245 const cv::Size& image_size,
246 bool use_median =
true);
256 void GenerateNewEstimate(
const cv::Mat& points1,
257 const cv::Mat& points2,
258 const cv::Size& image_size);
266 void LoadNewData(
double new_pitch,
279 bool GetMeanPitchAndRoll(
double& pitch,
293 bool GetMedianPitchAndRoll(
double& pitch,
312 #endif // IMAGE_UTIL_IMAGE_WARP_UTIL_H_
std::vector< cv::KeyPoint > kp2_
boost::circular_buffer< double > pitches_
static bool EstimateTransforms(cv::Mat &pts1, cv::Mat &pts2, cv::Mat &T_affine, cv::Mat &T_rigid, double &rms_error)
Estimates the "nearest" rigid, and corresponding full affine transformation for a set of matching poi...
bool ComputeGeometricMatches()
Matches keypoints using loose geometric constraints and stores them in kp1_matched_ and kp2_matched_...
void WarpPoints(double pitch, double roll, const cv::Mat &pts_in, cv::Mat &pts_out)
Warps a matrix of points (in the same form as the inliers)
PitchAndRollEstimator()
Constructor.
A class for estimating image warping based on perspective distortion. Primarily intended for use with...
cv::detail::PlaneWarper warper_
void WarpAffinePoints(const cv::Mat &T, const cv::Mat &pts_in, cv::Mat &pts_out)
Warps a matrix of points (in the same form as the inliers)
boost::circular_buffer< double > rolls_
void WarpPoints(double pitch, double roll, const cv::Size &image_size, const cv::Mat &pts_in, cv::Mat &pts_out)
cv::Mat WarpImage(const cv::Mat &image, double roll, double pitch)
~PitchAndRollEstimatorQueue()
cv::Mat GetR(double pitch, double roll, double yaw=0.0)
Gets the rotation matrix associated with the specified pitch and roll values.
std::vector< cv::KeyPoint > kp1_
cv::Mat EstimateNominalAngle(double &nominal_pitch, double &nominal_roll, bool show_image_diff=false)
Estimates the nominal pitch and roll of the camera (from perfectly vertical) from two overlapping ima...
A class for estimating image warping based on perspective distortion. Primarily intended for use with...