mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: Calibrator: use inplace initializer on array
This commit is contained in:
parent
b36ee10e7c
commit
c6b0a71c47
|
@ -504,13 +504,10 @@ void CompassCalibrator::run_sphere_fit()
|
|||
param_t fit1_params, fit2_params;
|
||||
fit1_params = fit2_params = _params;
|
||||
|
||||
float JTJ[COMPASS_CAL_NUM_SPHERE_PARAMS*COMPASS_CAL_NUM_SPHERE_PARAMS];
|
||||
float JTJ2[COMPASS_CAL_NUM_SPHERE_PARAMS*COMPASS_CAL_NUM_SPHERE_PARAMS];
|
||||
float JTFI[COMPASS_CAL_NUM_SPHERE_PARAMS];
|
||||
float JTJ[COMPASS_CAL_NUM_SPHERE_PARAMS*COMPASS_CAL_NUM_SPHERE_PARAMS] = { };
|
||||
float JTJ2[COMPASS_CAL_NUM_SPHERE_PARAMS*COMPASS_CAL_NUM_SPHERE_PARAMS] = { };
|
||||
float JTFI[COMPASS_CAL_NUM_SPHERE_PARAMS] = { };
|
||||
|
||||
memset(JTJ,0,sizeof(JTJ));
|
||||
memset(JTJ2,0,sizeof(JTJ2));
|
||||
memset(JTFI,0,sizeof(JTFI));
|
||||
// Gauss Newton Part common for all kind of extensions including LM
|
||||
for(uint16_t k = 0; k<_samples_collected; k++) {
|
||||
Vector3f sample = _sample_buffer[k].get();
|
||||
|
@ -620,13 +617,10 @@ void CompassCalibrator::run_ellipsoid_fit()
|
|||
fit1_params = fit2_params = _params;
|
||||
|
||||
|
||||
float JTJ[COMPASS_CAL_NUM_ELLIPSOID_PARAMS*COMPASS_CAL_NUM_ELLIPSOID_PARAMS];
|
||||
float JTJ2[COMPASS_CAL_NUM_ELLIPSOID_PARAMS*COMPASS_CAL_NUM_ELLIPSOID_PARAMS];
|
||||
float JTFI[COMPASS_CAL_NUM_ELLIPSOID_PARAMS];
|
||||
float JTJ[COMPASS_CAL_NUM_ELLIPSOID_PARAMS*COMPASS_CAL_NUM_ELLIPSOID_PARAMS] = { };
|
||||
float JTJ2[COMPASS_CAL_NUM_ELLIPSOID_PARAMS*COMPASS_CAL_NUM_ELLIPSOID_PARAMS] = { };
|
||||
float JTFI[COMPASS_CAL_NUM_ELLIPSOID_PARAMS] = { };
|
||||
|
||||
memset(JTJ,0,sizeof(JTJ));
|
||||
memset(JTJ2,0,sizeof(JTJ2));
|
||||
memset(JTFI,0,sizeof(JTFI));
|
||||
// Gauss Newton Part common for all kind of extensions including LM
|
||||
for(uint16_t k = 0; k<_samples_collected; k++) {
|
||||
Vector3f sample = _sample_buffer[k].get();
|
||||
|
|
Loading…
Reference in New Issue