mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
AP_Compass: simplify calibration transition to COMPASS_CAL_RUNNING_STEP_ONE
This commit is contained in:
parent
f21ee7694a
commit
f8433f82e6
@ -253,14 +253,12 @@ bool CompassCalibrator::set_status(compass_cal_status_t status) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if(_sample_buffer != NULL) {
|
||||
initialize_fit();
|
||||
_status = COMPASS_CAL_RUNNING_STEP_ONE;
|
||||
return true;
|
||||
if (_sample_buffer == NULL) {
|
||||
_sample_buffer =
|
||||
(CompassSample*) malloc(sizeof(CompassSample) *
|
||||
COMPASS_CAL_NUM_SAMPLES);
|
||||
}
|
||||
|
||||
_sample_buffer = (CompassSample*)malloc(sizeof(CompassSample)*COMPASS_CAL_NUM_SAMPLES);
|
||||
|
||||
if(_sample_buffer != NULL) {
|
||||
initialize_fit();
|
||||
_status = COMPASS_CAL_RUNNING_STEP_ONE;
|
||||
|
Loading…
Reference in New Issue
Block a user