19 #ifndef ROBOT_CALIBRATION_CERES_CHAIN3D_TO_MESH_ERROR_H
20 #define ROBOT_CALIBRATION_CERES_CHAIN3D_TO_MESH_ERROR_H
25 #include <ceres/ceres.h>
31 #include <robot_calibration_msgs/CalibrationData.h>
44 double distToLine(Eigen::Vector3d& a, Eigen::Vector3d& b, Eigen::Vector3d c)
46 Eigen::Vector3d ab = b - a;
47 Eigen::Vector3d ac = c - a;
48 Eigen::Vector3d bc = c - b;
50 double e = ac.dot(ab);
56 double f = ab.dot(ab);
63 return ac.dot(ac) - e * e /
f;
82 robot_calibration_msgs::CalibrationData& data,
94 double* residuals)
const
100 std::vector<geometry_msgs::PointStamped> chain_pts =
104 for (
size_t pt = 0; pt < chain_pts.size() ; ++pt)
106 Eigen::Vector3d p(chain_pts[pt].
point.x, chain_pts[pt].point.y, chain_pts[pt].point.z);
109 double dist = std::numeric_limits<double>::max();
110 for (
size_t t = 0;
t <
mesh_->triangle_count; ++
t)
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];
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]);
124 dist = std::min(
d, dist);
126 residuals[pt] = std::sqrt(dist);
137 robot_calibration_msgs::CalibrationData& data,
144 std::cerr <<
"Sensor name doesn't match any of the existing finders" << std::endl;
148 ceres::DynamicNumericDiffCostFunction<Chain3dToMesh> * func;
149 func =
new ceres::DynamicNumericDiffCostFunction<Chain3dToMesh>(
151 func->AddParameterBlock(offsets->
size());
152 func->SetNumResiduals(data.observations[
index].features.size());
154 return static_cast<ceres::CostFunction*
>(func);
159 robot_calibration_msgs::CalibrationData
data_;
165 #endif // ROBOT_CALIBRATION_CERES_CHAIN3D_TO_MESH_ERROR_H