19 #ifndef ROBOT_CALIBRATION_CERES_CHAIN3D_TO_PLANE_ERROR_H 20 #define ROBOT_CALIBRATION_CERES_CHAIN3D_TO_PLANE_ERROR_H 24 #include <ceres/ceres.h> 29 #include <robot_calibration_msgs/CalibrationData.h> 55 robot_calibration_msgs::CalibrationData& data,
56 double a,
double b,
double c,
double d,
72 std::cerr <<
"Plane normal is extremely small: " << denom << std::endl;
80 double* residuals)
const 86 std::vector<geometry_msgs::PointStamped> chain_pts =
90 for (
size_t i = 0; i < chain_pts.size() ; ++i)
92 residuals[i] =
abs((
a_ * chain_pts[i].point.x) +
93 (
b_ * chain_pts[i].point.y) +
105 robot_calibration_msgs::CalibrationData& data,
106 double a,
double b,
double c,
double d,
113 std::cerr <<
"Sensor name doesn't match any of the existing finders" << std::endl;
117 ceres::DynamicNumericDiffCostFunction<Chain3dToPlane> * func;
118 func =
new ceres::DynamicNumericDiffCostFunction<Chain3dToPlane>(
120 func->AddParameterBlock(offsets->
size());
121 func->SetNumResiduals(data.observations[index].features.size());
123 return static_cast<ceres::CostFunction*
>(func);
128 robot_calibration_msgs::CalibrationData
data_;
135 #endif // ROBOT_CALIBRATION_CERES_CHAIN3D_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.
Chain3dToPlane(ChainModel *chain_model, CalibrationOffsetParser *offsets, robot_calibration_msgs::CalibrationData &data, double a, double b, double c, double d, double scale)
This function is not used direcly, instead use the Create() function.
CalibrationOffsetParser * offsets_
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_
Combined parser and configuration for calibration offsets. Holds the configuration of what is to be c...
ChainModel * chain_model_
static ceres::CostFunction * Create(ChainModel *a_model, CalibrationOffsetParser *offsets, robot_calibration_msgs::CalibrationData &data, double a, double b, double c, double d, double scale)
Helper factory function to create a new error block. Parameters are described in the class constructo...
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
Calibration code lives under this namespace.
bool operator()(double const *const *free_params, double *residuals) const
virtual ~Chain3dToPlane()
INLINE Rall1d< T, V, S > abs(const Rall1d< T, V, S > &x)
Error block for computing the fit between a set of projected points and a plane (aX + bY + cZ + d = 0...
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.