21 #ifndef ROBOT_CALIBRATION_CERES_PLANE_TO_PLANE_ERROR_H
22 #define ROBOT_CALIBRATION_CERES_PLANE_TO_PLANE_ERROR_H
25 #include <ceres/ceres.h>
29 #include <robot_calibration_msgs/CalibrationData.h>
55 robot_calibration_msgs::CalibrationData &data,
56 double scale_normal,
double scale_offset)
74 double *residuals)
const
80 std::vector<geometry_msgs::PointStamped> a_pts =
84 Eigen::MatrixXd matrix_a =
getMatrix(a_pts);
85 Eigen::Vector3d normal_a;
90 std::vector<geometry_msgs::PointStamped> b_pts =
94 Eigen::MatrixXd matrix_b =
getMatrix(b_pts);
95 Eigen::Vector3d normal_b;
100 residuals[0] = std::fabs(normal_a(0) - normal_b(0)) *
scale_normal_;
101 residuals[1] = std::fabs(normal_a(1) - normal_b(1)) *
scale_normal_;
102 residuals[2] = std::fabs(normal_a(2) - normal_b(2)) *
scale_normal_;
105 Eigen::Vector3d centroid_a =
getCentroid(matrix_a);
106 residuals[3] = std::fabs((normal_b(0) * centroid_a(0)) +
107 (normal_b(1) * centroid_a(1)) +
120 robot_calibration_msgs::CalibrationData &data,
121 double scale_normal,
double scale_offset)
123 ceres::DynamicNumericDiffCostFunction <PlaneToPlaneError> *func;
124 func =
new ceres::DynamicNumericDiffCostFunction<PlaneToPlaneError>(
125 new PlaneToPlaneError(model_a, model_b, offsets, data, scale_normal, scale_offset));
126 func->AddParameterBlock(offsets->
size());
127 func->SetNumResiduals(4);
129 return static_cast<ceres::CostFunction*
>(func);
135 robot_calibration_msgs::CalibrationData
data_;
141 #endif // ROBOT_CALIBRATION_CERES_PLANE_TO_PLANE_ERROR_H