plane_to_plane_error.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018 Michael Ferguson
3  * Copyright (C) 2015-2017 Fetch Robotics Inc.
4  * Copyright (C) 2013-2014 Unbounded Robotics Inc.
5  *
6  * Licensed under the Apache License, Version 2.0 (the "License");
7  * you may not use this file except in compliance with the License.
8  * You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS,
14  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15  * See the License for the specific language governing permissions and
16  * limitations under the License.
17  */
18 
19 // Author: Niharika Arora
20 
21 #ifndef ROBOT_CALIBRATION_CERES_PLANE_TO_PLANE_ERROR_H
22 #define ROBOT_CALIBRATION_CERES_PLANE_TO_PLANE_ERROR_H
23 
24 #include <string>
25 #include <ceres/ceres.h>
30 #include <robot_calibration_msgs/CalibrationData.h>
31 
32 #include <opencv2/calib3d/calib3d.hpp>
33 #include <cv_bridge/cv_bridge.h>
34 
35 namespace robot_calibration
36 {
37 
46 {
57  ChainModel *model_b,
58  CalibrationOffsetParser *offsets,
59  robot_calibration_msgs::CalibrationData &data,
60  double scale_normal, double scale_offset)
61  {
62  model_a_ = model_a;
63  model_b_ = model_b;
64  offsets_ = offsets;
65  data_ = data;
66  scale_normal_ = scale_normal;
67  scale_offset_ = scale_offset;
68  }
69 
71  {}
72 
78  bool operator()(double const *const *free_params,
79  double *residuals) const
80  {
81  // Update calibration offsets based on free params
82  offsets_->update(free_params[0]);
83 
84  // Project the first camera observations
85  std::vector <geometry_msgs::PointStamped> a_pts =
87 
88  // Project the second camera estimation
89  std::vector <geometry_msgs::PointStamped> b_pts =
91 
92  // Calculate plane normals using SVD
93  std::vector <cv::Point3f> a_points;
94  std::vector <cv::Point3f> b_points;
95 
96  for (size_t i = 0; i < a_pts.size(); ++i)
97  {
98  a_points.push_back(cv::Point3f(a_pts[i].point.x, a_pts[i].point.y, a_pts[i].point.z));
99  }
100  for (size_t i = 0; i < b_pts.size(); ++i)
101  {
102  b_points.push_back(cv::Point3f(b_pts[i].point.x, b_pts[i].point.y, b_pts[i].point.z));
103  }
104 
105  // Find the planes
106  cv::Mat plane_1 = getPlane(a_points);
107  cv::Mat plane_2 = getPlane(b_points);
108 
109  // Compute the residuals by minimizing the normals of the calculated planes
110  residuals[0] = (std::fabs(plane_1.at<float>(0, 0)) - std::fabs(plane_2.at<float>(0, 0))) * scale_normal_;
111  residuals[1] = (std::fabs(plane_1.at<float>(0, 1)) - std::fabs(plane_2.at<float>(0, 1))) * scale_normal_;
112  residuals[2] = (std::fabs(plane_1.at<float>(0, 2)) - std::fabs(plane_2.at<float>(0, 2))) * scale_normal_;
113  //residuals[3] = TODO
114 
115  return true; // always return true
116  }
117 
122  static ceres::CostFunction *Create(ChainModel *model_a,
123  ChainModel *model_b,
124  CalibrationOffsetParser *offsets,
125  robot_calibration_msgs::CalibrationData &data,
126  double scale_normal, double scale_offset)
127  {
128  int index = getSensorIndex(data, model_a->name());
129  if (index == -1)
130  {
131  // In theory, we should never get here, because the optimizer does a check
132  std::cerr << "Sensor name doesn't match any of the existing finders" << std::endl;
133  return 0;
134  }
135 
136  ceres::DynamicNumericDiffCostFunction <PlaneToPlaneError> *func;
137  func = new ceres::DynamicNumericDiffCostFunction<PlaneToPlaneError>(
138  new PlaneToPlaneError(model_a, model_b, offsets, data, scale_normal, scale_offset));
139  func->AddParameterBlock(offsets->size());
140  func->SetNumResiduals(4);
141 
142  return static_cast<ceres::CostFunction *>(func);
143  }
144 
150  cv::Mat getPlane(std::vector <cv::Point3f> points) const
151  {
152  // Calculate centroid
153  cv::Point3f centroid(0, 0, 0);
154  for (size_t i = 0; i < points.size(); i++)
155  {
156  centroid += points.at(i);
157  }
158 
159  centroid.x = centroid.x / points.size();
160  centroid.y = centroid.y / points.size();
161  centroid.z = centroid.z / points.size();
162 
163  // subtract centroid from all points
164  cv::Mat pts_mat(points.size(), 3, CV_32F);
165  for (size_t i = 0; i < points.size(); i++)
166  {
167  pts_mat.at<float>(i, 0) = points[i].x - centroid.x;
168  pts_mat.at<float>(i, 1) = points[i].y - centroid.y;
169  pts_mat.at<float>(i, 2) = points[i].z - centroid.z;
170  }
171 
172  // SVD
173  cv::SVD svd(pts_mat, cv::SVD::FULL_UV);
174  cv::Mat normal = svd.vt.row(2);
175 
176  return normal;
177  }
178 
182  robot_calibration_msgs::CalibrationData data_;
184 };
185 
186 } // namespace robot_calibration
187 
188 #endif // ROBOT_CALIBRATION_CERES_PLANE_TO_PLANE_ERROR_H
virtual std::vector< geometry_msgs::PointStamped > project(const robot_calibration_msgs::CalibrationData &data, const CalibrationOffsetParser &offsets)
Compute the position of the estimated points.
Definition: models.cpp:48
PlaneToPlaneError(ChainModel *model_a, ChainModel *model_b, CalibrationOffsetParser *offsets, robot_calibration_msgs::CalibrationData &data, double scale_normal, double scale_offset)
Error block for calibrating two planar data sets.
int getSensorIndex(const robot_calibration_msgs::CalibrationData &msg, const std::string &sensor)
Determine which observation index corresponds to a particular sensor name.
Combined parser and configuration for calibration offsets. Holds the configuration of what is to be c...
Error block for computing the fit between two sets of projected points and their planar models plane ...
robot_calibration_msgs::CalibrationData data_
bool operator()(double const *const *free_params, double *residuals) const
Operator called by CERES optimizer.
TFSIMD_FORCE_INLINE const tfScalar & x() const
Calibration code lives under this namespace.
TFSIMD_FORCE_INLINE const tfScalar & z() const
cv::Mat getPlane(std::vector< cv::Point3f > points) const
Does a plane fit to the points and calculates the normals.
static ceres::CostFunction * Create(ChainModel *model_a, ChainModel *model_b, CalibrationOffsetParser *offsets, robot_calibration_msgs::CalibrationData &data, double scale_normal, double scale_offset)
Helper factory function to create a new error block. Parameters are described in the class constructo...
std::string name() const
Definition: chain.h:153
Model of a kinematic chain. This is the basic instance where we transform the world observations into...
Definition: chain.h:107
bool update(const double *const free_params)
Update the offsets based on free_params from ceres-solver.


robot_calibration
Author(s): Michael Ferguson
autogenerated on Tue Nov 3 2020 17:30:30