chain3d_to_chain3d_error.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018 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 // Author: Michael Ferguson
20 
21 #ifndef ROBOT_CALIBRATION_CERES_CHAIN3D_TO_CHAIN3D_ERROR_H
22 #define ROBOT_CALIBRATION_CERES_CHAIN3D_TO_CHAIN3D_ERROR_H
23 
24 #include <string>
25 #include <ceres/ceres.h>
30 #include <robot_calibration_msgs/CalibrationData.h>
31 
32 namespace robot_calibration
33 {
34 
41 {
50  ChainModel* b_model,
51  CalibrationOffsetParser* offsets,
52  robot_calibration_msgs::CalibrationData& data)
53  {
54  a_model_ = a_model;
55  b_model_ = b_model;
56  offsets_ = offsets;
57  data_ = data;
58  }
59 
60  virtual ~Chain3dToChain3d() {}
61 
67  bool operator()(double const * const * free_params,
68  double* residuals) const
69  {
70  // Update calibration offsets based on free params
71  offsets_->update(free_params[0]);
72 
73  // Project the observations into common base frame
74  std::vector<geometry_msgs::PointStamped> a_pts =
76  std::vector<geometry_msgs::PointStamped> b_pts =
78 
79  if (a_pts.size() != b_pts.size())
80  {
81  std::cerr << "Observations do not match in size." << std::endl;
82  return false;
83  }
84 
85  // Compute residuals
86  for (size_t i = 0; i < a_pts.size(); ++i)
87  {
88  if (a_pts[i].header.frame_id != b_pts[i].header.frame_id)
89  std::cerr << "Projected observation frame_ids do not match." << std::endl;
90  residuals[(3*i)+0] = a_pts[i].point.x - b_pts[i].point.x;
91  residuals[(3*i)+1] = a_pts[i].point.y - b_pts[i].point.y;
92  residuals[(3*i)+2] = a_pts[i].point.z - b_pts[i].point.z;
93  }
94 
95  return true; // always return true
96  }
97 
102  static ceres::CostFunction* Create(ChainModel* a_model,
103  ChainModel* b_model,
104  CalibrationOffsetParser* offsets,
105  robot_calibration_msgs::CalibrationData& data)
106  {
107  int index = getSensorIndex(data, a_model->name());
108  if (index == -1)
109  {
110  // In theory, we should never get here, because the optimizer does a check
111  std::cerr << "Sensor name doesn't match any of the existing finders" << std::endl;
112  return 0;
113  }
114 
115  ceres::DynamicNumericDiffCostFunction<Chain3dToChain3d> * func;
116  func = new ceres::DynamicNumericDiffCostFunction<Chain3dToChain3d>(
117  new Chain3dToChain3d(a_model, b_model, offsets, data));
118  func->AddParameterBlock(offsets->size());
119  func->SetNumResiduals(data.observations[index].features.size() * 3);
120 
121  return static_cast<ceres::CostFunction*>(func);
122  }
123 
127  robot_calibration_msgs::CalibrationData data_;
128 };
129 
130 } // namespace robot_calibration
131 
132 #endif // ROBOT_CALIBRATION_CERES_CHAIN3D_TO_CHAIN3D_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
static ceres::CostFunction * Create(ChainModel *a_model, ChainModel *b_model, CalibrationOffsetParser *offsets, robot_calibration_msgs::CalibrationData &data)
Helper factory function to create a new error block. Parameters are described in the class constructo...
int getSensorIndex(const robot_calibration_msgs::CalibrationData &msg, const std::string &sensor)
Determine which observation index corresponds to a particular sensor name.
robot_calibration_msgs::CalibrationData data_
Combined parser and configuration for calibration offsets. Holds the configuration of what is to be c...
bool operator()(double const *const *free_params, double *residuals) const
Operator called by CERES optimizer.
Chain3dToChain3d(ChainModel *a_model, ChainModel *b_model, CalibrationOffsetParser *offsets, robot_calibration_msgs::CalibrationData &data)
This function is not used direcly, instead use the Create() function.
Error block for computing the residual error between two 3d data sources. This can be used to calibra...
Calibration code lives under this namespace.
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