merging_pipeline.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015-2016, Jiri Horner.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the Jiri Horner nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  *********************************************************************/
36 
40 #include <ros/assert.h>
41 #include <ros/console.h>
42 
43 #include <opencv2/stitching/detail/matchers.hpp>
44 #include <opencv2/stitching/detail/motion_estimators.hpp>
45 
46 #include "estimation_internal.h"
47 
48 namespace combine_grids
49 {
51  double confidence)
52 {
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;
57  // TODO investigate value translation effect on features
58  auto finder = internal::chooseFeatureFinder(feature_type);
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>();
65 
66  if (images_.empty()) {
67  return true;
68  }
69 
70  /* find features in images */
71  ROS_DEBUG("computing features");
72  image_features.reserve(images_.size());
73  for (const cv::Mat& image : images_) {
74  image_features.emplace_back();
75  if (!image.empty()) {
76 #if CV_VERSION_MAJOR >= 4
77  cv::detail::computeImageFeatures(finder, image, image_features.back());
78 #else
79  (*finder)(image, image_features.back());
80 #endif
81  }
82  }
83  finder = {};
84 
85  /* find corespondent features */
86  ROS_DEBUG("pairwise matching features");
87  (*matcher)(image_features, pairwise_matches);
88  matcher = {};
89 
90 #ifndef NDEBUG
91  internal::writeDebugMatchingInfo(images_, image_features, pairwise_matches);
92 #endif
93 
94  /* use only matches that has enough confidence. leave out matches that are not
95  * connected (small components) */
96  good_indices = cv::detail::leaveBiggestComponent(
97  image_features, pairwise_matches, static_cast<float>(confidence));
98 
99  // no match found. try set first non-empty grid as reference frame. we try to
100  // avoid setting empty grid as reference frame, in case some maps never
101  // arrive. If all is empty just set null transforms.
102  if (good_indices.size() == 1) {
103  transforms_.clear();
104  transforms_.resize(images_.size());
105  for (size_t i = 0; i < images_.size(); ++i) {
106  if (!images_[i].empty()) {
107  // set identity
108  transforms_[i] = cv::Mat::eye(3, 3, CV_64F);
109  break;
110  }
111  }
112  return true;
113  }
114 
115  /* estimate transform */
116  ROS_DEBUG("calculating transforms in global reference frame");
117  // note: currently used estimator never fails
118  if (!(*estimator)(image_features, pairwise_matches, transforms)) {
119  return false;
120  }
121 
122  /* levmarq optimization */
123  // openCV just accepts float transforms
124  for (auto& transform : transforms) {
125  transform.R.convertTo(transform.R, CV_32F);
126  }
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.");
131  return false;
132  }
133 
134  transforms_.clear();
135  transforms_.resize(images_.size());
136  size_t i = 0;
137  for (auto& j : good_indices) {
138  // we want to work with transforms as doubles
139  transforms[i].R.convertTo(transforms_[static_cast<size_t>(j)], CV_64F);
140  ++i;
141  }
142 
143  return true;
144 }
145 
146 // checks whether given matrix is an identity, i.e. exactly appropriate Mat::eye
147 static inline bool isIdentity(const cv::Mat& matrix)
148 {
149  if (matrix.empty()) {
150  return false;
151  }
152  cv::MatExpr diff = matrix != cv::Mat::eye(matrix.size(), matrix.type());
153  return cv::countNonZero(diff) == 0;
154 }
155 
156 nav_msgs::OccupancyGrid::Ptr MergingPipeline::composeGrids()
157 {
158  ROS_ASSERT(images_.size() == transforms_.size());
159  ROS_ASSERT(images_.size() == grids_.size());
160 
161  if (images_.empty()) {
162  return nullptr;
163  }
164 
165  ROS_DEBUG("warping grids");
166  internal::GridWarper warper;
167  std::vector<cv::Mat> imgs_warped;
168  imgs_warped.reserve(images_.size());
169  std::vector<cv::Rect> rois;
170  rois.reserve(images_.size());
171 
172  for (size_t i = 0; i < images_.size(); ++i) {
173  if (!transforms_[i].empty() && !images_[i].empty()) {
174  imgs_warped.emplace_back();
175  rois.emplace_back(
176  warper.warp(images_[i], transforms_[i], imgs_warped.back()));
177  }
178  }
179 
180  if (imgs_warped.empty()) {
181  return nullptr;
182  }
183 
184  ROS_DEBUG("compositing result grid");
185  nav_msgs::OccupancyGrid::Ptr result;
186  internal::GridCompositor compositor;
187  result = compositor.compose(imgs_warped, rois);
188 
189  // set correct resolution to output grid. use resolution of identity (works
190  // for estimated trasforms), or any resolution (works for know_init_positions)
191  // - in that case all resolutions should be the same.
192  float any_resolution = 0.0;
193  for (size_t i = 0; i < transforms_.size(); ++i) {
194  // check if this transform is the reference frame
195  if (isIdentity(transforms_[i])) {
196  result->info.resolution = grids_[i]->info.resolution;
197  break;
198  }
199  if (grids_[i]) {
200  any_resolution = grids_[i]->info.resolution;
201  }
202  }
203  if (result->info.resolution <= 0.f) {
204  result->info.resolution = any_resolution;
205  }
206 
207  // set grid origin to its centre
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;
213 
214  return result;
215 }
216 
217 std::vector<geometry_msgs::Transform> MergingPipeline::getTransforms() const
218 {
219  std::vector<geometry_msgs::Transform> result;
220  result.reserve(transforms_.size());
221 
222  for (auto& transform : transforms_) {
223  if (transform.empty()) {
224  result.emplace_back();
225  continue;
226  }
227 
228  ROS_ASSERT(transform.type() == CV_64F);
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.;
233 
234  // our rotation is in fact only 2D, thus quaternion can be simplified
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);
241 
242  result.push_back(ros_transform);
243  }
244 
245  return result;
246 }
247 
248 } // namespace combine_grids
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)
Definition: grid_warper.cpp:47
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)
#define ROS_WARN(...)
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_
#define ROS_ASSERT(cond)
#define ROS_DEBUG(...)


map_merge
Author(s): Jiri Horner
autogenerated on Mon Feb 28 2022 22:46:02