From a8b9b2742d65953f1b736f92caafe27e6e10238b Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 7 Mar 2023 15:40:24 +0900 Subject: [PATCH] GCS_MAVLink: move camera command handling to AP_Camera --- libraries/GCS_MAVLink/GCS_Common.cpp | 34 +--------------------------- 1 file changed, 1 insertion(+), 33 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 22a78712ce..690621002f 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -3361,39 +3361,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_camera(const mavlink_command_long_t &pack return MAV_RESULT_UNSUPPORTED; } - MAV_RESULT result = MAV_RESULT_FAILED; - switch (packet.command) { - case MAV_CMD_DO_DIGICAM_CONFIGURE: - camera->configure(packet.param1, - packet.param2, - packet.param3, - packet.param4, - packet.param5, - packet.param6, - packet.param7); - result = MAV_RESULT_ACCEPTED; - break; - case MAV_CMD_DO_DIGICAM_CONTROL: - camera->control(packet.param1, - packet.param2, - packet.param3, - packet.param4, - packet.param5, - packet.param6); - result = MAV_RESULT_ACCEPTED; - break; - case MAV_CMD_DO_SET_CAM_TRIGG_DIST: - camera->set_trigger_distance(packet.param1); - if (is_equal(packet.param3, 1.0f)) { - camera->take_picture(); - } - result = MAV_RESULT_ACCEPTED; - break; - default: - result = MAV_RESULT_UNSUPPORTED; - break; - } - return result; + return camera->handle_command_long(packet); } #endif