43 #include <opencv2/stitching/detail/matchers.hpp> 44 #include <opencv2/stitching/detail/motion_estimators.hpp> 53 std::vector<cv::detail::ImageFeatures> image_features;
54 std::vector<cv::detail::MatchesInfo> pairwise_matches;
55 std::vector<cv::detail::CameraParams> transforms;
56 std::vector<int> good_indices;
59 cv::Ptr<cv::detail::FeaturesMatcher> matcher =
60 cv::makePtr<cv::detail::AffineBestOf2NearestMatcher>();
61 cv::Ptr<cv::detail::Estimator> estimator =
62 cv::makePtr<cv::detail::AffineBasedEstimator>();
63 cv::Ptr<cv::detail::BundleAdjusterBase> adjuster =
64 cv::makePtr<cv::detail::BundleAdjusterAffinePartial>();
72 image_features.reserve(
images_.size());
73 for (
const cv::Mat& image :
images_) {
74 image_features.emplace_back();
76 #if CV_VERSION_MAJOR >= 4 77 cv::detail::computeImageFeatures(finder, image, image_features.back());
79 (*finder)(image, image_features.back());
87 (*matcher)(image_features, pairwise_matches);
96 good_indices = cv::detail::leaveBiggestComponent(
97 image_features, pairwise_matches, static_cast<float>(confidence));
102 if (good_indices.size() == 1) {
105 for (
size_t i = 0; i < images_.size(); ++i) {
106 if (!images_[i].empty()) {
116 ROS_DEBUG(
"calculating transforms in global reference frame");
118 if (!(*estimator)(image_features, pairwise_matches, transforms)) {
124 for (
auto& transform : transforms) {
125 transform.R.convertTo(transform.R, CV_32F);
127 ROS_DEBUG(
"optimizing global transforms");
128 adjuster->setConfThresh(confidence);
129 if (!(*adjuster)(image_features, pairwise_matches, transforms)) {
130 ROS_WARN(
"Bundle adjusting failed. Could not estimate transforms.");
137 for (
auto& j : good_indices) {
139 transforms[i].R.convertTo(
transforms_[static_cast<size_t>(j)], CV_64F);
149 if (matrix.empty()) {
152 cv::MatExpr
diff = matrix != cv::Mat::eye(matrix.size(), matrix.type());
153 return cv::countNonZero(diff) == 0;
167 std::vector<cv::Mat> imgs_warped;
168 imgs_warped.reserve(
images_.size());
169 std::vector<cv::Rect> rois;
172 for (
size_t i = 0; i <
images_.size(); ++i) {
174 imgs_warped.emplace_back();
180 if (imgs_warped.empty()) {
185 nav_msgs::OccupancyGrid::Ptr result;
187 result = compositor.
compose(imgs_warped, rois);
192 float any_resolution = 0.0;
196 result->info.resolution =
grids_[i]->info.resolution;
200 any_resolution =
grids_[i]->info.resolution;
203 if (result->info.resolution <= 0.f) {
204 result->info.resolution = any_resolution;
208 result->info.origin.position.x =
209 -(result->info.width / 2.0) * double(result->info.resolution);
210 result->info.origin.position.y =
211 -(result->info.height / 2.0) * double(result->info.resolution);
212 result->info.origin.orientation.w = 1.0;
219 std::vector<geometry_msgs::Transform> result;
223 if (transform.empty()) {
224 result.emplace_back();
229 geometry_msgs::Transform ros_transform;
230 ros_transform.translation.x = transform.at<
double>(0, 2);
231 ros_transform.translation.y = transform.at<
double>(1, 2);
232 ros_transform.translation.z = 0.;
235 double a = transform.at<
double>(0, 0);
236 double b = transform.at<
double>(1, 0);
237 ros_transform.rotation.w = std::sqrt(2. + 2. * a) * 0.5;
238 ros_transform.rotation.x = 0.;
239 ros_transform.rotation.y = 0.;
240 ros_transform.rotation.z = std::copysign(std::sqrt(2. - 2. * a) * 0.5, b);
242 result.push_back(ros_transform);
std::vector< cv::Mat > transforms_
std::vector< cv::Mat > images_
nav_msgs::OccupancyGrid::Ptr composeGrids()
cv::Rect warp(const cv::Mat &grid, const cv::Mat &transform, cv::Mat &warped_grid)
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
static void writeDebugMatchingInfo(const std::vector< cv::Mat > &images, const std::vector< cv::detail::ImageFeatures > &image_features, const std::vector< cv::detail::MatchesInfo > &pairwise_matches)
bool estimateTransforms(FeatureType feature=FeatureType::AKAZE, double confidence=1.0)
nav_msgs::OccupancyGrid::Ptr compose(const std::vector< cv::Mat > &grids, const std::vector< cv::Rect > &rois)
static bool isIdentity(const cv::Mat &matrix)
std::vector< geometry_msgs::Transform > getTransforms() const
static cv::Ptr< cv::detail::FeaturesFinder > chooseFeatureFinder(FeatureType type)
std::vector< nav_msgs::OccupancyGrid::ConstPtr > grids_