Webcam Controls

Introduction

This basic tutorial describes 8 webcam controls available in the SDK. It includes an example, using 2 of these controls to potentially improve TensorFlow recognition in Freight Frenzy.

Hats off to rgatkinson and Windwoes who developed these webcam controls.

Software Overview

The SDK contains a superinterface called CameraControl, which contains 5 interfaces:

Similar to Java classes, Java interfaces provide methods. A webcam can be controlled using methods of these 5 interfaces.

PtzControl allows control of 3 related features: virtual pan, tilt and zoom. ExposureControl also contains a feature called auto-exposure priority, or AE Priority. Together there are 8 webcam controls discussed in this tutorial.

The official documentation is found in the Javadocs. Click the link for RobotCore, then click the CameraControl link in the left column.

../../../_images/020-RobotCore.png

RobotCore Javadoc API

That page provides links to the 5 interfaces listed above.

The methods described here can be used in Android Studio or OnBot Java. They can also be provided to Blocks programmers by creating myBlocks, covered in a separate Blocks programming Tutorial.

You will see Vuforia mentioned here, and in the sample OpModes below. Why Vuforia? The FIRST Tech Challenge implementation of Google’s TensorFlow Lite receives camera images from a Vuforia video stream. The SDK already includes and uses Vuforia for navigation, so it’s a convenient tool for passing camera streams to TFOD.

These CameraControl interfaces allow some control of the webcam, within requirements or settings of Vuforia for its own performance. Such settings include resolution and frame rate, not covered here.

Exposure Control

Exposure is the amount of light that reaches the webcam sensor. It is an important part of how bright or dark your image appears.

Exposure varies directly with the amount of time that the shutter is open, allowing light to enter and reach the sensor. So, the interface ExposureControl uses a single value of duration, in units of time that you specify, typically TimeUnit.MILLISECONDS.

For example, at a frame rate of 60 frames per second (fps), exposure duration is 1/60 of a second, or 1/60 x 1000 = 16 milliseconds. This basic tutorial does not address frame rate.

Here are the methods to manage exposure:

  • setExposure() has two parameters: duration and time unit

  • getExposure() has one parameter: time unit

The webcam may support minimum and maximum allowed values of exposure. These can be retrieved with:

  • getMinExposure(TimeUnit.MILLISECONDS)

  • getMaxExposure(TimeUnit.MILLISECONDS)

There are no set() methods for min and max exposure; these are hard-coded in the webcam’s firmware. Note that firmware settings may vary among different versions of the same webcam model.

These and other exposure methods are called on an ExposureControl object; sample code is shown below, after Exposure Control Mode.

Exposure Control Mode

org.firstinspires.ftc.robotcore.external.hardware.camera.controls

A webcam may operate in one of various exposure modes.

Many common webcams offer only some of these modes. To directly control the exposure, set the webcam to Manual mode.

The SDK supports these values of ExposureControl.Mode:

  • AperturePriority

  • Auto

  • ContinuousAuto

  • Manual

  • ShutterPriority

  • Unknown

Mode is managed with these ExposureControl methods:

  • setMode(ExposureControl.Mode._mode_)

  • getMode()

The Logitech C920 and C270 models offer two exposure modes: AperturePriority and Manual.

Exposure Control code samples

  1. Import the interface. This line is automatically added by OnBot Java when the interface is used (coded).

  • import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.ExposureControl;

  1. Declare the ExposureControl object, before runOpMode().

  • ExposureControl myExposureControl;

  1. Assign the Vuforia/TFOD video stream control to your control object, in runOpMode().

  • myExposureControl = vuforia.getCamera().getControl(ExposureControl.class);

  1. Set the mode to Manual, for direct control.

  • myExposureControl.setMode(ExposureControl.Mode.Manual);

  1. Set the exposure duration, in this case to 30 milliseconds.

  • myExposureControl.setExposure(30, TimeUnit.MILLISECONDS);

See far below for these and other exposure controls illustrated in Sample OpModes.

Gain Control

org.firstinspires.ftc.robotcore.external.hardware.camera.controls

Gain is a digital camera setting that controls the amplification of the signal from the webcam sensor. This amplifies the whole signal, including any associated background noise.

Gain can be managed in coordination with exposure. Raising exposure and keeping gain low, can provide a bright image and low noise. On the other hand, longer exposure can cause motion blur, which may affect target tracking performance. In some cases, reducing exposure duration and increasing gain may provide a sharper image, although with more noise.

The interface GainControl uses a single value to control gain. It’s used for amplification, and thus has no units – it’s just a number of type integer. Its methods are:

  • setGain(int gain)

  • getGain()

As with exposure, the webcam may support minimum and maximum allowed values of gain. These can be retrieved with:

  • getMinGain()

  • getMaxGain()

There are no set() methods for min and max gain; these are hard-coded in the webcam’s firmware. Note that firmware settings may vary among different versions of the same webcam model.

These and other gain methods are called on a GainControl object, as described above for exposure.

Example 1: Exposure’s effect on TFOD

We interrupt this tutorial to demonstrate the two webcam interfaces described so far: ExposureControl and GainControl.

These 2 examples assume you are already using TensorFlow Object Detection (TFOD) in the Freight Frenzy game. Namely you have a TFOD model and OpMode that are working reasonably well. The model may have been supplied with the SDK, or created with the Machine Learning toolchain [forum] [manual]

Here we will discuss only the Duck game element. Can the exposure and/or gain controls improve the chance of a fast, accurate TFOD detection?

Another way to frame this effort is: can these controls simulate the lighting conditions used for TFOD model training? Namely, if the competition field has different lighting that affects recognition, can you achieve close to your original (trained) TFOD performance?

We first try exposure alone. Setting gain to zero, we apply TFOD to webcam images at various exposure values.

../../../_images/200-Gain0Exp00-to-20.png

Gain 0, Exp 0 -> 20

../../../_images/210-Gain0Exp23-to-40.png

Gain 0, Exp 23 - > 40

../../../_images/220-Gain0Exp45-to-55.png

Gain 0, Exp 45 -> 55

Five fresh readings were taken at each exposure setting. Namely the test OpMode was opened (INIT) each time for a new TFOD initialization and webcam image processing.

This chart shows TFOD confidence levels; ‘instant’ is defined here as recognition within 1 second.

../../../_images/250-chart-gain=0.png

Five readings at each exposure level

Higher exposure does improve recognition, then performance suddenly drops. Then at higher levels, this TFOD model begins to “see” a Cube, not a Duck. Not good!

So, there does seem to be a range of exposure values that gives better results. Note the sharp drop-off at both ends of the range: below 25 and above 40. In engineering, a robust solution can withstand variation. Using a value in the middle of the improved range, can reduce the effects of unforeseen variation. But this range varies with ambient lighting conditions, which may be quite different at the tournament venue.

This data is the result of a very particular combination of: webcam model (Logitech C270), distance (12 inches), lookdown angle (30 degrees), TFOD model (SDK 7.0 default), ambient lighting, background, etc. Your results will vary, perhaps significantly.

Example 2: Gain’s effect on TFOD

Now we adjust only gain. We set Exposure to a fixed value of 15, selected because it was a poor performer in Example 1. Can gain help?

../../../_images/300-Exp15Gain000-to-035.png

Exp 15, Gain 000 -> 035

../../../_images/310-Exp15Gain040-to-060.png

Exp 15, Gain 040 -> 060

../../../_images/330-Exp15Gain070-to-100.png

Exp 15, Gain 070 -> 100

Five fresh readings were taken at each gain setting.

../../../_images/350-chart-exposure=15.png

Five readings at each gain level

Higher gain does improve recognition, then performance declines. Then at higher levels, this TFOD model begins to “see” a Cube, not a Duck. The gain effect was similar to the exposure effect.

These two charts suggest that TFOD results are affected by, and can perhaps be optimized by, setting specific values for exposure and gain. A team should compare this with the default or automatic performance of their robot and webcam, in the full range of expected match conditions.

Example 3: An odd preview

../../../_images/400-Duck-in-Dark.png

Did TFOD make this recognition?

How can this be? Answer: this image was not an ‘instant’ result. Exposure was reduced very low, after TFOD had recognized the Duck.

The implementations of TensorFlow Lite (and Vuforia) are good at tracking a currently-identified object (or image) through translation, rotation, partial blockage, and even extreme changes in exposure.

White Balance Control

org.firstinspires.ftc.robotcore.external.hardware.camera.controls.WhiteBalanceControl

Continuing with other interfaces, the SDK (new for version 7.1) provides methods for white balance control.

White balance is a digital camera setting that balances the color temperature in the image. Color temperature is measured in units of degrees Kelvin (K) and is a physical property of light.

For example, sunlight at noon measures between 5200-6000 K. An incandescent light bulb (warm/orange) has a color temperature of around 3000 K, while shade (cool/blue) measures around 8000 K.

When performed automatically, white balance adds the opposite color to the image in an attempt to bring the color temperature back to neutral. This interface WhiteBalanceControl allows the color temperature to be directly programmed by a user.

A single value is used here to control white balance temperature, in units of degrees Kelvin, of Java type integer. Here are the methods:

  • setWhiteBalanceTemperature(int temperature)

  • getWhiteBalanceTemperature()

As with exposure and gain, the webcam may support minimum and maximum allowed values of white balance temperature. These can be retrieved with:

  • getMinWhiteBalanceTemperature()

  • getMaxWhiteBalanceTemperature()

There are no set() methods for min and max temperature values; these are hard-coded in the webcam’s firmware. Note that firmware settings may vary among different versions of the same webcam model.

The Logitech C920 webcam has a min value of 2000 and a max value of 6500.

White Balance Control Mode

org.firstinspires.ftc.robotcore.external.hardware.camera.controls.WhiteBalanceControl.Mode

This interface supports 3 values of WhiteBalanceControl.Mode:

  • AUTO

  • MANUAL

  • UNKNOWN

To directly control the color balance temperature, set the webcam to Manual mode. Mode is managed with these WhiteBalanceControl methods:

  • setMode(WhiteBalanceControl.Mode.MODE)

  • getMode()

The Logitech C920 defaults to Auto mode for white balance control, and even reverts to Auto in a fresh session, after being set to Manual in a previous session. For other CameraControl settings, some webcams revert to a default value and some preserve their last commanded value.

Focus Control

org.firstinspires.ftc.robotcore.external.hardware.camera.controls.FocusControl

At a distance called “focus length”, a subject’s image (light rays) converge from the lens to form a clear image on the webcam sensor.

If supported by the webcam, focus can be managed with these FocusControl methods:

  • setFocusLength(double focusLength)

  • getFocusLength()

Distance units are not specified here; they may be undimensioned values within an allowed range. For example, the Logitech C920 allows values from 0 to 250, with higher values focusing on closer objects.

The webcam may support minimum and maximum allowed values of focus length. These can be retrieved with:

  • getMinFocusLength()

  • getMaxFocusLength()

There are no set() methods for min and max focus length; these are hard-coded in the webcam’s firmware. Note that firmware settings may vary among different versions of the same webcam model.

These and other focus methods are called on a FocusControl object, as described above for exposure.

Focus Control Mode

org.firstinspires.ftc.robotcore.external.hardware.camera.controls.FocusControl.Mode

A webcam may operate in one of various focus modes. To directly control the focus length, set the webcam to Fixed mode.

The SDK supports these values of FocusControl.Mode:

  • Auto

  • ContinuousAuto

  • Fixed

  • Infinity

  • Macro

  • Unknown

Mode is managed with these FocusControl methods:

  • setMode(ExposureControl.Mode._mode_)

  • getMode()

The Logitech C920 webcam offers two modes: ContinuousAuto and Fixed, which does respond to FocusControl methods. The Logitech C270 (older model) offers only Fixed mode, but does not allow programmed control.

Full details are described in the FocusControl Javadoc.

Pan-Tilt-Zoom Control

org.firstinspires.ftc.robotcore.external.hardware.camera.controls.PtzControl

The SDK provides methods for virtual pan (horizontal motion), tilt (vertical motion), and zoom (enlargement and reduction of image size). This is virtual PTZ since the actions are digitally simulated, within the full original image captured by the webcam. Pan and tilt are possible only to the extent that zoom has provided extra image space to move in that direction.

Pan and Tilt

A webcam does not typically express pan and tilt values in pixels, the smallest unit of image capture by the webcam sensor. For example, the Logitech C920 and the Microsoft LifeCam VX-5000 have a range of +/-36,000 units, far greater than the pixel count in each axis.

The webcam accepts pan and tilt as a pair of (x, y) values. Thus the SDK pan and tilt methods handle these values only as a pair, in a special class named PanTiltHolder. This class has two fields, named pan and tilt, of type integer.

Here’s an example to illustrate using the basic methods:

myHolder.pan = 5;                  // assign the pan field
myHolder.tilt = 10;                // assign the tilt field
myPtzControl.setPanTilt(myHolder);         // command the webcam with (x, y) pair

To retrieve values from the webcam:

newHolder = myPtzControl.getPanTilt();      // retrieve (x, y) pair from webcam
int currentPanValue = newHolder.pan;        // access the pan value
int currentTiltValue = newHolder.tilt;      // access the tilt value

The above examples assume these objects already exist:

PtzControl myPtzControl = vuforia.getCamera().getControl(PtzControl.class); // create PTZ webcam control object
PtzControl.PanTiltHolder myHolder = new PtzControl.PanTiltHolder();         // instantiate input holder object
PtzControl.PanTiltHolder newHolder;                                 // declare output holder object

The webcam may support minimum and maximum allowed pan/tilt paired values. Subject to the control object guidelines shown above, these can be retrieved as follows:

  • minPanTiltHolder = getMinPanTilt();

  • maxPanTiltHolder = getMaxPanTilt();

There are no set() methods for min and max pan/tilt values; these are hard-coded in the webcam’s firmware. Note that firmware settings may vary among different versions of the same webcam model.

These pan and tilt methods are called on a PtzControl object, as described above for exposure.

Zoom

Virtual zoom is described with a single dimensionless value of type integer. Similar to the interfaces described above, virtual zoom can be managed with these methods:

  • setZoom(int zoom)

  • getZoom()

  • getMinZoom()

  • getMaxZoom()

The Logitech C920 allows zoom values ranging from 100 to 500, although values higher than 250-280 have no further effect on the preview image (influenced by Vuforia).

These zoom methods are called on a PtzControl object, as described above for exposure.

AE Priority

Auto-Exposure Priority is a setting within the ExposureControl interface. It’s listed here at the end, not likely to be needed in since it it operates in very low lighting.

What does it do? Imagine that the webcam is operating at its default frame rate, for example 30 frames per second (fps). Note that frame rate is not covered in this basic tutorial.

If the webcam’s built-in auto-exposure detects that the image is very dark, AE Priority allows the frame rate to decrease. This slowdown, or ‘undershoot’, allows more light per frame, which can ‘brighten’ the image.

Its methods are:

  • setAePriority(boolean priority)

  • getAePriority()

These AE Priority methods are called on an ExposureControl object, as described above.

../../../_images/500-AE-Priority.png

Two examples of AE Priority

Here are two pairs of previews, each with AE Priority off and on. In both pairs, the ambient light level is very low. These results are from a Logitech C270 webcam.

The Exposure=0 recognition here was made before reducing exposure and gain. When testing ‘instant’ results, AE Priority could improve the chance of recognition.

Again, this effect is triggered only in very low lighting, not expected in competition. If the building loses all power, Duck recognition becomes… less essential.

Evaluating Your Webcam

The firmware of a specific webcam may or may not support certain features described here. The SDK provides some methods to query the webcam and/or return values that indicate whether a valid response was available.

Exposure Support

Here are two methods to query exposure and a specific exposure mode:

  • isExposureSupported()

  • isModeSupported(ExposureControl.Mode._mode_)

    • for mode, enter the specific mode name you are testing

For the following methods, a field called unknownExposure of type long is returned if exposure unavailable:

  • getExposure(TimeUnit.MILLISECONDS)

  • getMinExposure(TimeUnit.MILLISECONDS)

  • getMaxExposure(TimeUnit.MILLISECONDS)

The methods that set the exposure and mode can also return a Boolean, presumably indicating whether the operation was successful or not. As optional examples:

  • wasExposureSet =  setExposure(25);

  • wasExposureModeSet = setMode(ExposureControl.Mode.Manual)

Likewise the AE Priority feature can return a Boolean. For example:

  • wasAEPrioritySet =  setAePriority(true);

Gain Support

The method that sets the gain can also return a Boolean indicating whether the operation was successful or not. As an optional example:

  • wasGainSet =  setGain(25);

White Balance Support

The methods that set temperature and mode can also return a Boolean, indicating whether the operation was successful or not. As optional examples:

  • wasTemperatureSet = setWhiteBalanceTemperature(3000);

  • wasWhiteBalanceModeSet = setMode(WhiteBalanceControl.Mode.MANUAL);

Focus Support

Here are two methods to query focus and and a specific focus mode:

  • isFocusLengthSupported()

  • isModeSupported(FocusControl.Mode._mode_)

The following methods return a negative value if the requested focus value is unavailable. For example, -1 is returned by the Logitech C270 and the Microsoft LifeCam VX-5000. The Javadoc also mentions a field unknownFocusLength of type double.

  • getFocusLength()

  • getMinFocusLength()

  • getMaxFocusLength()

The methods that set the focus length and mode can also return a Boolean, presumably indicating whether the operation was successful or not. As optional examples:

  • wasFocusSet =  setFocusLength(25);

  • wasFocusModeSet = setMode(FocusControl.Mode.Fixed)

PTZ Support

The methods that set the pan/tilt pair and zoom value can also return a Boolean, presumably indicating whether the operation was successful or not. As optional examples:

  • wasPanTiltSet =  setPanTilt(myHolder);

  • wasZoomSet = setZoom(3)

For PTZ get() methods, some webcams simply return zero for unsupported values.

Some Caveats

  • the SDK supports webcams conforming to the UVC standard

    • many non-UVC webcams work well in competition, despite lacking UVC certification

    • some non-UVC webcams can be listed in Configure Robot, but crash the RC app at runtime

  • webcams may retain an assigned Exposure Mode or Focus Mode, even if unplugged

    • always verify the current mode

  • for a given exposure value, one mode’s preview may look very different than another mode’s preview

  • some webcams accept / set() and confirm / get() a non-supported mode

  • Logitech C270 preview becomes lighter up to exposure 655, then rolls over to dark at 656

    • this webcam’s Min is 0, Max is 1000.

  • Logitech V-UAX16 preview looks normal at exposure = 0, becomes darker up to 30-40

  • Logitech C920 gain value (0-255) greatly influences preview quality, comparable to exposure (0-204)

  • restarting the RC app is sometimes needed after a webcam OpMode crashes

  • firmware versions may vary among webcams of the same model number

Lastly, some features here may be implemented or enhanced with the help of an external library such as OpenCV or EasyOpenCV. That potential is not covered in this basic tutorial. A separate tutorial covers the general use of External Libraries in Blocks and OnBot Java.

Sample OpModes

The intent of this tutorial is to describe the available webcam controls, allowing programmers to develop their own solutions guided by the SDK API (Javadoc).

The following sample OpModes are linked here for reference only. These rudimentary OpModes may not apply to your webcam and may not meet your needs in general.

Adjust exposure, gain and AE Priority

W_WebcamControls_Exp_Gain.java

/* 

This example OpMode allows direct gamepad control of webcam exposure and 
gain.  It's a companion to the FTC wiki tutorial on Webcam Controls.

Add your own Vuforia key, where shown below.

Questions, comments and corrections to [email protected]

from v06 11/10/21
*/

package org.firstinspires.ftc.teamcode;

import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.ExposureControl;
import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.GainControl;
import java.util.concurrent.TimeUnit;

import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;

import org.firstinspires.ftc.robotcore.external.ClassFactory;
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
import org.firstinspires.ftc.robotcore.external.navigation.VuforiaLocalizer;

@TeleOp(name="Webcam Controls - Exp & Gain v06", group ="Webcam Controls")

public class W_WebcamControls_Exp_Gain_v06 extends LinearOpMode {

    private static final String VUFORIA_KEY =
            "  INSERT YOUR VUFORIA KEY HERE  ";

    // Declare class members
    private VuforiaLocalizer vuforia    = null;
    private WebcamName webcamName       = null;

    ExposureControl myExposureControl;  // declare exposure control object
    long minExp;
    long maxExp;
    long curExp;            // exposure is duration, in time units specified

    GainControl myGainControl;      // declare gain control object
    int minGain;
    int maxGain;
    int curGain;
    boolean wasSetGainSuccessful;   // returned from setGain()

    @Override public void runOpMode() {
        
        telemetry.setMsTransmissionInterval(50);
        
        // Connect to the webcam, using exact name per robot Configuration.
        webcamName = hardwareMap.get(WebcamName.class, "Webcam 1");

        /*
         * Configure Vuforia by creating a Parameter object, and passing it to the Vuforia engine.
         * We pass Vuforia the handle to a camera preview resource (on the RC screen).
         */
        
        int cameraMonitorViewId = hardwareMap.appContext.getResources().getIdentifier("cameraMonitorViewId", "id", hardwareMap.appContext.getPackageName());
        VuforiaLocalizer.Parameters parameters = new VuforiaLocalizer.Parameters(cameraMonitorViewId);
        // VuforiaLocalizer.Parameters parameters = new VuforiaLocalizer.Parameters();

        parameters.vuforiaLicenseKey = VUFORIA_KEY;

        // We also indicate which camera we wish to use.
        parameters.cameraName = webcamName;

        // Assign the Vuforia engine object.
        vuforia = ClassFactory.getInstance().createVuforia(parameters);

        // Assign the exposure and gain control objects, to use their methods.
        myExposureControl = vuforia.getCamera().getControl(ExposureControl.class);
        myGainControl = vuforia.getCamera().getControl(GainControl.class);

        // Display exposure features and settings of this webcam.
        checkExposureFeatures();
        
        // Retrieve from webcam its current exposure and gain values.
        curExp = myExposureControl.getExposure(TimeUnit.MILLISECONDS);
        curGain = myGainControl.getGain();

        // Display mode and starting values to user.
        telemetry.addLine("\nTouch Start arrow to control webcam Exposure and Gain");
        telemetry.addData("\nCurrent exposure mode", myExposureControl.getMode());
        telemetry.addData("Current exposure value", curExp);
        telemetry.addData("Current gain value", curGain);
        telemetry.update();


        waitForStart();

        // Get webcam exposure limits.
            minExp = myExposureControl.getMinExposure(TimeUnit.MILLISECONDS);
            maxExp = myExposureControl.getMaxExposure(TimeUnit.MILLISECONDS);

        // Get webcam gain limits.
            minGain = myGainControl.getMinGain();
            maxGain = myGainControl.getMaxGain();

        // Change mode to Manual, in order to control directly.
        // A non-default setting may persist in the camera, until changed again.
        myExposureControl.setMode(ExposureControl.Mode.Manual);

        // Set initial exposure and gain, same as current.
        myExposureControl.setExposure(curExp, TimeUnit.MILLISECONDS);
        myGainControl.setGain(curGain);

        // This loop allows manual adjustment of exposure and gain,
        // while observing the effect on the preview image.
        while (opModeIsActive()) {

            // Manually adjust the webcam exposure and gain variables.
            float changeExp = -gamepad1.left_stick_y;
            float changeGain = -gamepad1.right_stick_y;

            int changeExpInt = (int) (changeExp*5);
            int changeGainInt = (int) (changeGain*5);

            curExp += changeExpInt;
            curGain += changeGainInt;

            // Ensure inputs are within webcam limits, if provided.
            curExp = Math.max(curExp, minExp);
            curExp = Math.min(curExp, maxExp);
            curGain = Math.max(curGain, minGain);
            curGain = Math.min(curGain, maxGain);

            // Update the webcam's settings.
            myExposureControl.setExposure(curExp, TimeUnit.MILLISECONDS);
            wasSetGainSuccessful = myGainControl.setGain(curGain);

            // Manually set Auto-Exposure Priority.
            if (gamepad1.a) {                           // turn on with green A
                myExposureControl.setAePriority(true);
            } else if (gamepad1.b) {                    // turn off with red B
                myExposureControl.setAePriority(false); 
            }

            telemetry.addLine("\nExposure: left stick Y; Gain: right stick Y");
            telemetry.addData("Exposure", "Min:%d, Max:%d, Current:%d", minExp, maxExp, curExp);
            telemetry.addData("Gain", "Min:%d, Max:%d, Current:%d", minGain, maxGain, curGain);
            telemetry.addData("Gain change successful?", wasSetGainSuccessful);
            telemetry.addData("Current exposure mode", myExposureControl.getMode());
            
            telemetry.addLine("\nAutoExposure Priority: green A ON; red B OFF");
            telemetry.addData("AutoExposure Priority?", myExposureControl.getAePriority());
            telemetry.update();

            sleep(100);

        }   // end main while() loop

    }    // end OpMode


    // Display the exposure features and modes supported by this webcam.
    private void checkExposureFeatures() {
        
        while (!gamepad1.y && !isStopRequested()) {
            telemetry.addLine("**Exposure settings of this webcam:");
            telemetry.addData("Exposure control supported?", myExposureControl.isExposureSupported());
            telemetry.addData("Autoexposure priority?", myExposureControl.getAePriority());

            telemetry.addLine("\n**Exposure Modes supported by this webcam:");
            telemetry.addData("AperturePriority", myExposureControl.isModeSupported(ExposureControl.Mode.AperturePriority));
            telemetry.addData("Auto", myExposureControl.isModeSupported(ExposureControl.Mode.Auto));
            telemetry.addData("ContinuousAuto", myExposureControl.isModeSupported(ExposureControl.Mode.ContinuousAuto));
            telemetry.addData("Manual", myExposureControl.isModeSupported(ExposureControl.Mode.Manual));
            telemetry.addData("ShutterPriority", myExposureControl.isModeSupported(ExposureControl.Mode.ShutterPriority));
            telemetry.addData("Unknown", myExposureControl.isModeSupported(ExposureControl.Mode.Unknown));
            telemetry.addLine("*** PRESS Y TO CONTINUE ***");
            telemetry.update();
        }
        
    }   // end method checkExposureFeatures()


}   // end OpMode class
Adjust exposure and gain with TFOD (test OpMode for Examples 1, 2, 3)

W_TFOD_WebcamExpGain.java

/*
 * This example OpMode shows how existing webcam controls can affect 
 * TensorFlow Object Detection (TFOD) of FTC Freight Frenzy game elements.
 * It's a companion to the FTC wiki tutorial on Webcam Controls.
 * 
 * Put the Driver Station in Landscape Mode for this telemetry.
 *
 * The FTC SDK 7.0 includes up to 7 ways of controlling the preview image,
 * depending on webcam capability.  This OpMode uses 2 of those controls, 
 * Exposure and Gain, available on most webcams and offering good
 * potential for affecting TFOD recognition.
 * 
 * This OpMode simply adds ExposureControl and GainControl methods to the FTC
 * sample called "ConceptTensorFlowObjectDetectionWebcam.java".  Here, you can
 * use a gamepad to directly change the preview image and observe TFOD results.
 * 
 * Teams can use this to seek better recognition results from their existing
 * TFOD model -- whether the basic version in the 7.0 release, or their own
 * custom model created with the FTC Machine Learning toolchain.
 * 
 * Exposure, gain and other CameraControl values could be pre-programmed in
 * team autonomous OpModes.  It's also possible to manually enter such values
 * before a match begins, based on anticipated lighting, starting position and 
 * other game-time factors.
 * 
 * Add your own Vuforia key, where shown below.
 *
 * Questions, comments and corrections to [email protected]
 *
 * from v04 11/11/21 
 */
 
package org.firstinspires.ftc.teamcode;

import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.ExposureControl;
import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.GainControl;
import java.util.concurrent.TimeUnit;

import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.firstinspires.ftc.robotcore.external.navigation.VuforiaLocalizer;
import org.firstinspires.ftc.robotcore.external.tfod.TFObjectDetector;
import org.firstinspires.ftc.robotcore.external.tfod.Recognition;
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
import org.firstinspires.ftc.robotcore.external.ClassFactory;
import java.util.List;

@TeleOp(name = "W TFOD Webcam Exposure & Gain v04", group = "Webcam Controls")

public class W_TFOD_WebcamExpGain_v04 extends LinearOpMode {
  /* Note: This sample uses the all-objects Tensor Flow model (FreightFrenzy_BCDM.tflite), which contains
   * the following 4 detectable objects
   *  0: Ball,
   *  1: Cube,
   *  2: Duck,
   *  3: Marker (duck location tape marker)
   *
   *  Two additional model assets are available which only contain a subset of the objects:
   *  FreightFrenzy_BC.tflite  0: Ball,  1: Cube
   *  FreightFrenzy_DM.tflite  0: Duck,  1: Marker
   */
    private static final String TFOD_MODEL_ASSET = "FreightFrenzy_BCDM.tflite";
    private static final String[] LABELS = {
      "Ball",
      "Cube",
      "Duck",
      "Marker"
    };

    /*
     * IMPORTANT: You need to obtain your own license key to use Vuforia. The string below with which
     * 'parameters.vuforiaLicenseKey' is initialized is for illustration only, and will not function.
     * A Vuforia 'Development' license key, can be obtained free of charge from the Vuforia developer
     * web site at https://developer.vuforia.com/license-manager.
     *
     * Vuforia license keys are always 380 characters long, and look as if they contain mostly
     * random data. As an example, here is a example of a fragment of a valid key:
     *      ... yIgIzTqZ4mWjk9wd3cZO9T1axEqzuhxoGlfOOI2dRzKS4T0hQ8kT ...
     * Once you've obtained a license key, copy the string from the Vuforia web site
     * and paste it in to your code on the next line, between the double quotes.
     */
    private static final String VUFORIA_KEY =
            //"   INSERT YOUR VUFORIA KEY HERE  ";
            
    /**
     * {@link #vuforia} is the variable we will use to store our instance of the Vuforia
     * localization engine.
     */
    private VuforiaLocalizer vuforia;

    /**
     * {@link #tfod} is the variable we will use to store our instance of the TensorFlow Object
     * Detection engine.
     */
    private TFObjectDetector tfod;

    // *** ADD WEBCAM CONTROLS -- SECTION START ***
    ExposureControl myExposureControl;  // declare exposure control object
    long minExp;
    long maxExp;
    long curExp;            // exposure is duration, in time units specified

    GainControl myGainControl;      // declare gain control object
    int minGain;
    int maxGain;
    int curGain;
    boolean wasSetGainSuccessful;   // returned from setGain()
    
    boolean isAEPriorityOn = false;
    // *** ADD WEBCAM CONTROLS -- SECTION END ***

    @Override
    public void runOpMode() {
        // The TFObjectDetector uses the camera frames from the VuforiaLocalizer, so we create that
        // first.
        initVuforia();
        initTfod();

        /**
         * Activate TensorFlow Object Detection before we wait for the start command.
         * Do it here so that the Camera Stream window will have the TensorFlow annotations visible.
         **/
        if (tfod != null) {
            tfod.activate();

            // The TensorFlow software will scale the input images from the camera to a lower resolution.
            // This can result in lower detection accuracy at longer distances (> 55cm or 22").
            // If your target is at distance greater than 50 cm (20") you can adjust the magnification value
            // to artificially zoom in to the center of image.  For best results, the "aspectRatio" argument
            // should be set to the value of the images used to create the TensorFlow Object Detection model
            // (typically 16/9).
            tfod.setZoom(1.0, 16.0/9.0);    // modified for testing Exposure & Gain
            // tfod.setZoom(2.5, 16.0/9.0); // original settings in Concept OpMode
        }

        // *** ADD WEBCAM CONTROLS -- SECTION START ***

        // Assign the exposure and gain control objects, to use their methods.
        myExposureControl = vuforia.getCamera().getControl(ExposureControl.class);
        myGainControl = vuforia.getCamera().getControl(GainControl.class);

        // get webcam exposure limits
        minExp = myExposureControl.getMinExposure(TimeUnit.MILLISECONDS);
        maxExp = myExposureControl.getMaxExposure(TimeUnit.MILLISECONDS);

        // get webcam gain limits
        minGain = myGainControl.getMinGain();
        maxGain = myGainControl.getMaxGain();

        // Change mode to Manual, in order to control directly.
        // A non-default setting may persist in the camera, until changed again.
        myExposureControl.setMode(ExposureControl.Mode.Manual);

        // Retrieve from webcam its current exposure and gain values
        curExp = myExposureControl.getExposure(TimeUnit.MILLISECONDS);
        curGain = myGainControl.getGain();

        // display exposure mode and starting values to user
        telemetry.addLine("\nTouch Start arrow to control webcam Exposure and Gain");
        telemetry.addData("\nCurrent exposure mode", myExposureControl.getMode());
        telemetry.addData("Current exposure value", curExp);
        telemetry.addData("Current gain value", curGain);
        telemetry.update();
        // *** ADD WEBCAM CONTROLS -- SECTION END ***


        waitForStart();

        if (opModeIsActive()) {
            while (opModeIsActive()) {
                  
                // *** ADD WEBCAM CONTROLS -- SECTION START ***
                // Driver Station in Landscape Mode for this telemetry.
                telemetry.addLine("Exposure: left stick Y; Gain: right stick Y");
                telemetry.addData("Exposure", "Min:%d, Max:%d, Current:%d", minExp, maxExp, curExp);
                telemetry.addData("Gain", "Min:%d, Max:%d, Current:%d", minGain, maxGain, curGain);
                telemetry.addLine("\nAutoExposure Priority: green A ON; red B OFF");
                telemetry.addData("AE Priority on?", isAEPriorityOn);
                // *** ADD WEBCAM CONTROLS -- SECTION END ***
    
                if (tfod != null) {
                    // getUpdatedRecognitions() will return null if no new information is available since
                    // the last time that call was made.
                    List<Recognition> updatedRecognitions = tfod.getUpdatedRecognitions();
                    if (updatedRecognitions != null) {
                      telemetry.addData("\n# Object Detected", updatedRecognitions.size());
                      // step through the list of recognitions and display boundary info.
                      int i = 0;
                      for (Recognition recognition : updatedRecognitions) {
                        telemetry.addData(String.format("label (%d)", i), recognition.getLabel());
                        telemetry.addData(String.format("  left,top (%d)", i), "%.03f , %.03f",
                                recognition.getLeft(), recognition.getTop());
                        telemetry.addData(String.format("  right,bottom (%d)", i), "%.03f , %.03f",
                                recognition.getRight(), recognition.getBottom());
                        i++;
                      }  // end for() loop
                      
                    }   // end if (updatedRecognitions)
                
                }   // end if (tfod)
                
                telemetry.update();
                
                // *** ADD WEBCAM CONTROLS -- SECTION START ***
                
                // manually adjust the webcam exposure & gain variables
                float changeExp = -gamepad1.left_stick_y;
                float changeGain = -gamepad1.right_stick_y;

                int changeExpInt = (int) (changeExp*2);     // was *5
                int changeGainInt = (int) (changeGain*2);   // was *5

                curExp += changeExpInt;
                curGain += changeGainInt;

                if (gamepad1.a) {           // AE Priority ON with green A
                    myExposureControl.setAePriority(true);
                    isAEPriorityOn = true;
                } else if (gamepad1.b) {    // AE Priority OFF with red B
                    myExposureControl.setAePriority(false);
                    isAEPriorityOn = false;
                }

                // ensure inputs are within webcam limits, if provided
                curExp = Math.max(curExp, minExp);
                curExp = Math.min(curExp, maxExp);
                curGain = Math.max(curGain, minGain);
                curGain = Math.min(curGain, maxGain);

                // update the webcam's settings
                myExposureControl.setExposure(curExp, TimeUnit.MILLISECONDS);
                wasSetGainSuccessful = myGainControl.setGain(curGain);

                sleep(50);             // slow down the main while() loop

                // *** ADD WEBCAM CONTROLS -- SECTION END ***

            }   // end main while() loop

        } // end if opModeIsActive()

    }  // end runOpMode()


    /**
     * Initialize the Vuforia localization engine.
     */
    private void initVuforia() {
        /*
         * Configure Vuforia by creating a Parameter object, and passing it to the Vuforia engine.
         */
        VuforiaLocalizer.Parameters parameters = new VuforiaLocalizer.Parameters();

        parameters.vuforiaLicenseKey = VUFORIA_KEY;
        parameters.cameraName = hardwareMap.get(WebcamName.class, "Webcam 1");

        //  Instantiate the Vuforia engine
        vuforia = ClassFactory.getInstance().createVuforia(parameters);

        // Loading trackables is not necessary for the TensorFlow Object Detection engine.

    }   // end method initVuforia()

    /**
     * Initialize the TensorFlow Object Detection engine.
     */
    private void initTfod() {
        int tfodMonitorViewId = hardwareMap.appContext.getResources().getIdentifier(
            "tfodMonitorViewId", "id", hardwareMap.appContext.getPackageName());
        TFObjectDetector.Parameters tfodParameters = new TFObjectDetector.Parameters(tfodMonitorViewId);
       tfodParameters.minResultConfidence = 0.8f;
       tfodParameters.isModelTensorFlow2 = true;
       tfodParameters.inputSize = 320;
       tfod = ClassFactory.getInstance().createTFObjectDetector(tfodParameters, vuforia);
       tfod.loadModelFromAsset(TFOD_MODEL_ASSET, LABELS);
    }  // end method initTfod()

}  //end class
Adjust white balance temperature, if supported

W_WebcamControls_WhiteBalance.java

/* 

This example OpMode allows direct gamepad control of white balance temperature,
if supported.  It's a companion to the FTC wiki tutorial on Webcam Controls.

Put the Driver Station Layout in Landscape mode for this telemetry.

Add your own Vuforia key, where shown below.

Questions, comments and corrections to [email protected]

from v01 11/12/21
 */

package org.firstinspires.ftc.teamcode;

import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.WhiteBalanceControl;

import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;

import org.firstinspires.ftc.robotcore.external.ClassFactory;
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
import org.firstinspires.ftc.robotcore.external.navigation.VuforiaLocalizer;

@TeleOp(name="Webcam Controls - White Balance v01", group ="Webcam Controls")

public class W_WebcamControls_WhiteBalance_v01 extends LinearOpMode {

    private static final String VUFORIA_KEY =
            //"   INSERT YOUR VUFORIA KEY HERE  ";
            
    // Class Members
    private VuforiaLocalizer vuforia    = null;
    private WebcamName webcamName       = null;

    WhiteBalanceControl myWBControl;  // declare White Balance Control object
    int minWhiteBalanceTemp;          // temperature in degrees Kelvin (K)
    int maxWhiteBalanceTemp;
    int curWhiteBalanceTemp;

    int tempIncrement = 100;          // for manual gamepad adjustment
    boolean wasTemperatureSet;        // did the set() operation succeed?
    boolean wasWhiteBalanceModeSet;   // did the setMode() operation succeed?
    boolean useTempLimits = true;
    
    @Override public void runOpMode() {
        
        telemetry.setMsTransmissionInterval(50);
        
        // Connect to the webcam, using exact name per robot Configuration.
        webcamName = hardwareMap.get(WebcamName.class, "Webcam 1");

        /*
         * Configure Vuforia by creating a Parameter object, and passing it to the Vuforia engine.
         * We pass Vuforia the handle to a camera preview resource (on the RC screen).
         */
        
        int cameraMonitorViewId = hardwareMap.appContext.getResources().getIdentifier("cameraMonitorViewId", "id", hardwareMap.appContext.getPackageName());
        VuforiaLocalizer.Parameters parameters = new VuforiaLocalizer.Parameters(cameraMonitorViewId);

        parameters.vuforiaLicenseKey = VUFORIA_KEY;

        // We also indicate which camera we wish to use.
        parameters.cameraName = webcamName;

        //  Set up the Vuforia engine
        vuforia = ClassFactory.getInstance().createVuforia(parameters);

        // Assign the white balance control object, to use its methods.
        myWBControl = vuforia.getCamera().getControl(WhiteBalanceControl.class);

        // display current white balance mode
        telemetry.addLine("\nTouch Start arrow to control white balance temperature.");
        telemetry.addLine("\nRecommended: put Driver Station Layout in Landscape.");
        telemetry.addData("\nCurrent white balance mode", myWBControl.getMode());
        telemetry.update();


        waitForStart();

        // set variable to current actual temperature, if supported
        curWhiteBalanceTemp = myWBControl.getWhiteBalanceTemperature();
        
        // get webcam temperature limits, if provided
        minWhiteBalanceTemp = myWBControl.getMinWhiteBalanceTemperature();
        maxWhiteBalanceTemp = myWBControl.getMaxWhiteBalanceTemperature();
        
        // Set white balance mode to Manual, for direct control.
        // A non-default setting may persist in the camera, until changed again.
        wasWhiteBalanceModeSet = myWBControl.setMode(WhiteBalanceControl.Mode.MANUAL);

        while (opModeIsActive()) {

            // manually adjust the color temperature variable
            if (gamepad1.x) {                  // increase with blue X (cooler)
                curWhiteBalanceTemp += tempIncrement;
            }  else if (gamepad1.b) {          // decrease with red B (warmer)
                curWhiteBalanceTemp -= tempIncrement;
            }
    
            // ensure inputs are within webcam limits, if provided
            if (useTempLimits) {
                curWhiteBalanceTemp = Math.max(curWhiteBalanceTemp, minWhiteBalanceTemp);
                curWhiteBalanceTemp = Math.min(curWhiteBalanceTemp, maxWhiteBalanceTemp);
            } 

            // update the color temperature setting
            wasTemperatureSet = myWBControl.setWhiteBalanceTemperature(curWhiteBalanceTemp);
            
            // display live feedback while user observes preview image
            telemetry.addLine("Adjust temperature with blue X (cooler) & red B (warmer)");
            
            telemetry.addData("\nWhite Balance Temperature",
                "Min: %d, Max: %d, Actual: %d",
                minWhiteBalanceTemp, maxWhiteBalanceTemp,
                myWBControl.getWhiteBalanceTemperature());

            telemetry.addData("\nProgrammed temperature", "%d", curWhiteBalanceTemp);
            telemetry.addData("Temperature set OK?", wasTemperatureSet);

            telemetry.addData("\nCurrent white balance mode", myWBControl.getMode());
            telemetry.addData("White balance mode set OK?", wasWhiteBalanceModeSet);
            telemetry.update();

            sleep(100);

        }   // end main while() loop

    }    // end OpMode

}   // end class
Adjust focus, if supported
/* 

This example OpMode allows direct gamepad control of webcam focus,
if supported.  It's a companion to the FTC wiki tutorial on Webcam Controls.

Add your own Vuforia key, where shown below.

Questions, comments and corrections to [email protected]

from v03 11/10/21
 */

package org.firstinspires.ftc.teamcode;

import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.FocusControl;

import com.qualcomm.robotcore.eventloop.opmode.OpMode;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import org.firstinspires.ftc.robotcore.external.Telemetry;

import org.firstinspires.ftc.robotcore.external.ClassFactory;
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
import org.firstinspires.ftc.robotcore.external.navigation.VuforiaLocalizer;

@TeleOp(name="Webcam Controls - Focus v03", group ="Webcam Controls")

public class W_WebcamControls_Focus_v03 extends LinearOpMode {

    private static final String VUFORIA_KEY =
            "   INSERT YOUR VUFORIA KEY HERE  ";

    // Class Members
    private VuforiaLocalizer vuforia    = null;
    private WebcamName webcamName       = null;

    FocusControl myFocusControl;  // declare Focus Control object
    double minFocus;              // focus length
    double maxFocus;
    double curFocus;
    double focusIncrement = 10;   // for manual gamepad adjustment
    boolean isFocusSupported;     // does this webcam support getFocusLength()?
    boolean isMinFocusSupported;  // does this webcam support getMinFocusLength()?
    boolean isMaxFocusSupported;  // does this webcam support getMaxFocusLength()?

    @Override public void runOpMode() {
        
        telemetry.setMsTransmissionInterval(50);
        
        // Connect to the webcam, using exact name per robot Configuration.
        webcamName = hardwareMap.get(WebcamName.class, "Webcam 1");

        /*
         * Configure Vuforia by creating a Parameter object, and passing it to the Vuforia engine.
         * We pass Vuforia the handle to a camera preview resource (on the RC screen).
         */
        
        int cameraMonitorViewId = hardwareMap.appContext.getResources().getIdentifier("cameraMonitorViewId", "id", hardwareMap.appContext.getPackageName());
        VuforiaLocalizer.Parameters parameters = new VuforiaLocalizer.Parameters(cameraMonitorViewId);

        parameters.vuforiaLicenseKey = VUFORIA_KEY;

        // We also indicate which camera we wish to use.
        parameters.cameraName = webcamName;

        //  Set up the Vuforia engine
        vuforia = ClassFactory.getInstance().createVuforia(parameters);

        // Assign the focus control object, to use its methods.
        myFocusControl = vuforia.getCamera().getControl(FocusControl.class);

        // display current Focus Control Mode
        telemetry.addLine("\nTouch Start arrow to control webcam Focus");
        telemetry.addData("\nDefault focus mode", myFocusControl.getMode());
        telemetry.update();


        waitForStart();

        // set variable to current actual focal length of webcam, if supported
        curFocus = myFocusControl.getFocusLength();
        isFocusSupported = (curFocus >= 0.0);           // false if negative
        
        //isFocusSupported = true;  // can activate this line for testing

        // get webcam focal length limits, if provided
        minFocus = myFocusControl.getMinFocusLength();
        isMinFocusSupported = (minFocus >= 0.0);        // false if negative

        maxFocus = myFocusControl.getMaxFocusLength();
        isMaxFocusSupported = (maxFocus >= 0.0);        // false if negative

        // A non-default setting may persist in the camera, until changed again.
        myFocusControl.setMode(FocusControl.Mode.Fixed);

        // set initial focus length, if supported
        myFocusControl.setFocusLength(curFocus);

        checkFocusModes();     // display Focus Modes supported by this webcam

        while (opModeIsActive()) {

            // manually adjust the webcam focus variable
            if (gamepad1.right_bumper) {
                curFocus += focusIncrement;
            }  else if (gamepad1.left_bumper) {
                curFocus -= focusIncrement;
            }
    
            // ensure inputs are within webcam limits, if provided
            if (isMinFocusSupported) {
                curFocus = Math.max(curFocus, minFocus);
            } else {
                telemetry.addLine("minFocus not available on this webcam");
            }
            
            if (isMaxFocusSupported) {
                curFocus = Math.min(curFocus, maxFocus);
            } else {
                telemetry.addLine("maxFocus not available on this webcam");
            }
            
            // update the webcam's focus length setting
            myFocusControl.setFocusLength(curFocus);
            
            // display live feedback while user observes preview image
            if (isFocusSupported) {
                telemetry.addLine("Adjust focus length with Left & Right Bumpers");

                telemetry.addLine("\nWebcam properties (negative means not supported)");
                telemetry.addData("Focus Length", "Min: %.1f, Max: %.1f, Actual: %.1f",
                    minFocus, maxFocus, myFocusControl.getFocusLength());

                telemetry.addData("\nProgrammed Focus Length", "%.1f", curFocus);
            } else {
                telemetry.addLine("\nThis webcam does not support adustable focus length.");
            }
            
            telemetry.update();

            sleep(100);

        }   // end main while() loop

    }    // end OpMode


    // display Focus Modes supported by this webcam
    private void checkFocusModes() {
        
        while (!gamepad1.y && opModeIsActive()) {
            telemetry.addLine("Focus Modes supported by this webcam:");
            telemetry.addData("Auto", myFocusControl.isModeSupported(FocusControl.Mode.Auto));
            telemetry.addData("ContinuousAuto", myFocusControl.isModeSupported(FocusControl.Mode.ContinuousAuto));
            telemetry.addData("Fixed", myFocusControl.isModeSupported(FocusControl.Mode.Fixed));
            telemetry.addData("Infinity", myFocusControl.isModeSupported(FocusControl.Mode.Infinity));
            telemetry.addData("Macro", myFocusControl.isModeSupported(FocusControl.Mode.Macro));
            telemetry.addData("Unknown", myFocusControl.isModeSupported(FocusControl.Mode.Unknown));
            telemetry.addLine("*** PRESS Y TO CONTINUE ***");
            telemetry.update();
        }
        
    }   // end method checkFocusModes()

}   // end class
Adjust virtual pan, tilt and zoom, if supported

W_WebcamControls_PTZ.java

/* 

This example OpMode allows direct gamepad control of webcam virtual pan/tilt/zoom,
if supported.  It's a companion to the FTC wiki tutorial on Webcam Controls.

Add your own Vuforia key, where shown below.

Some tested webcams:
Logitech C920 responds to all pan/tilt/zoom (PTZ) methods
Microsoft LifeCam VX-5000 does support PTZ, with 10 positions each.
Logitech C270 (old firmware) does not support PTZ.

Questions, comments and corrections to [email protected]

from v03 11/11/21
 */

package org.firstinspires.ftc.teamcode;

import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.PtzControl;

import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;

import org.firstinspires.ftc.robotcore.external.ClassFactory;
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
import org.firstinspires.ftc.robotcore.external.navigation.VuforiaLocalizer;

import org.firstinspires.ftc.robotcore.external.Telemetry;
import org.firstinspires.ftc.robotcore.external.Telemetry.DisplayFormat;


@TeleOp(name="Webcam Controls - PTZ v03", group ="Webcam Controls")

public class W_WebcamControls_PTZ_v03 extends LinearOpMode {

    private static final String VUFORIA_KEY =
            // "  INSERT YOUR VUFORIA KEY HERE   ";
            
    // Class Members
    private VuforiaLocalizer vuforia    = null;
    private WebcamName webcamName       = null;

    PtzControl myPtzControl;                // declare PTZ Control object
    
    PtzControl.PanTiltHolder minPanTilt;    // declare Holder for min
    int minPan;
    int minTilt;

    PtzControl.PanTiltHolder maxPanTilt;    // declare Holder for max
    int maxPan;
    int maxTilt;

    // declare Holder for current; must instantiate to set values
    PtzControl.PanTiltHolder curPanTilt = new PtzControl.PanTiltHolder();  
    int curPan;
    int curTilt;

    int minZoom;
    int maxZoom;
    int curZoom;
    
    int panIncrement = 7200;        // for manual gamepad control
    int tiltIncrement = 7200;
    int zoomIncrement = 1;
    // pan/tilt increment 7200 is for Microsoft LifeCam VX-5000
    // can use smaller increment for Logitech C920
    
    boolean useLimits = true;       // use webcam-provided limits


    @Override public void runOpMode() {
        
        telemetry.setMsTransmissionInterval(50);
        
        // Connect to the webcam, using exact name per robot Configuration.
        webcamName = hardwareMap.get(WebcamName.class, "Webcam 1");

        /*
         * Configure Vuforia by creating a Parameter object, and passing it to the Vuforia engine.
         * We pass Vuforia the handle to a camera preview resource (on the RC screen).
         */
        
        int cameraMonitorViewId = hardwareMap.appContext.getResources().getIdentifier("cameraMonitorViewId", "id", hardwareMap.appContext.getPackageName());
        VuforiaLocalizer.Parameters parameters = new VuforiaLocalizer.Parameters(cameraMonitorViewId);

        parameters.vuforiaLicenseKey = VUFORIA_KEY;

        // We also indicate which camera we wish to use.
        parameters.cameraName = webcamName;

        // Assign the Vuforia engine object
        vuforia = ClassFactory.getInstance().createVuforia(parameters);

        // Assign the PTZ control object, to use its methods.
        myPtzControl = vuforia.getCamera().getControl(PtzControl.class);

        // display current PTZ values to user
        telemetry.addLine("\nTouch Start arrow to control webcam Pan, Tilt & Zoom (PTZ)");

        // Get the current properties from the webcam.  May be dummy zeroes.
        curPanTilt = myPtzControl.getPanTilt();
        curPan = curPanTilt.pan;
        curTilt = curPanTilt.tilt;
        curZoom = myPtzControl.getZoom();
        
        telemetry.addData("\nInitial pan value", curPan);
        telemetry.addData("Initial tilt value", curTilt);
        telemetry.addData("Initial zoom value", curZoom);
        telemetry.update();


        waitForStart();

        // Get webcam PTZ limits; may be dummy zeroes.
        minPanTilt = myPtzControl.getMinPanTilt();
        minPan = minPanTilt.pan;
        minTilt = minPanTilt.tilt;
        
        maxPanTilt = myPtzControl.getMaxPanTilt();
        maxPan = maxPanTilt.pan;
        maxTilt = maxPanTilt.tilt;

        minZoom = myPtzControl.getMinZoom();
        maxZoom = myPtzControl.getMaxZoom();

        while (opModeIsActive()) {

            // manually adjust the webcam PTZ variables
            if (gamepad1.dpad_right) {
                curPan += panIncrement;
            }  else if (gamepad1.dpad_left) {
                curPan -= panIncrement;
            }

            if (gamepad1.dpad_up) {
                curTilt += tiltIncrement;
            }  else if (gamepad1.dpad_down) {
                curTilt -= tiltIncrement;
            }  //reverse tilt direction for Microsoft LifeCam VX-5000
            
            if (gamepad1.y) {
                curZoom += zoomIncrement;
            }  else if (gamepad1.a) {
                curZoom -= zoomIncrement;
            }

            // ensure inputs are within webcam limits, if provided
            if (useLimits) {
                curPan = Math.max(curPan, minPan);
                curPan = Math.min(curPan, maxPan);

                curTilt = Math.max(curTilt, minTilt);
                curTilt = Math.min(curTilt, maxTilt);

                curZoom = Math.max(curZoom, minZoom);
                curZoom = Math.min(curZoom, maxZoom);
            }

            
            // update the webcam's settings
            curPanTilt.pan = curPan;
            curPanTilt.tilt = curTilt;
            myPtzControl.setPanTilt(curPanTilt);
            myPtzControl.setZoom(curZoom);
            
            // display live feedback while user observes preview image
            telemetry.addLine("\nPAN: Dpad up/dn; TILT: Dpad L/R; ZOOM: Y/A");

            telemetry.addLine("\nWebcam properties (zero may mean not supported)");

            telemetry.addData("Pan", "Min: %d, Max: %d, Actual: %d",
                minPan, maxPan, myPtzControl.getPanTilt().pan);
            telemetry.addData("Programmed Pan", curPan);

            telemetry.addData("\nTilt", "Min: %d, Max: %d, Actual: %d",
                minTilt, maxTilt, myPtzControl.getPanTilt().tilt);
            
            telemetry.addData("Programmed Tilt", curTilt);
                
            telemetry.addData("\nZoom", "Min: %d, Max: %d, Actual: %d",
                minZoom, maxZoom, myPtzControl.getZoom());      
            telemetry.addData("Programmed Zoom", curZoom);

            telemetry.update();

            sleep(100);

        }   // end main while() loop

    }    // end OpMode

}   // end class

Summary

Some webcam controls in the SDK could potentially improve TFOD recognitions. Exposure, gain and other values could be pre-programmed in team autonomous OpModes. It’s also possible to manually enter such values before a match begins, based on anticipated lighting, starting position and other game-time factors.

You are encouraged to submit other webcam reports and examples that worked for you.


Questions, comments and corrections to westsiderobotics@verizon.net