mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: remove unused calc_mean_squared_residuals
This commit is contained in:
parent
feb0f141fa
commit
90cfbe01e4
|
@ -461,11 +461,6 @@ float CompassCalibrator::calc_residual(const Vector3f& sample, const param_t& pa
|
||||||
return params.radius - (softiron*(sample+params.offset)).length();
|
return params.radius - (softiron*(sample+params.offset)).length();
|
||||||
}
|
}
|
||||||
|
|
||||||
float CompassCalibrator::calc_mean_squared_residuals() const
|
|
||||||
{
|
|
||||||
return calc_mean_squared_residuals(_params);
|
|
||||||
}
|
|
||||||
|
|
||||||
// calc the fitness given a set of parameters (offsets, diagonals, off diagonals)
|
// calc the fitness given a set of parameters (offsets, diagonals, off diagonals)
|
||||||
float CompassCalibrator::calc_mean_squared_residuals(const param_t& params) const
|
float CompassCalibrator::calc_mean_squared_residuals(const param_t& params) const
|
||||||
{
|
{
|
||||||
|
|
|
@ -133,7 +133,6 @@ private:
|
||||||
// calc the fitness of the parameters (offsets, diagonals, off diagonals) vs all the samples collected
|
// calc the fitness of the parameters (offsets, diagonals, off diagonals) vs all the samples collected
|
||||||
// returns 1.0e30f if the sample buffer is empty
|
// returns 1.0e30f if the sample buffer is empty
|
||||||
float calc_mean_squared_residuals(const param_t& params) const;
|
float calc_mean_squared_residuals(const param_t& params) const;
|
||||||
float calc_mean_squared_residuals() const;
|
|
||||||
|
|
||||||
// calculate initial offsets by simply taking the average values of the samples
|
// calculate initial offsets by simply taking the average values of the samples
|
||||||
void calc_initial_offset();
|
void calc_initial_offset();
|
||||||
|
|
Loading…
Reference in New Issue