Copter: remove loop-initialisation of output

Use brace initialisation instead.  This is the only loop in here which
loops over the max number of compasses vs the number of compasses.
This commit is contained in:
Peter Barker 2019-06-03 10:11:57 +10:00 committed by Randy Mackay
parent e9ed3540f1
commit fa150bc982
1 changed files with 1 additions and 6 deletions

View File

@ -19,7 +19,7 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
float throttle_pct; // throttle as a percentage 0.0 ~ 1.0
float throttle_pct_max = 0.0f; // maximum throttle reached (as a percentage 0~1.0)
float current_amps_max = 0.0f; // maximum current reached
float interference_pct[COMPASS_MAX_INSTANCES]; // interference as a percentage of total mag field (for reporting purposes only)
float interference_pct[COMPASS_MAX_INSTANCES]{}; // interference as a percentage of total mag field (for reporting purposes only)
uint32_t last_run_time;
uint32_t last_send_time;
bool updated = false; // have we updated the compensation vector at least once
@ -33,11 +33,6 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
ap.compass_mot = true;
}
// initialise output
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
interference_pct[i] = 0.0f;
}
GCS_MAVLINK_Copter &gcs_chan = gcs().chan(chan-MAVLINK_COMM_0);
// check compass is enabled