OpenFTC/EasyOpenCV

2 Webcams with Control Hub works on 1st run - but fails on subsequent runs without restarting robot controller

SteveAtStealth opened this issue · 17 comments

This issue is similar to issue#12. Using 2 webcams, we are also getting error "Startstreaming() Called, but Camera is Not Opened!" (which, once occurs requires restarting the robot) - see picture of error below:
image
However, in our case the streaming/pipelines from both webcams works fine immediately after restarting the robot controller. But if we stop the op mode and then press "INIT" on the driver's station phone (without restarting the robot), we get this error. We are using 2 Logitech C270 webcams plugged directly into a Control Hub - one into the USB2.0 port and one into the USB3.0 port. We are using 320 X 240 resolution on both webcams. The driver's station is on a MOTO E5.

This is our code:

Code in declarations:
OpenCvCamera Cam1;
OpenCvCamera Cam2;
SideDeterminationPipeline pipeline1;
RingDeterminationPipeline pipeline2;

Code in public void runOpMode();

    int cameraMonitorViewId = hardwareMap.appContext.getResources().getIdentifier("cameraMonitorViewId", "id", hardwareMap.appContext.getPackageName());
    int[] viewportContainerIds = OpenCvCameraFactory.getInstance()
            .splitLayoutForMultipleViewports(
                    cameraMonitorViewId, //The container we're splitting
                    2, //The number of sub-containers to create
                    OpenCvCameraFactory.ViewportSplitMethod.VERTICALLY); //Whether to split the container vertically or horizontally

    Cam1 = OpenCvCameraFactory.getInstance().createWebcam(hardwareMap.get(WebcamName.class, "Webcam 1"), viewportContainerIds[0]);
    Cam2 = OpenCvCameraFactory.getInstance().createWebcam(hardwareMap.get(WebcamName.class, "Webcam 2"), viewportContainerIds[1]);

    pipeline1 = new SideDeterminationPipeline();
    pipeline2= new RingDeterminationPipeline();
    Cam1.setPipeline(pipeline1);
    Cam2.setPipeline(pipeline2);

    Cam1.openCameraDeviceAsync(new OpenCvCamera.AsyncCameraOpenListener()
    {
        @Override
        public void onOpened()
        {
            Cam1.startStreaming(320,240, OpenCvCameraRotation.UPRIGHT);
        }
    });

    Cam2.openCameraDeviceAsync(new OpenCvCamera.AsyncCameraOpenListener()
    {
        @Override
        public void onOpened()
        {
            Cam2.startStreaming(320,240, OpenCvCameraRotation.UPRIGHT);
        }
    });

Note - when using only 1 webcam we are able to stop the op mode and re-INIT/restart without having to restart the robot. So this is only an issue when using 2 webcams. However we need 2 webcams and would really prefer to not have to restart the robot for every run.

Thanks in advance for any assistance!
-Steve

Attached is robotControllerLog.txt, which I obtained by performing the following steps (similar to issue#12):

  1. Used a file manager to delete robotControllerLog.txt from the control hub
  2. Removed power and then reapplied power to the control hub
  3. Reproduced the initial success and then the subsequent error
  4. Removed power and then reapplied power to the control hub
  5. Copied robotControllerLog.txt file to my computer and uploaded it here

robotControllerLog.txt

Note: we are not using Vuforia - only EasyOpenCV

What version of the SDK and EasyOpenCV are you using?

What version of the SDK and EasyOpenCV are you using?

Ok I see from your log that you're on EOCV v1.4.3, which means you must be on SDK v6.1 since EOCV 1.4.3 requires at least SDK v6.1.

Your log has some very interesting messages which I haven't seen before:

01-01 14:03:39.267  1014  1159 D UvcStream: [stream.cpp:654] bad packet: error bit set
01-01 14:03:39.267  1014  1159 D UvcStream: [stream.cpp:654] bad packet: error bit set
01-01 14:03:39.267  1014  1159 D UvcStream: [stream.cpp:654] bad packet: error bit set
01-01 14:03:39.267  1014  1159 D UvcStream: [stream.cpp:654] bad packet: error bit set
01-01 14:03:39.267  1014  1159 D UvcStream: [stream.cpp:654] bad packet: error bit set
01-01 14:03:39.267  1014  1159 D UvcStream: [stream.cpp:654] bad packet: error bit set
01-01 14:03:39.267  1014  1159 D UvcStream: [stream.cpp:654] bad packet: error bit set
01-01 14:03:39.267  1014  1159 D UvcStream: [stream.cpp:654] bad packet: error bit set

I do have access to 2 webcams and a Control Hub, I will see if I can reproduce the issue.

Thank You!!
Yes - I'm using SDK6.1 and easyopencv1.4.3

Unfortunately, I cannot reproduce this on my end with SDK v6.1, EOCV v1.4.3, and Control Hub OS v1.1.2.
I am able to start and stop the OpMode multiple times without any problems. For reference, the webcams I tested with were different models (one was a C920 and one was a UVC microscope). I'm not sure if that makes a difference or not.

Question: does the Switchable Webcam API work for multiple runs for you?

For reference, here is the code I tried to reproduce with:

package org.firstinspires.ftc.teamcode;

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

import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
import org.opencv.core.Mat;
import org.opencv.core.Point;
import org.opencv.core.Scalar;
import org.opencv.imgproc.Imgproc;
import org.openftc.easyopencv.OpenCvCamera;
import org.openftc.easyopencv.OpenCvCameraFactory;
import org.openftc.easyopencv.OpenCvCameraRotation;
import org.openftc.easyopencv.OpenCvPipeline;

@TeleOp
public class MultipleWebcamTest extends LinearOpMode
{
    OpenCvCamera webcam2;
    OpenCvCamera webcam;

    @Override
    public void runOpMode()
    {
        int cameraMonitorViewId = hardwareMap.appContext.getResources().getIdentifier("cameraMonitorViewId", "id", hardwareMap.appContext.getPackageName());
        
        int[] viewportContainerIds = OpenCvCameraFactory.getInstance()
                .splitLayoutForMultipleViewports(
                        cameraMonitorViewId,
                        2,
                        OpenCvCameraFactory.ViewportSplitMethod.VERTICALLY);

        webcam2 = OpenCvCameraFactory.getInstance().createWebcam(
                hardwareMap.get(WebcamName.class, "Webcam 2"), viewportContainerIds[0]);

        webcam = OpenCvCameraFactory.getInstance().createWebcam(
                hardwareMap.get(WebcamName.class, "Webcam 1"), viewportContainerIds[1]);

        webcam2.openCameraDeviceAsync(new OpenCvCamera.AsyncCameraOpenListener()
        {
            @Override
            public void onOpened()
            {
                webcam2.setPipeline(new UselessGreenBoxDrawingPipeline());
                webcam2.startStreaming(320, 240, OpenCvCameraRotation.UPRIGHT);
            }
        });

        webcam.openCameraDeviceAsync(new OpenCvCamera.AsyncCameraOpenListener()
        {
            @Override
            public void onOpened()
            {
                webcam.setPipeline(new UselessGreenBoxDrawingPipeline());
                webcam.startStreaming(320, 240, OpenCvCameraRotation.UPRIGHT);
            }
        });

        waitForStart();

        while (opModeIsActive())
        {
            telemetry.addData("Webcam2 FPS", webcam2.getFps());
            telemetry.addData("Webcam FPS", webcam.getFps());
            telemetry.update();

            sleep(100);
        }
    }

    class UselessGreenBoxDrawingPipeline extends OpenCvPipeline
    {
        @Override
        public Mat processFrame(Mat input)
        {
            Imgproc.rectangle(
                    input,
                    new Point(
                            input.cols()/4,
                            input.rows()/4),
                    new Point(
                            input.cols()*(3f/4f),
                            input.rows()*(3f/4f)),
                    new Scalar(0, 255, 0), 4);

            return input;
        }
    }
}

I tried the code you posted directly above (which you tried to reproduce my error with), and I get the same error as I got with my code. So it seems to be a camera-specific issue. I'm still trying to get the Switchable Webcam API working; getting a "uses or overrides a deprecated API, Recompile with -Xlint:deprecation for details" message. Will keep working at it and will post results.

Got the Switchable Webcam API working. But when I run it for multiple runs I get the same error: "Startstreaming() Called, but Camera is Not Opened!".

Ref switchable camera API: interesting. Hmm. I know you said you're not using Vuforia, but would you be able to try using Vuforia with switchable webcams and see how it works? Reason being, both Vuforia and EasyOpenCV ultimately use the same UVC driver in the SDK. So if works in Vuforia but not in EOCV, then there's probably some parameter I need to adjust. If it doesn't work in either, then there's likely a bug in the SDK's UVC driver.

Here is the official SDK sample for switchable webcams with Vuforia. Well, technically it's for TFOD, but TFOD actually runs on top of Vuforia (pulling frames out of the Vuforia frame queue).

BTW if you're wondering why EOCV doesn't do the same (pulling frames out of the Vuforia frame queue) it's because that is 1) much less efficient than getting the frames directly 2) doesn't allow drawing on the viewport or anything like that (you're stuck with the raw camera feed) and 3) is much less flexible: you get much more low-level control over the camera when using it directly.

Ok, I'll try it - but it may take a few days to get there. Will keep you posted. Thanks, Steve

I'd also be interested in what happens if you make an OpMode where it opens camera A, streams for a few seconds, closes camera A, opens camera B, streams for a few seconds, closes camera B, then repeats.

Ok, I'll try that too. Any chance you could suggest the code to do this (i.e. open/close camera streams in series)?

Update: We tried a Logitech C920 webcam with a Logitech C270 webcam, and we did not have the same issue - it worked fine. Still trying to understand why using (2) C270 webcams causes this issue.

Interesting..... I'm not sure what to make of that.

Were you able to test Vuforia with the two C270s in switchable mode?

Closing this for now.