chain3d_to_mesh_error.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018-2022 Michael Ferguson
3  * Copyright (C) 2015 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 #ifndef ROBOT_CALIBRATION_CERES_CHAIN3D_TO_MESH_ERROR_H
20 #define ROBOT_CALIBRATION_CERES_CHAIN3D_TO_MESH_ERROR_H
21 
22 #include <limits>
23 #include <string>
24 #include <math.h>
25 #include <ceres/ceres.h>
31 #include <robot_calibration_msgs/CalibrationData.h>
32 
33 namespace robot_calibration
34 {
35 
44 double distToLine(Eigen::Vector3d& a, Eigen::Vector3d& b, Eigen::Vector3d c)
45 {
46  Eigen::Vector3d ab = b - a;
47  Eigen::Vector3d ac = c - a;
48  Eigen::Vector3d bc = c - b;
49 
50  double e = ac.dot(ab);
51  if (e <= 0.0)
52  {
53  // Point A is closest to C
54  return ac.dot(ac);
55  }
56  double f = ab.dot(ab);
57  if (e >= f)
58  {
59  // Point B is closest to C
60  return bc.dot(bc);
61  }
62  // C actually projects between
63  return ac.dot(ac) - e * e / f;
64 }
65 
72 {
80  Chain3dToMesh(ChainModel* chain_model,
81  CalibrationOffsetParser* offsets,
82  robot_calibration_msgs::CalibrationData& data,
83  MeshPtr& mesh)
84  {
85  chain_model_ = chain_model;
86  offsets_ = offsets;
87  data_ = data;
88  mesh_ = mesh;
89  }
90 
91  virtual ~Chain3dToMesh() {}
92 
93  bool operator()(double const * const * free_params,
94  double* residuals) const
95  {
96  // Update calibration offsets based on free params
97  offsets_->update(free_params[0]);
98 
99  // Project the camera observations
100  std::vector<geometry_msgs::PointStamped> chain_pts =
102 
103  // Compute residuals
104  for (size_t pt = 0; pt < chain_pts.size() ; ++pt)
105  {
106  Eigen::Vector3d p(chain_pts[pt].point.x, chain_pts[pt].point.y, chain_pts[pt].point.z);
107 
108  // Find shortest distance to any line segment forming a triangle
109  double dist = std::numeric_limits<double>::max();
110  for (size_t t = 0; t < mesh_->triangle_count; ++t)
111  {
112  // Get the index of each vertex of the triangle
113  int A_idx = mesh_->triangles[(3 * t) + 0];
114  int B_idx = mesh_->triangles[(3 * t) + 1];
115  int C_idx = mesh_->triangles[(3 * t) + 2];
116  // Get the vertices
117  Eigen::Vector3d A(mesh_->vertices[(3 * A_idx) + 0], mesh_->vertices[(3 * A_idx) + 1], mesh_->vertices[(3 * A_idx) + 2]);
118  Eigen::Vector3d B(mesh_->vertices[(3 * B_idx) + 0], mesh_->vertices[(3 * B_idx) + 1], mesh_->vertices[(3 * B_idx) + 2]);
119  Eigen::Vector3d C(mesh_->vertices[(3 * C_idx) + 0], mesh_->vertices[(3 * C_idx) + 1], mesh_->vertices[(3 * C_idx) + 2]);
120  // Compare each line segment
121  double d = distToLine(A, B, p);
122  d = std::min(d, distToLine(B, C, p));
123  d = std::min(d, distToLine(C, A, p));
124  dist = std::min(d, dist);
125  }
126  residuals[pt] = std::sqrt(dist);
127  }
128  return true;
129  }
130 
135  static ceres::CostFunction* Create(ChainModel* a_model,
136  CalibrationOffsetParser* offsets,
137  robot_calibration_msgs::CalibrationData& data,
138  MeshPtr mesh)
139  {
140  int index = getSensorIndex(data, a_model->getName());
141  if (index == -1)
142  {
143  // In theory, we should never get here, because the optimizer does a check
144  std::cerr << "Sensor name doesn't match any of the existing finders" << std::endl;
145  return 0;
146  }
147 
148  ceres::DynamicNumericDiffCostFunction<Chain3dToMesh> * func;
149  func = new ceres::DynamicNumericDiffCostFunction<Chain3dToMesh>(
150  new Chain3dToMesh(a_model, offsets, data, mesh));
151  func->AddParameterBlock(offsets->size());
152  func->SetNumResiduals(data.observations[index].features.size());
153 
154  return static_cast<ceres::CostFunction*>(func);
155  }
156 
159  robot_calibration_msgs::CalibrationData data_;
161 };
162 
163 } // namespace robot_calibration
164 
165 #endif // ROBOT_CALIBRATION_CERES_CHAIN3D_TO_MESH_ERROR_H
robot_calibration::CalibrationOffsetParser::size
size_t size()
Definition: calibration_offset_parser.cpp:178
robot_calibration::Chain3dToMesh::mesh_
MeshPtr mesh_
Definition: chain3d_to_mesh_error.h:160
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::Chain3dToMesh::chain_model_
ChainModel * chain_model_
Definition: chain3d_to_mesh_error.h:157
robot_calibration::Chain3dToMesh::data_
robot_calibration_msgs::CalibrationData data_
Definition: chain3d_to_mesh_error.h:159
offset_parser.h
robot_calibration::Chain3dToMesh::operator()
bool operator()(double const *const *free_params, double *residuals) const
Definition: chain3d_to_mesh_error.h:93
f
f
robot_calibration::B
const unsigned B
Definition: led_finder.cpp:37
A
robot_calibration::MeshPtr
std::shared_ptr< shapes::Mesh > MeshPtr
Definition: mesh_loader.h:32
robot_calibration::Chain3dToMesh::Chain3dToMesh
Chain3dToMesh(ChainModel *chain_model, CalibrationOffsetParser *offsets, robot_calibration_msgs::CalibrationData &data, MeshPtr &mesh)
This function is not used direcly, instead use the Create() function.
Definition: chain3d_to_mesh_error.h:80
robot_calibration::Chain3dToMesh::~Chain3dToMesh
virtual ~Chain3dToMesh()
Definition: chain3d_to_mesh_error.h:91
mesh_loader.h
robot_calibration::Chain3dToMesh::offsets_
CalibrationOffsetParser * offsets_
Definition: chain3d_to_mesh_error.h:158
d
d
robot_calibration::distToLine
double distToLine(Eigen::Vector3d &a, Eigen::Vector3d &b, Eigen::Vector3d c)
Get the squared distance line segment A-B for point C.
Definition: chain3d_to_mesh_error.h:44
chain.h
robot_calibration::Chain3dToMesh::Create
static ceres::CostFunction * Create(ChainModel *a_model, CalibrationOffsetParser *offsets, robot_calibration_msgs::CalibrationData &data, MeshPtr mesh)
Helper factory function to create a new error block. Parameters are described in the class constructo...
Definition: chain3d_to_mesh_error.h:135
point
std::chrono::system_clock::time_point point
robot_calibration
Calibration code lives under this namespace.
Definition: base_calibration.h:28
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
index
unsigned int index
robot_calibration::ChainModel::getName
virtual std::string getName() const
Get the name of this model (as provided in the YAML config)
Definition: models.cpp:152
calibration_data_helpers.h
robot_calibration::getSensorIndex
int getSensorIndex(const robot_calibration_msgs::CalibrationData &msg, const std::string &sensor)
Determine which observation index corresponds to a particular sensor name.
Definition: calibration_data_helpers.h:30
camera3d.h
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
t
geometry_msgs::TransformStamped t
robot_calibration::Chain3dToMesh
Error block for computing the fit between a set of projected points and a mesh (usually part of the r...
Definition: chain3d_to_mesh_error.h:71
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
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01