marker_map_estimator.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2016, Lukas Pfeifhofer <lukas.pfeifhofer@devlabs.pro>
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright notice,
9  * this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above copyright notice,
12  * this list of conditions and the following disclaimer in the documentation
13  * and/or other materials provided with the distribution.
14  *
15  * 3. Neither the name of the copyright holder nor the names of its contributors
16  * may be used to endorse or promote products derived from this software without
17  * specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
33 
34 #include "ros/ros.h"
35 
37 
38 }
39 
40 static cv::Mat getRTMatrix(const cv::Mat &_rvec, const cv::Mat &_tvec) {
41  if (_rvec.empty())
42  return cv::Mat();
43  cv::Mat m = cv::Mat::eye(4, 4, CV_32FC1);
44  cv::Mat R33 = cv::Mat(m, cv::Rect(0, 0, 3, 3));
45  cv::Rodrigues(_rvec, R33);
46  for (int i = 0; i < 3; i++)
47  m.at<float>(i, 3) = _tvec.ptr<float>(0)[i];
48  return m;
49 }
50 
51 void
52 MarkerMapEstimator::estimatePose(std::vector<MarkerFiducials> &markerFiducials, cv::Mat &camera_k, cv::Mat &camera_d,
53  std::vector<MarkerPose> &markerPosesOutput) {
54  std::vector<cv::Point3f> object_points;
55  std::vector<cv::Point2f> image_points;
56 
57  std::vector<MarkerFiducials>::iterator it = markerFiducials.begin();
58  while (it != markerFiducials.end()) {
59  MarkerFiducials &fiducial = *it;
60 
61  // Only try to match if marker id is known
62  if (fiducial.ids.size() > 0) {
63  int id = fiducial.ids[0];
64 
65  for (auto &markerDetails:details_.markers) {
66 
67  // Only match ids for now, no type check is done
68  if (id == markerDetails.id) {
69 
70  // Just add these object/image points
71  for (cv::Point3f &object_point:fiducial.object_points) {
72  object_point = object_point + cv::Point3f(markerDetails.position);
73  // FIXME: No rotation is done yet
74  // ROS_INFO("x=%f, y=%f, z=%f", object_point.x, object_point.y, object_point.z);
75  object_points.push_back(object_point);
76  }
77 
78  for (auto &image_point:fiducial.image_points)
79  image_points.push_back(image_point);
80  }
81 
82  }
83 
84  // Remove fiducial element from list to avoid multiple use in another estimator
85  // Next element follows
86  it = markerFiducials.erase(it);
87  } else {
88  std::next(it);
89  }
90  }
91 
92  // Estimate MarkerMap pose
93  if (image_points.size() > 2 && object_points.size() > 2) {
94  MarkerPose pose({details_.id}, {1});
95  {
96  cv::Mat rv, tv;
97  cv::solvePnP(object_points, image_points, camera_k, camera_d, rv, tv);
98 
99  cv::Mat rvec, tvec;
100  rv.convertTo(rvec, CV_32F);
101  tv.convertTo(tvec, CV_32F);
102 
103  pose.rt_matrix = getRTMatrix(rvec, tvec);
104  }
105  if (!pose.rt_matrix.empty())
106  markerPosesOutput.push_back(pose);
107  }
108 
109 }
std::vector< MarkerDetails > markers
MarkerMapEstimator(MarkerMapDetails details)
static cv::Mat getRTMatrix(const cv::Mat &_rvec, const cv::Mat &_tvec)
void estimatePose(std::vector< MarkerFiducials > &markers, cv::Mat &camera_k, cv::Mat &camera_d, std::vector< MarkerPose > &markerPoses)
std::vector< cv::Point3f > object_points
MarkerMapDetails details_
std::vector< cv::Point2f > image_points
std::vector< int > ids


tuw_marker_pose_estimation
Author(s): Lukas Pfeifhofer
autogenerated on Mon Jun 10 2019 15:42:13