diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 6e4fef23b5..7fda979a44 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -414,8 +414,9 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan) static void NOINLINE send_raw_imu1(mavlink_channel_t chan) { - Vector3f accel = ins.get_accel(); - Vector3f gyro = ins.get_gyro(); + const Vector3f &accel = ins.get_accel(); + const Vector3f &gyro = ins.get_gyro(); + const Vector3f &mag = compass.get_field(); mavlink_msg_raw_imu_send( chan, @@ -426,9 +427,9 @@ static void NOINLINE send_raw_imu1(mavlink_channel_t chan) gyro.x * 1000.0, gyro.y * 1000.0, gyro.z * 1000.0, - compass.mag_x, - compass.mag_y, - compass.mag_z); + mag.x, + mag.y, + mag.z); } static void NOINLINE send_raw_imu2(mavlink_channel_t chan) @@ -473,7 +474,7 @@ static void NOINLINE send_raw_imu3(mavlink_channel_t chan) static void NOINLINE send_ahrs(mavlink_channel_t chan) { - Vector3f omega_I = ahrs.get_gyro_drift(); + const Vector3f &omega_I = ahrs.get_gyro_drift(); mavlink_msg_ahrs_send( chan, omega_I.x, diff --git a/ArduPlane/Log.pde b/ArduPlane/Log.pde index 9f37d0bca7..7f4e5cd5f0 100644 --- a/ArduPlane/Log.pde +++ b/ArduPlane/Log.pde @@ -455,13 +455,14 @@ struct PACKED log_Compass { // Write a Compass packet. Total length : 15 bytes static void Log_Write_Compass() { - Vector3f mag_offsets = compass.get_offsets(); + const Vector3f &mag_offsets = compass.get_offsets(); + const Vector3f &mag = compass.get_field(); struct log_Compass pkt = { LOG_PACKET_HEADER_INIT(LOG_COMPASS_MSG), time_ms : hal.scheduler->millis(), - mag_x : compass.mag_x, - mag_y : compass.mag_y, - mag_z : compass.mag_z, + mag_x : (int16_t)mag.x, + mag_y : (int16_t)mag.y, + mag_z : (int16_t)mag.z, offset_x : (int16_t)mag_offsets.x, offset_y : (int16_t)mag_offsets.y, offset_z : (int16_t)mag_offsets.z diff --git a/ArduPlane/test.pde b/ArduPlane/test.pde index b1918c1a58..10b8184940 100644 --- a/ArduPlane/test.pde +++ b/ArduPlane/test.pde @@ -523,15 +523,12 @@ test_mag(uint8_t argc, const Menu::arg *argv) counter++; if (counter>20) { if (compass.healthy) { - Vector3f maggy = compass.get_offsets(); - cliSerial->printf_P(PSTR("Heading: %ld, XYZ: %d, %d, %d,\tXYZoff: %6.2f, %6.2f, %6.2f\n"), - (wrap_360_cd(ToDeg(heading) * 100)) /100, - (int)compass.mag_x, - (int)compass.mag_y, - (int)compass.mag_z, - maggy.x, - maggy.y, - maggy.z); + const Vector3f &mag_ofs = compass.get_offsets(); + const Vector3f &mag = compass.get_field(); + cliSerial->printf_P(PSTR("Heading: %ld, XYZ: %.0f, %.0f, %.0f,\tXYZoff: %6.2f, %6.2f, %6.2f\n"), + (wrap_360_cd(ToDeg(heading) * 100)) /100, + mag.x, mag.y, mag.z, + mag_ofs.x, mag_ofs.y, mag_ofs.z); } else { cliSerial->println_P(PSTR("compass not healthy")); }