Copter: initialise compass_mot interference_pct variable

resolves a compiler warning
This commit is contained in:
Randy Mackay 2016-04-23 10:21:36 +09:00 committed by Tom Pittenger
parent f70072c54b
commit 472f54ce45
1 changed files with 5 additions and 0 deletions

View File

@ -35,6 +35,11 @@ uint8_t 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;
}
// check compass is enabled
if (!g.compass_enabled) {
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "Compass disabled");