GCS_MAVLink: send mav-cmd-set-camera-zoom to AP_Camera

also send focus and image capture
This commit is contained in:
Randy Mackay 2023-03-07 16:11:18 +09:00
parent 227daf31f7
commit a3e3e5fd2d

View File

@ -4701,6 +4701,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
case MAV_CMD_DO_DIGICAM_CONFIGURE:
case MAV_CMD_DO_DIGICAM_CONTROL:
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
case MAV_CMD_SET_CAMERA_ZOOM:
case MAV_CMD_SET_CAMERA_FOCUS:
case MAV_CMD_IMAGE_START_CAPTURE:
case MAV_CMD_VIDEO_START_CAPTURE:
case MAV_CMD_VIDEO_STOP_CAPTURE:
result = handle_command_camera(packet);
break;
#endif