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> 30 #include <robot_calibration_msgs/CalibrationData.h> 32 #include <opencv2/calib3d/calib3d.hpp> 59 robot_calibration_msgs::CalibrationData &data,
60 double scale_normal,
double scale_offset)
79 double *residuals)
const 85 std::vector <geometry_msgs::PointStamped> a_pts =
89 std::vector <geometry_msgs::PointStamped> b_pts =
93 std::vector <cv::Point3f> a_points;
94 std::vector <cv::Point3f> b_points;
96 for (
size_t i = 0; i < a_pts.size(); ++i)
98 a_points.push_back(cv::Point3f(a_pts[i].point.x, a_pts[i].point.y, a_pts[i].point.z));
100 for (
size_t i = 0; i < b_pts.size(); ++i)
102 b_points.push_back(cv::Point3f(b_pts[i].point.x, b_pts[i].point.y, b_pts[i].point.z));
106 cv::Mat plane_1 =
getPlane(a_points);
107 cv::Mat plane_2 =
getPlane(b_points);
110 residuals[0] = (std::fabs(plane_1.at<
float>(0, 0)) - std::fabs(plane_2.at<
float>(0, 0))) *
scale_normal_;
111 residuals[1] = (std::fabs(plane_1.at<
float>(0, 1)) - std::fabs(plane_2.at<
float>(0, 1))) *
scale_normal_;
112 residuals[2] = (std::fabs(plane_1.at<
float>(0, 2)) - std::fabs(plane_2.at<
float>(0, 2))) *
scale_normal_;
125 robot_calibration_msgs::CalibrationData &data,
126 double scale_normal,
double scale_offset)
132 std::cerr <<
"Sensor name doesn't match any of the existing finders" << std::endl;
136 ceres::DynamicNumericDiffCostFunction <PlaneToPlaneError> *func;
137 func =
new ceres::DynamicNumericDiffCostFunction<PlaneToPlaneError>(
138 new PlaneToPlaneError(model_a, model_b, offsets, data, scale_normal, scale_offset));
139 func->AddParameterBlock(offsets->
size());
140 func->SetNumResiduals(4);
142 return static_cast<ceres::CostFunction *
>(func);
150 cv::Mat
getPlane(std::vector <cv::Point3f> points)
const 153 cv::Point3f centroid(0, 0, 0);
154 for (
size_t i = 0; i < points.size(); i++)
156 centroid += points.at(i);
159 centroid.x = centroid.x / points.size();
160 centroid.y = centroid.y / points.size();
161 centroid.z = centroid.z / points.size();
164 cv::Mat pts_mat(points.size(), 3, CV_32F);
165 for (
size_t i = 0; i < points.size(); i++)
167 pts_mat.at<
float>(i, 0) = points[i].
x - centroid.x;
168 pts_mat.at<
float>(i, 1) = points[i].y - centroid.y;
169 pts_mat.at<
float>(i, 2) = points[i].
z - centroid.z;
173 cv::SVD svd(pts_mat, cv::SVD::FULL_UV);
174 cv::Mat normal = svd.vt.row(2);
182 robot_calibration_msgs::CalibrationData
data_;
188 #endif // ROBOT_CALIBRATION_CERES_PLANE_TO_PLANE_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.
PlaneToPlaneError(ChainModel *model_a, ChainModel *model_b, CalibrationOffsetParser *offsets, robot_calibration_msgs::CalibrationData &data, double scale_normal, double scale_offset)
Error block for calibrating two planar data sets.
int getSensorIndex(const robot_calibration_msgs::CalibrationData &msg, const std::string &sensor)
Determine which observation index corresponds to a particular sensor name.
Combined parser and configuration for calibration offsets. Holds the configuration of what is to be c...
Error block for computing the fit between two sets of projected points and their planar models plane ...
robot_calibration_msgs::CalibrationData data_
bool operator()(double const *const *free_params, double *residuals) const
Operator called by CERES optimizer.
TFSIMD_FORCE_INLINE const tfScalar & x() const
Calibration code lives under this namespace.
CalibrationOffsetParser * offsets_
TFSIMD_FORCE_INLINE const tfScalar & z() const
cv::Mat getPlane(std::vector< cv::Point3f > points) const
Does a plane fit to the points and calculates the normals.
static ceres::CostFunction * Create(ChainModel *model_a, ChainModel *model_b, CalibrationOffsetParser *offsets, robot_calibration_msgs::CalibrationData &data, double scale_normal, double scale_offset)
Helper factory function to create a new error block. Parameters are described in the class constructo...
Model of a kinematic chain. This is the basic instance where we transform the world observations into...
bool update(const double *const free_params)
Update the offsets based on free_params from ceres-solver.
virtual ~PlaneToPlaneError()