diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde
index 00b0d36e7f3d4177ee72acd789c3ae27040b5c8b..b1728e46ab84ca5ca7c2f3a286d7cfce1f1d4a7e 100644
--- a/ArduCopter/GCS_Mavlink.pde
+++ b/ArduCopter/GCS_Mavlink.pde
@@ -276,8 +276,7 @@ static void NOINLINE send_location(mavlink_channel_t chan)
 
 static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
 {
-    Vector3f targets;
-    get_angle_targets_for_reporting(targets);
+    const Vector3f &targets = attitude_control.angle_ef_targets();
     mavlink_msg_nav_controller_output_send(
         chan,
         targets.x / 1.0e2f,
diff --git a/ArduCopter/Log.pde b/ArduCopter/Log.pde
index 1b146eadba9875db0541314694dfc1a365d614b6..0f0c8a0fb5dea8ed8caacaed019baeeaed9443a2 100644
--- a/ArduCopter/Log.pde
+++ b/ArduCopter/Log.pde
@@ -469,8 +469,7 @@ struct PACKED log_Attitude {
 // Write an attitude packet
 static void Log_Write_Attitude()
 {
-    Vector3f targets;
-    get_angle_targets_for_reporting(targets);
+    const Vector3f &targets = attitude_control.angle_ef_targets();
     struct log_Attitude pkt = {
         LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG),
         time_ms         : hal.scheduler->millis(),
diff --git a/ArduCopter/flight_mode.pde b/ArduCopter/flight_mode.pde
index 9caf7eb316c221a3d03d3b39f5346312338dce36..07761919913b77a83f8aedff41823ed255073da1 100644
--- a/ArduCopter/flight_mode.pde
+++ b/ArduCopter/flight_mode.pde
@@ -327,8 +327,3 @@ print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
     }
 }
 
-// get_angle_targets_for_reporting() - returns 3d vector of roll, pitch and yaw target angles for logging and reporting to GCS
-static void get_angle_targets_for_reporting(Vector3f& targets)
-{
-    targets = attitude_control.angle_ef_targets();
-}