Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #ifndef ROBOT_CALIBRATION_CERES_GROUND_PLANE_ERROR_H
00019 #define ROBOT_CALIBRATION_CERES_GROUND_PLANE_ERROR_H
00020
00021 #include <string>
00022 #include <ceres/ceres.h>
00023 #include <robot_calibration/calibration_offset_parser.h>
00024 #include <robot_calibration/models/camera3d.h>
00025 #include <robot_calibration/models/chain.h>
00026 #include <robot_calibration_msgs/CalibrationData.h>
00027
00028 namespace robot_calibration
00029 {
00030
00031 struct GroundPlaneError
00032 {
00033 GroundPlaneError(Camera3dModel* camera_model,
00034 CalibrationOffsetParser* offsets,
00035 robot_calibration_msgs::CalibrationData& data,
00036 double z)
00037 {
00038 camera_model_ = camera_model;
00039 z_ = z;
00040 offsets_ = offsets;
00041 data_ = data;
00042 }
00043
00044 virtual ~GroundPlaneError() {}
00045
00046 bool operator()(double const * const * free_params,
00047 double* residuals) const
00048 {
00049
00050 offsets_->update(free_params[0]);
00051
00052
00053 std::vector<geometry_msgs::PointStamped> camera_pts =
00054 camera_model_->project(data_, *offsets_);
00055
00056
00057 for (size_t i = 0; i < camera_pts.size() ; ++i)
00058 {
00059 residuals[i] = camera_pts[i].point.z - z_;
00060 }
00061 return true;
00062 }
00063
00064 static ceres::CostFunction* Create(Camera3dModel* camera_model,
00065 double z ,
00066 CalibrationOffsetParser* offsets,
00067 robot_calibration_msgs::CalibrationData& data)
00068 {
00069 int index = -1;
00070 for (size_t k =0; k < data.observations.size() ; k++)
00071 {
00072 if ( data.observations[k].sensor_name == camera_model->name())
00073 {
00074 index = k;
00075 break;
00076 }
00077 }
00078
00079 if (index == -1)
00080 {
00081 std::cerr << "Sensor name doesn't match any of the existing finders" << std::endl;
00082 return 0;
00083 }
00084
00085 ceres::DynamicNumericDiffCostFunction<GroundPlaneError> * func;
00086 func = new ceres::DynamicNumericDiffCostFunction<GroundPlaneError>(
00087 new GroundPlaneError(camera_model, offsets, data, z));
00088 func->AddParameterBlock(offsets->size());
00089 func->SetNumResiduals(data.observations[index].features.size());
00090
00091 return static_cast<ceres::CostFunction*>(func);
00092 }
00093
00094 Camera3dModel * camera_model_;
00095 double z_;
00096 CalibrationOffsetParser * offsets_;
00097 robot_calibration_msgs::CalibrationData data_;
00098 };
00099 }
00100
00101 #endif // ROBOT_CALIBRATION_CAPTURE_GROUND_PLANE_FINDER_H