pose_estimation_markermap_base.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  : params_(), markerMapConfig_(markerMapConfig) {
39 
40  estimators_.clear();
41  for (auto &markerMap:markerMapConfig_.markerMaps) {
42  estimators_.push_back(MarkerMapEstimator(markerMap));
43  }
44 }
45 
47 
48 static cv::Mat getRTMatrix(const cv::Mat &_rvec, const cv::Mat &_tvec) {
49  if (_rvec.empty())
50  return cv::Mat();
51  cv::Mat m = cv::Mat::eye(4, 4, CV_32FC1);
52  cv::Mat R33 = cv::Mat(m, cv::Rect(0, 0, 3, 3));
53  cv::Rodrigues(_rvec, R33);
54  for (int i = 0; i < 3; i++)
55  m.at<float>(i, 3) = _tvec.ptr<float>(0)[i];
56  return m;
57 }
58 
59 void PoseEstimationMarkerMapBase::estimatePose(std::vector<MarkerFiducials> &markerFiducials,
60  cv::Mat &camera_k, cv::Mat &camera_d,
61  std::vector<MarkerPose> &markerPoses) {
62  for (auto &estimator:estimators_) {
63  estimator.estimatePose(markerFiducials, camera_k, camera_d, markerPoses);
64  }
65 }
66 
68  return params_;
69 }
70 
72 
73 }
std::vector< MarkerMapDetails > markerMaps
std::vector< MarkerMapEstimator > estimators_
void estimatePose(std::vector< MarkerFiducials > &markers, cv::Mat &camera_k, cv::Mat &camera_d, std::vector< MarkerPose > &markerPoses)
static cv::Mat getRTMatrix(const cv::Mat &_rvec, const cv::Mat &_tvec)
PoseEstimationMarkerMapParameters & getParameters()
PoseEstimationMarkerMapParameters params_
PoseEstimationMarkerMapBase(MarkerMapConfig markerMapConfig)


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