diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 19e0b4cefd..942b26419c 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -469,9 +469,9 @@ static void NOINLINE send_raw_imu2(mavlink_channel_t chan) static void NOINLINE send_raw_imu3(mavlink_channel_t chan) { - Vector3f mag_offsets = compass.get_offsets(); - Vector3f accel_offsets = ins.get_accel_offsets(); - Vector3f gyro_offsets = ins.get_gyro_offsets(); + const Vector3f &mag_offsets = compass.get_offsets(); + const Vector3f &accel_offsets = ins.get_accel_offsets(); + const Vector3f &gyro_offsets = ins.get_gyro_offsets(); mavlink_msg_sensor_offsets_send(chan, mag_offsets.x, diff --git a/ArduCopter/setup.pde b/ArduCopter/setup.pde index 02a8e77801..429f8b76cc 100644 --- a/ArduCopter/setup.pde +++ b/ArduCopter/setup.pde @@ -1182,8 +1182,8 @@ static void zero_eeprom(void) static void print_accel_offsets_and_scaling(void) { - Vector3f accel_offsets = ins.get_accel_offsets(); - Vector3f accel_scale = ins.get_accel_scale(); + const Vector3f &accel_offsets = ins.get_accel_offsets(); + const Vector3f &accel_scale = ins.get_accel_scale(); cliSerial->printf_P(PSTR("A_off: %4.2f, %4.2f, %4.2f\nA_scale: %4.2f, %4.2f, %4.2f\n"), (float)accel_offsets.x, // Pitch (float)accel_offsets.y, // Roll @@ -1196,7 +1196,7 @@ print_accel_offsets_and_scaling(void) static void print_gyro_offsets(void) { - Vector3f gyro_offsets = ins.get_gyro_offsets(); + const Vector3f &gyro_offsets = ins.get_gyro_offsets(); cliSerial->printf_P(PSTR("G_off: %4.2f, %4.2f, %4.2f\n"), (float)gyro_offsets.x, (float)gyro_offsets.y,