Commit a76c14af authored by Don Gagne's avatar Don Gagne

Merge pull request #2995 from DonLakeFlyer/APM3Compass

Support for third compass calibration
parents 0d7fd3ce 9a5cf379
...@@ -148,9 +148,15 @@ CalWorkerThread::calibrate_return CalWorkerThread::calibrate(void) ...@@ -148,9 +148,15 @@ CalWorkerThread::calibrate_return CalWorkerThread::calibrate(void)
if (rgCompassAvailable[cur_mag]) { if (rgCompassAvailable[cur_mag]) {
_emitVehicleTextMessage(QString("[cal] mag #%1 off: x:%2 y:%3 z:%4").arg(cur_mag).arg(-sphere_x[cur_mag]).arg(-sphere_y[cur_mag]).arg(-sphere_z[cur_mag])); _emitVehicleTextMessage(QString("[cal] mag #%1 off: x:%2 y:%3 z:%4").arg(cur_mag).arg(-sphere_x[cur_mag]).arg(-sphere_y[cur_mag]).arg(-sphere_z[cur_mag]));
if (cur_mag != 2) { float sensorId = 0.0f;
float sensorId; if (cur_mag == 0) {
sensorId = cur_mag == 0 ? 2.0f : 5.0f; sensorId = 2.0f;
} else if (cur_mag == 1) {
sensorId = 5.0f;
} else if (cur_mag == 2) {
sensorId = 6.0f;
}
if (sensorId != 0.0f) {
_vehicle->doCommandLong(0, MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS, sensorId, -sphere_x[cur_mag], -sphere_y[cur_mag], -sphere_z[cur_mag]); _vehicle->doCommandLong(0, MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS, sensorId, -sphere_x[cur_mag], -sphere_y[cur_mag], -sphere_z[cur_mag]);
} }
} }
...@@ -704,5 +710,6 @@ void APMCompassCal::_stopCalibration(void) ...@@ -704,5 +710,6 @@ void APMCompassCal::_stopCalibration(void)
void APMCompassCal::_emitVehicleTextMessage(const QString& message) void APMCompassCal::_emitVehicleTextMessage(const QString& message)
{ {
qCDebug(APMCompassCalLog()) << message;
emit vehicleTextMessage(_vehicle->id(), 0, MAV_SEVERITY_INFO, message); emit vehicleTextMessage(_vehicle->id(), 0, MAV_SEVERITY_INFO, message);
} }
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment