diff --git a/ArduCopter/control_auto.pde b/ArduCopter/control_auto.pde index 6ca9e652b4..718efe99bb 100644 --- a/ArduCopter/control_auto.pde +++ b/ArduCopter/control_auto.pde @@ -595,7 +595,7 @@ static void set_auto_yaw_roi(const Location &roi_location) set_auto_yaw_mode(AUTO_YAW_ROI); } // send the command to the camera mount - camera_mount.set_roi_cmd(&roi_location); + camera_mount.set_roi_target(roi_location); // TO-DO: expand handling of the do_nav_roi to support all modes of the MAVLink. Currently we only handle mode 4 (see below) // 0: do nothing