21 #ifndef ROBOT_CALIBRATION_CERES_CHAIN3D_TO_CHAIN3D_ERROR_H 22 #define ROBOT_CALIBRATION_CERES_CHAIN3D_TO_CHAIN3D_ERROR_H 25 #include <ceres/ceres.h> 30 #include <robot_calibration_msgs/CalibrationData.h> 52 robot_calibration_msgs::CalibrationData& data)
68 double* residuals)
const 74 std::vector<geometry_msgs::PointStamped> a_pts =
76 std::vector<geometry_msgs::PointStamped> b_pts =
79 if (a_pts.size() != b_pts.size())
81 std::cerr <<
"Observations do not match in size." << std::endl;
86 for (
size_t i = 0; i < a_pts.size(); ++i)
88 if (a_pts[i].header.frame_id != b_pts[i].header.frame_id)
89 std::cerr <<
"Projected observation frame_ids do not match." << std::endl;
90 residuals[(3*i)+0] = a_pts[i].point.x - b_pts[i].point.x;
91 residuals[(3*i)+1] = a_pts[i].point.y - b_pts[i].point.y;
92 residuals[(3*i)+2] = a_pts[i].point.z - b_pts[i].point.z;
105 robot_calibration_msgs::CalibrationData& data)
111 std::cerr <<
"Sensor name doesn't match any of the existing finders" << std::endl;
115 ceres::DynamicNumericDiffCostFunction<Chain3dToChain3d> * func;
116 func =
new ceres::DynamicNumericDiffCostFunction<Chain3dToChain3d>(
118 func->AddParameterBlock(offsets->
size());
119 func->SetNumResiduals(data.observations[index].features.size() * 3);
121 return static_cast<ceres::CostFunction*
>(func);
127 robot_calibration_msgs::CalibrationData
data_;
132 #endif // ROBOT_CALIBRATION_CERES_CHAIN3D_TO_CHAIN3D_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.
static ceres::CostFunction * Create(ChainModel *a_model, ChainModel *b_model, CalibrationOffsetParser *offsets, robot_calibration_msgs::CalibrationData &data)
Helper factory function to create a new error block. Parameters are described in the class constructo...
int getSensorIndex(const robot_calibration_msgs::CalibrationData &msg, const std::string &sensor)
Determine which observation index corresponds to a particular sensor name.
robot_calibration_msgs::CalibrationData data_
virtual ~Chain3dToChain3d()
Combined parser and configuration for calibration offsets. Holds the configuration of what is to be c...
bool operator()(double const *const *free_params, double *residuals) const
Operator called by CERES optimizer.
Chain3dToChain3d(ChainModel *a_model, ChainModel *b_model, CalibrationOffsetParser *offsets, robot_calibration_msgs::CalibrationData &data)
This function is not used direcly, instead use the Create() function.
Error block for computing the residual error between two 3d data sources. This can be used to calibra...
Calibration code lives under this namespace.
CalibrationOffsetParser * offsets_
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.