chain3d_to_plane_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 #ifndef ROBOT_CALIBRATION_CERES_CHAIN3D_TO_PLANE_ERROR_H
20 #define ROBOT_CALIBRATION_CERES_CHAIN3D_TO_PLANE_ERROR_H
21 
22 #include <string>
23 #include <math.h>
24 #include <ceres/ceres.h>
29 #include <robot_calibration_msgs/CalibrationData.h>
30 
31 namespace robot_calibration
32 {
33 
41 {
53  Chain3dToPlane(ChainModel* chain_model,
54  CalibrationOffsetParser* offsets,
55  robot_calibration_msgs::CalibrationData& data,
56  double a, double b, double c, double d,
57  double scale)
58  {
59  chain_model_ = chain_model;
60  offsets_ = offsets;
61  data_ = data;
62 
63  a_ = a;
64  b_ = b;
65  c_ = c;
66  d_ = d;
67 
68  // Precompute denominator of distance to plane
69  double denom = sqrt((a_ * a_) + (b_* b_) + (c_ * c_));
70  if (abs(denom) < 0.1)
71  {
72  std::cerr << "Plane normal is extremely small: " << denom << std::endl;
73  }
74  scale_ = scale / denom;
75  }
76 
77  virtual ~Chain3dToPlane() {}
78 
79  bool operator()(double const * const * free_params,
80  double* residuals) const
81  {
82  // Update calibration offsets based on free params
83  offsets_->update(free_params[0]);
84 
85  // Project the camera observations
86  std::vector<geometry_msgs::PointStamped> chain_pts =
88 
89  // Compute residuals
90  for (size_t i = 0; i < chain_pts.size() ; ++i)
91  {
92  residuals[i] = abs((a_ * chain_pts[i].point.x) +
93  (b_ * chain_pts[i].point.y) +
94  (c_ * chain_pts[i].point.z) + d_) * scale_;
95  }
96  return true;
97  }
98 
103  static ceres::CostFunction* Create(ChainModel* a_model,
104  CalibrationOffsetParser* offsets,
105  robot_calibration_msgs::CalibrationData& data,
106  double a, double b, double c, double d,
107  double scale)
108  {
109  int index = getSensorIndex(data, a_model->getName());
110  if (index == -1)
111  {
112  // In theory, we should never get here, because the optimizer does a check
113  std::cerr << "Sensor name doesn't match any of the existing finders" << std::endl;
114  return 0;
115  }
116 
117  ceres::DynamicNumericDiffCostFunction<Chain3dToPlane> * func;
118  func = new ceres::DynamicNumericDiffCostFunction<Chain3dToPlane>(
119  new Chain3dToPlane(a_model, offsets, data, a, b, c, d, scale));
120  func->AddParameterBlock(offsets->size());
121  func->SetNumResiduals(data.observations[index].features.size());
122 
123  return static_cast<ceres::CostFunction*>(func);
124  }
125 
128  robot_calibration_msgs::CalibrationData data_;
129  double a_, b_, c_, d_;
130  double scale_, denom_;
131 };
132 
133 } // namespace robot_calibration
134 
135 #endif // ROBOT_CALIBRATION_CERES_CHAIN3D_TO_PLANE_ERROR_H
robot_calibration::Chain3dToPlane::operator()
bool operator()(double const *const *free_params, double *residuals) const
Definition: chain3d_to_plane_error.h:79
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::Chain3dToPlane::c_
double c_
Definition: chain3d_to_plane_error.h:129
offset_parser.h
robot_calibration::Chain3dToPlane::offsets_
CalibrationOffsetParser * offsets_
Definition: chain3d_to_plane_error.h:127
robot_calibration::Chain3dToPlane::~Chain3dToPlane
virtual ~Chain3dToPlane()
Definition: chain3d_to_plane_error.h:77
d
d
robot_calibration::Chain3dToPlane::chain_model_
ChainModel * chain_model_
Definition: chain3d_to_plane_error.h:126
chain.h
robot_calibration::Chain3dToPlane::denom_
double denom_
Definition: chain3d_to_plane_error.h:130
point
std::chrono::system_clock::time_point point
robot_calibration::Chain3dToPlane::b_
double b_
Definition: chain3d_to_plane_error.h:129
robot_calibration::Chain3dToPlane::Create
static ceres::CostFunction * Create(ChainModel *a_model, CalibrationOffsetParser *offsets, robot_calibration_msgs::CalibrationData &data, double a, double b, double c, double d, double scale)
Helper factory function to create a new error block. Parameters are described in the class constructo...
Definition: chain3d_to_plane_error.h:103
robot_calibration::Chain3dToPlane
Error block for computing the fit between a set of projected points and a plane (aX + bY + cZ + d = 0...
Definition: chain3d_to_plane_error.h:40
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
robot_calibration::Chain3dToPlane::scale_
double scale_
Definition: chain3d_to_plane_error.h:130
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
robot_calibration::Chain3dToPlane::a_
double a_
Definition: chain3d_to_plane_error.h:129
robot_calibration::Chain3dToPlane::d_
double d_
Definition: chain3d_to_plane_error.h:129
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::Chain3dToPlane::Chain3dToPlane
Chain3dToPlane(ChainModel *chain_model, CalibrationOffsetParser *offsets, robot_calibration_msgs::CalibrationData &data, double a, double b, double c, double d, double scale)
This function is not used direcly, instead use the Create() function.
Definition: chain3d_to_plane_error.h:53
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::Chain3dToPlane::data_
robot_calibration_msgs::CalibrationData data_
Definition: chain3d_to_plane_error.h:128
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