transform_estimator.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015-2016, Jiri Horner.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the author nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  *********************************************************************/
00036 
00037 #include <combine_grids/transform_estimator.h>
00038 
00039 #include <opencv2/core/utility.hpp>
00040 
00041 #include <ros/console.h>
00042 #include <ros/assert.h>
00043 
00044 namespace combine_grids
00045 {
00046 namespace internal
00047 {
00053 class CalcAffineTransform
00054 {
00055 public:
00056   CalcAffineTransform(
00057       int _num_images,
00058       const std::vector<cv::detail::MatchesInfo> &_pairwise_matches,
00059       std::vector<cv::detail::CameraParams> &_cameras)
00060     : num_images(_num_images)
00061     , pairwise_matches(&_pairwise_matches[0])
00062     , cameras(&_cameras[0])
00063   {
00064   }
00065 
00066   void operator()(const cv::detail::GraphEdge &edge)
00067   {
00068     int pair_idx = edge.from * num_images + edge.to;
00069 
00070     ROS_DEBUG("computing transform, from %d, to %d, pair_idx %d", edge.from,
00071               edge.to, pair_idx);
00072 
00073     ROS_DEBUG_STREAM("cameras[edge.from]:\n" << cameras[edge.from].R);
00074     ROS_DEBUG_STREAM("H:\n" << pairwise_matches[pair_idx].H);
00075 
00076     cameras[edge.to].R = cameras[edge.from].R * pairwise_matches[pair_idx].H;
00077   }
00078 
00079 private:
00080   int num_images;
00081   const cv::detail::MatchesInfo *pairwise_matches;
00082   cv::detail::CameraParams *cameras;
00083 };
00084 
00085 bool AffineBasedEstimator::estimate(
00086     const std::vector<cv::detail::ImageFeatures> &features,
00087     const std::vector<cv::detail::MatchesInfo> &pairwise_matches,
00088     std::vector<cv::detail::CameraParams> &cameras)
00089 {
00090   ROS_DEBUG("AffineBasedEstimator: have %lu pairwise matches.",
00091             pairwise_matches.size());
00092 
00093   cameras.resize(features.size());
00094   const int num_images = static_cast<int>(features.size());
00095 
00096   // find if we have any affine estimates
00097   bool have_any_transform = false;
00098   for(auto& match : pairwise_matches) {
00099     have_any_transform |= !match.H.empty();
00100   }
00101   // we don't need to do anything
00102   if(!have_any_transform) {
00103     return true;
00104   }
00105 
00106   // find maximum spaning tree on pairwise matches
00107   cv::detail::Graph span_tree;
00108   std::vector<int> span_tree_centers;
00109   // function from motion estimators, uses number of inliers as weights
00110   findMaxSpanningTree(num_images, pairwise_matches, span_tree,
00111                       span_tree_centers);
00112 
00113   ROS_DEBUG("constructed spanning tree with %d vertices",
00114             span_tree.numVertices());
00115 
00116   // compute final transform by chaining H together
00117   span_tree.walkBreadthFirst(
00118       span_tree_centers[0],
00119       CalcAffineTransform(num_images, pairwise_matches, cameras));
00120   return true;
00121 }
00122 }  // namespace internal
00123 }  // namespace combine_grids


map_merge
Author(s): Jiri Horner
autogenerated on Sun Mar 26 2017 03:48:10