mirror of https://github.com/ArduPilot/ardupilot
AP_AccelCal: remove pointless assignment when counting calibrators
cal isn't used after the assignment is made. Pointed out by clang-scan-build
This commit is contained in:
parent
cf496a3c00
commit
0e2461ffd2
|
@ -44,9 +44,8 @@ void AP_AccelCal::update()
|
||||||
if (_started) {
|
if (_started) {
|
||||||
update_status();
|
update_status();
|
||||||
|
|
||||||
AccelCalibrator *cal;
|
|
||||||
uint8_t num_active_calibrators = 0;
|
uint8_t num_active_calibrators = 0;
|
||||||
for(uint8_t i=0; (cal = get_calibrator(i)); i++) {
|
for(uint8_t i=0; get_calibrator(i) != nullptr; i++) {
|
||||||
num_active_calibrators++;
|
num_active_calibrators++;
|
||||||
}
|
}
|
||||||
if (num_active_calibrators != _num_active_calibrators) {
|
if (num_active_calibrators != _num_active_calibrators) {
|
||||||
|
@ -56,6 +55,7 @@ void AP_AccelCal::update()
|
||||||
if(_start_collect_sample) {
|
if(_start_collect_sample) {
|
||||||
collect_sample();
|
collect_sample();
|
||||||
}
|
}
|
||||||
|
AccelCalibrator *cal;
|
||||||
switch(_status) {
|
switch(_status) {
|
||||||
case ACCEL_CAL_NOT_STARTED:
|
case ACCEL_CAL_NOT_STARTED:
|
||||||
fail();
|
fail();
|
||||||
|
|
Loading…
Reference in New Issue