From 4be8073328bfc57ec34410bba4eae527af6f9643 Mon Sep 17 00:00:00 2001 From: Amilcar Lucas Date: Sat, 4 Aug 2012 18:44:29 +0200 Subject: [PATCH] Implement set ROI --- ArduPlane/commands_logic.pde | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/ArduPlane/commands_logic.pde b/ArduPlane/commands_logic.pde index fa3761a35e..ff84fc47d9 100644 --- a/ArduPlane/commands_logic.pde +++ b/ArduPlane/commands_logic.pde @@ -121,11 +121,10 @@ static void handle_process_do_command() // |Region of interest mode. (see MAV_ROI enum)| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple cameras etc.)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| case MAV_CMD_DO_SET_ROI: #if 0 - // we need to extract the location from the mission to - // support this - camera_mount.set_roi_cmd(); + // send the command to the camera mount + camera_mount.set_roi_cmd(&command_nav_queue); #else - gcs_send_text_P(SEVERITY_LOW, PSTR("DO_SET_ROI not supported")); + gcs_send_text_P(SEVERITY_LOW, PSTR("DO_SET_ROI not supported")); #endif break;