plane_to_plane_error.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018-2022 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>
29 #include <robot_calibration_msgs/CalibrationData.h>
30 
31 namespace robot_calibration
32 {
33 
42 {
53  ChainModel *model_b,
54  CalibrationOffsetParser *offsets,
55  robot_calibration_msgs::CalibrationData &data,
56  double scale_normal, double scale_offset)
57  {
58  model_a_ = model_a;
59  model_b_ = model_b;
60  offsets_ = offsets;
61  data_ = data;
62  scale_normal_ = scale_normal;
63  scale_offset_ = scale_offset;
64  }
65 
66  virtual ~PlaneToPlaneError() = default;
67 
73  bool operator()(double const *const *free_params,
74  double *residuals) const
75  {
76  // Update calibration offsets based on free params
77  offsets_->update(free_params[0]);
78 
79  // Project the first camera observations
80  std::vector<geometry_msgs::PointStamped> a_pts =
82 
83  // Get plane parameters for first set of points
84  Eigen::MatrixXd matrix_a = getMatrix(a_pts);
85  Eigen::Vector3d normal_a;
86  double d_a = 0.0;
87  getPlane(matrix_a, normal_a, d_a);
88 
89  // Project the second camera estimation
90  std::vector<geometry_msgs::PointStamped> b_pts =
92 
93  // Get plane parameters for second set of points
94  Eigen::MatrixXd matrix_b = getMatrix(b_pts);
95  Eigen::Vector3d normal_b;
96  double d_b = 0.0;
97  getPlane(matrix_b, normal_b, d_b);
98 
99  // Compute the residuals by minimizing the normals of the calculated planes
100  residuals[0] = std::fabs(normal_a(0) - normal_b(0)) * scale_normal_;
101  residuals[1] = std::fabs(normal_a(1) - normal_b(1)) * scale_normal_;
102  residuals[2] = std::fabs(normal_a(2) - normal_b(2)) * scale_normal_;
103 
104  // Final residual is the distance between the centroid of one plane and the second plane itself
105  Eigen::Vector3d centroid_a = getCentroid(matrix_a);
106  residuals[3] = std::fabs((normal_b(0) * centroid_a(0)) +
107  (normal_b(1) * centroid_a(1)) +
108  (normal_b(2) * centroid_a(2)) + d_b) * scale_offset_;
109 
110  return true; // always return true
111  }
112 
117  static ceres::CostFunction *Create(ChainModel *model_a,
118  ChainModel *model_b,
119  CalibrationOffsetParser *offsets,
120  robot_calibration_msgs::CalibrationData &data,
121  double scale_normal, double scale_offset)
122  {
123  ceres::DynamicNumericDiffCostFunction <PlaneToPlaneError> *func;
124  func = new ceres::DynamicNumericDiffCostFunction<PlaneToPlaneError>(
125  new PlaneToPlaneError(model_a, model_b, offsets, data, scale_normal, scale_offset));
126  func->AddParameterBlock(offsets->size());
127  func->SetNumResiduals(4);
128 
129  return static_cast<ceres::CostFunction*>(func);
130  }
131 
135  robot_calibration_msgs::CalibrationData data_;
137 };
138 
139 } // namespace robot_calibration
140 
141 #endif // ROBOT_CALIBRATION_CERES_PLANE_TO_PLANE_ERROR_H
robot_calibration::PlaneToPlaneError::Create
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...
Definition: plane_to_plane_error.h:117
robot_calibration::PlaneToPlaneError::~PlaneToPlaneError
virtual ~PlaneToPlaneError()=default
robot_calibration::CalibrationOffsetParser::size
size_t size()
Definition: calibration_offset_parser.cpp:178
robot_calibration::CalibrationOffsetParser
Combined parser and configuration for calibration offsets. Holds the configuration of what is to be c...
Definition: offset_parser.h:33
robot_calibration::PlaneToPlaneError::model_a_
ChainModel * model_a_
Definition: plane_to_plane_error.h:132
robot_calibration::PlaneToPlaneError::scale_normal_
double scale_normal_
Definition: plane_to_plane_error.h:136
offset_parser.h
robot_calibration::PlaneToPlaneError::operator()
bool operator()(double const *const *free_params, double *residuals) const
Operator called by CERES optimizer.
Definition: plane_to_plane_error.h:73
robot_calibration::getMatrix
Eigen::MatrixXd getMatrix(const std::vector< geometry_msgs::PointStamped > &points)
Get an Eigen::MatrixXd from a vector of PointStamped.
Definition: eigen_geometry.h:35
eigen_geometry.h
chain.h
robot_calibration::getCentroid
Eigen::Vector3d getCentroid(Eigen::MatrixXd points)
Get the centroid of a point cloud.
Definition: eigen_geometry.h:50
robot_calibration::getPlane
bool getPlane(Eigen::MatrixXd points, Eigen::Vector3d &normal, double &d)
Find the plane parameters for a point cloud.
Definition: eigen_geometry.h:64
robot_calibration
Calibration code lives under this namespace.
Definition: base_calibration.h:28
robot_calibration::PlaneToPlaneError::model_b_
ChainModel * model_b_
Definition: plane_to_plane_error.h:133
robot_calibration::PlaneToPlaneError
Error block for computing the fit between two sets of projected points and their planar models plane ...
Definition: plane_to_plane_error.h:41
robot_calibration::CalibrationOffsetParser::update
bool update(const double *const free_params)
Update the offsets based on free_params from ceres-solver.
Definition: calibration_offset_parser.cpp:132
robot_calibration::PlaneToPlaneError::scale_offset_
double scale_offset_
Definition: plane_to_plane_error.h:136
robot_calibration::PlaneToPlaneError::PlaneToPlaneError
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.
Definition: plane_to_plane_error.h:52
robot_calibration::ChainModel::project
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:53
robot_calibration::PlaneToPlaneError::data_
robot_calibration_msgs::CalibrationData data_
Definition: plane_to_plane_error.h:135
robot_calibration::ChainModel
Model of a kinematic chain. This is the basic instance where we transform the world observations into...
Definition: chain.h:107
robot_calibration::PlaneToPlaneError::offsets_
CalibrationOffsetParser * offsets_
Definition: plane_to_plane_error.h:134


robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01