Program Listing for File chain3d_to_chain3d_error.hpp
↰ Return to documentation for file (/tmp/ws/src/robot_calibration/robot_calibration/include/robot_calibration/cost_functions/chain3d_to_chain3d_error.hpp
)
/*
* Copyright (C) 2018 Michael Ferguson
* Copyright (C) 2015 Fetch Robotics Inc.
* Copyright (C) 2013-2014 Unbounded Robotics Inc.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
// Author: Michael Ferguson
#ifndef ROBOT_CALIBRATION_COST_FUNCTIONS_CHAIN3D_TO_CHAIN3D_ERROR_HPP
#define ROBOT_CALIBRATION_COST_FUNCTIONS_CHAIN3D_TO_CHAIN3D_ERROR_HPP
#include <string>
#include <ceres/ceres.h>
#include <robot_calibration/optimization/offsets.hpp>
#include <robot_calibration/util/calibration_data.hpp>
#include <robot_calibration/models/camera3d.hpp>
#include <robot_calibration/models/chain3d.hpp>
#include <robot_calibration_msgs/msg/calibration_data.hpp>
namespace robot_calibration
{
struct Chain3dToChain3d
{
Chain3dToChain3d(Chain3dModel* a_model,
Chain3dModel* b_model,
OptimizationOffsets* offsets,
robot_calibration_msgs::msg::CalibrationData& data)
{
a_model_ = a_model;
b_model_ = b_model;
offsets_ = offsets;
data_ = data;
}
virtual ~Chain3dToChain3d() {}
bool operator()(double const * const * free_params,
double* residuals) const
{
// Update calibration offsets based on free params
offsets_->update(free_params[0]);
// Project the observations into common base frame
std::vector<geometry_msgs::msg::PointStamped> a_pts =
a_model_->project(data_, *offsets_);
std::vector<geometry_msgs::msg::PointStamped> b_pts =
b_model_->project(data_, *offsets_);
if (a_pts.size() != b_pts.size())
{
std::cerr << "Observations do not match in size." << std::endl;
return false;
}
// Compute residuals
for (size_t i = 0; i < a_pts.size(); ++i)
{
if (a_pts[i].header.frame_id != b_pts[i].header.frame_id)
std::cerr << "Projected observation frame_ids do not match." << std::endl;
residuals[(3*i)+0] = a_pts[i].point.x - b_pts[i].point.x;
residuals[(3*i)+1] = a_pts[i].point.y - b_pts[i].point.y;
residuals[(3*i)+2] = a_pts[i].point.z - b_pts[i].point.z;
}
return true; // always return true
}
static ceres::CostFunction* Create(Chain3dModel* a_model,
Chain3dModel* b_model,
OptimizationOffsets* offsets,
robot_calibration_msgs::msg::CalibrationData& data)
{
int index = getSensorIndex(data, a_model->getName());
if (index == -1)
{
// In theory, we should never get here, because the optimizer does a check
std::cerr << "Sensor name doesn't match any of the existing finders" << std::endl;
return 0;
}
ceres::DynamicNumericDiffCostFunction<Chain3dToChain3d> * func;
func = new ceres::DynamicNumericDiffCostFunction<Chain3dToChain3d>(
new Chain3dToChain3d(a_model, b_model, offsets, data));
func->AddParameterBlock(offsets->size());
func->SetNumResiduals(data.observations[index].features.size() * 3);
return static_cast<ceres::CostFunction*>(func);
}
Chain3dModel * a_model_;
Chain3dModel * b_model_;
OptimizationOffsets * offsets_;
robot_calibration_msgs::msg::CalibrationData data_;
};
} // namespace robot_calibration
#endif // ROBOT_CALIBRATION_COST_FUNCTIONS_CHAIN3D_TO_CHAIN3D_ERROR_HPP