template<typename ConcreteOccGridMapUtil>
class getResidual : public ceres::SizedCostFunction<1,3>
{
public:
ConcreteOccGridMapUtil* occ;
DataContainer dataPoints;
getResidual(ConcreteOccGridMapUtil* occ, const DataContainer& dataPoints)
{
this->occ = occ;
this->dataPoints = dataPoints;
}
virtual ~getResidual() {}
virtual bool Evaluate(double const* const* parameters,
double* residuals,
double** jacobians) const
{
Eigen::Matrix<double, 3, 1> pose1(parameters[0][0],parameters[0][1],parameters[0][2]);
Eigen::Vector3f pose = pose1.cast<float>();
Eigen::Affine2f transform(occ->getTransformForState(pose)); // transform: rotation->translation
float sinRot = std::sin(pose[2]);
float cosRot = std::cos(pose[2]);
int size = dataPoints.getSize();
if (jacobians == NULL || jacobians[0]==NULL)
{
return true;
}
residuals[0] = 0;
jacobians[0][0]=0;
jacobians[0][1]=0;
jacobians[0][2]=0;
for (int i = 0; i < size; ++i)
{
const Eigen::Vector2f& currPoint (dataPoints.getVecEntry(i)); /// lidar point
Eigen::Vector3f transformedPointData(occ->interpMapValueWithDerivatives(transform * currPoint)); /// {M,dM/dx,dM/dy}
float funVal = 1.0f - transformedPointData[0];
// float weight=util::WeightValue(funVal);
float weight=1.0;
residuals[0] += static_cast<double>(funVal);
double rotDeriv = ((-sinRot * currPoint.x() - cosRot * currPoint.y()) * transformedPointData[1] + (cosRot * currPoint.x() - sinRot * currPoint.y()) * transformedPointData[2]);
jacobians[0][0] += static_cast<double>(transformedPointData[1]);
jacobians[0][1] += static_cast<double>(transformedPointData[2]);
jacobians[0][2] += static_cast<double>(rotDeriv);
}
return true;
}
};
Solver Summary (v 1.12.0-eigen-(3.2.0)-lapack-suitesparse-(4.2.1)-openmp)
Original Reduced
Parameter blocks 1 1
Parameters 3 3
Residual blocks 1 1
Residual 1 1
Minimizer TRUST_REGION
Dense linear algebra library EIGEN
Trust region strategy LEVENBERG_MARQUARDT
Given Used
Linear solver DENSE_QR DENSE_QR
Threads 1 1
Linear solver threads 1 1
Linear solver ordering AUTOMATIC 1
Cost:
Initial 8.569800e+04
Final 8.569800e+04
Change 0.000000e+00
Minimizer iterations 1
Successful steps 1
Unsuccessful steps 0
Time (in seconds):
Preprocessor 0.0001
Residual evaluation 0.0000
Jacobian evaluation 0.0050
Linear solver 0.0000
Minimizer 0.0051
Postprocessor 0.0000
Total 0.0052
iter cost cost_change |gradient| |step| tr_ratio tr_radius ls_iter iter_time total_time
0 1.327398e+04 0.00e+00 1.30e+03 0.00e+00 0.00e+00 1.00e+04 0 3.66e-03 3.71e-03
W1227 11:35:48.130611 19682 residual_block.cc:131]
Error in evaluating the ResidualBlock.
There are two possible reasons. Either the CostFunction did not evaluate and fill all
residual and jacobians that were requested or there was a non-finite value (nan/infinite)
generated during the or jacobian computation.
Residual Block size: 1 parameter blocks x 1 residuals
For each parameter block, the value of the parameters are printed in the first column
and the value of the jacobian under the corresponding residual. If a ParameterBlock was
held constant then the corresponding jacobian is printed as 'Not Computed'. If an entry
of the Jacobian/residual array was requested but was not written to by user code, it is
indicated by 'Uninitialized'. This is an error. Residuals or Jacobian values evaluating
to Inf or NaN is also an error.
Residuals: Uninitialized
Parameter Block 0, size: 3
86.9613 | Not Computed
86.9613 | Not Computed
-6.78875 | Not Computed
W1227 11:35:48.130638 19682 trust_region_minimizer.cc:729] Step failed to evaluate. Treating it as a step with infinite cost
1 1.797693e+308 -1.80e+308 0.00e+00 1.18e+01 -1.35e+304 5.00e+03 1 1.33e-04 3.93e-03
W1227 11:35:48.130678 19682 residual_block.cc:131]
Error in evaluating the ResidualBlock.
There are two possible reasons. Either the CostFunction did not evaluate and fill all
residual and jacobians that were requested or there was a non-finite value (nan/infinite)
generated during the or jacobian computation.
Residual Block size: 1 parameter blocks x 1 residuals
For each parameter block, the value of the parameters are printed in the first column
and the value of the jacobian under the corresponding residual. If a ParameterBlock was
held constant then the corresponding jacobian is printed as 'Not Computed'. If an entry
of the Jacobian/residual array was requested but was not written to by user code, it is
indicated by 'Uninitialized'. This is an error. Residuals or Jacobian values evaluating
to Inf or NaN is also an error.
pose = [x,y,theta]
my objective function is to minimize the occupancy value in map about pose and laser point. And here I add them manually together into residuals[0]
I have 3 parameters [x,y,theta], parameters[0][3],
so my jacobians have 3 dimensions in jocobians[0][3]
--
You received this message because you are subscribed to the Google Groups "Ceres Solver" group.
To unsubscribe from this group and stop receiving emails from it, send an email to ceres-solver...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/ceres-solver/0fea0e90-1fbe-48e4-b344-18d449c955bf%40googlegroups.com.
For more options, visit https://groups.google.com/d/optout.
class QuadraticCostFunction : public ceres::SizedCostFunction<1, 1> { public: virtual ~QuadraticCostFunction() {}
virtual bool Evaluate(double const* const* parameters, double* residuals, double** jacobians) const {
const double x = parameters[0][0]; residuals[0] = 10 - x; // Compute the Jacobian if asked for. if (jacobians != NULL && jacobians[0] != NULL) { jacobians[0][0] = -1; } return true; } };Could you explain more about why the checking makes sense?
The reason the one or more of the Jacobians may not be requested is because,
1. Sometimes Ceres just needs the cost and not the derivatives. E.g. when evaluating the quality of the trust region step. In this case asking the user to evaluate the Jacobian is wasteful work.
2. If you have a cost function where one or more of the parameter blocks are held constant, then we will not ask you for derivatives with respect to that parameter block. Again for reasons of efficiency.
Therefore it is important to check if the jacobians array is non-null AND that individual entries of this array are non-null before deciding to compute their values and filling them.
Sameer
To unsubscribe from this group and stop receiving emails from it, send an email to ceres-solver+unsubscribe@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/ceres-solver/7d84afc3-5e8d-4be0-84e9-5ecfeeaa2a58%40googlegroups.com.