Delay in source switching and high latency for cameras

This is an follow-up to the thread I posted earlier here. The code I am working on is, as before, on Github at this link.

From the previous thread, I was able to get the MjpegServer working along with the camera switching. The code sends the image from the cameras connected to the RoboRIO to SmartDashboard. With the help of the reply in the previous thread to set the URL in SmartDashboard to the correct setting, the camera does display the images from the cameras. However, I am unable to achieve a relatively low latency nor a particularly good FPS.

I am using 160x120 for the camera sizes, with pixels very clear on the screen, and yet the FPS is unable to go above approximately 20. There is also a clear delay, with about .2 or more seconds of latency (e.g., when a hand is waved in front of the cameras, it takes around that time to register). Additionally, I have tried setting the FPS to 30 along with the camera size setting, and simply setting the FPS and not touching the size settings. None of the attempts have worked.

My code also uses

MjpegServer.setsource();

in order to switch between cameras on button press, and when this is attempted there can be up to several seconds of delay before the image from the other camera appears.

It is most likely not the problem with the cameras (they are HD streaming cameras and work when directly connected to computer), and it is also not the problem with the computer (~20% CPU used, ~50% memory, very low (<5-10%) for the rest) so I was wondering if there was a way to optimize the latency, FPS, and setSource camera switching delay.

The main things that our team wants optimized is the latency and FPS. Help would be appreciated.

Thanks in advance!

  • Bryan Li
    Team 449 Programmer

What camera models are you using and how much lighting do you have / what are your camera settings? With some testing with a HD-3000, FPS is 30 with a brightly lit scene, but can drop off to <10 fps given a dark scene as the camera goes into a low light mode. Setting the exposure controls to fixed rather than auto can fix these sorts of issues (open a web browser to http://roborio-449-frc.local:5800/ to get a simple settings gui to try things out).

The main reason you’re seeing the delay in switching between cameras is because cscore automatically turns off the camera you’re not using, so when you switch it needs to go through the entire connection process all over again. This is intentional to save CPU resources when there’s no one connected to the camera stream, but there’s a relatively easy workaround: create a CvSink, connect it to the camera, and enable it (it’s not necessary to grab frames). This will cause the library to stay connected to the camera (because an enabled sink is always connected). E.g.:


public CvSink sink1;
public CvSink sink2;

...

sink1 = new CvSink("cam1cv");
sink1.setSource(cam1);
sink1.setEnabled(true);

sink2 = new CvSink("cam1cv");
sink2.setSource(cam2);
sink2.setEnabled(true);

Note you can use the CameraServer wrapper classes to get the other benefits of CameraServer (e.g. NetworkTables publishing), with code like the following rather than calling “new UsbCamera” explicitly.


cam1 = CameraServer.getInstance().startAutomaticCapture(0);
cam2 = CameraServer.getInstance().startAutomaticCapture(1);
server = CameraServer.getInstance().getServer();

// dummy CvSinks
sink1 = CameraServer.getInstance().getVideo(cam1);
sink1.setEnabled(true);
sink2 = CameraServer.getInstance().getVideo(cam2);
sink2.setEnabled(true);

I am testing with two different HD cameras; not sure if this could cause a problem. One is a Microsoft HD-3000 camera, the other is a Genius WideCam F100. The tests are performed in a brightly-lit room, so it seems like the main problem is the delay from the cameras having to go to the roboRIO first then going to the computer.

As for CvSink and CameraServer, I will try to use both your suggestions. Thanks!

EDIT: I’d like to ask if and how CameraServer/CvSink can switch between cameras. It seems like the code you had posted displays both cameras at once, although I haven’t tested it yet. Since we will be sending and receiving over a radio/wifi connection, our team wants to minimize the bandwidth usage.

Sorry if my message above wasn’t clear… just add the CvSink lines to your existing code (which uses SetSource to switch cameras). All the CvSink lines do is keep the camera connection open so that SetSource can instantly switch rather than being delayed due to taking a while to reconnect to the disconnected camera. It also makes both streams available simultaneously, but you can use SetSource to switch between them the way you were already doing.

I tested with both a HD3000 and a Logitech C210 with your code plus the CvSink lines and could switch instantly. I was getting 30 fps from the HD3000 in a brightly lit environment; the C210 wasn’t quite as fast but I didn’t spend the time to tweak settings.

In terms of delays/latency, if the client is not requesting a different resolution than the camera is set to (the default case for SmartDashboard or viewing the stream via a web browser), the roboRio is performing minimal processing on the image–basically it just gets the JPEG image from the camera (via the Linux video layer) and forwards it via the HTTP connection; it’s about as fast as you can get for a USB camera. Again, it’s most likely slower FPS is due to the camera trying to compensate for lighting conditions; I highly recommend you try fixed exposure etc settings on the camera.

I have a further question; since the last time I asked I have used the CvSinks. However, recently I have been getting this error:

CS: ERROR: cam1: could not start streaming due to USB bandwidth limitations; try a lower resolution or a different pixel format (VIDIOC_STREAMON: No space left on device) (UsbCameraImpl.cpp:569)

This leads to the video feed simply freezing when we switch, until we switch back.

I don’t know what causes this, because the camera that works (I have switched the cameras around), works on both 160x120 resolution and 1080x720 - meaning it cannot be because of not enough space left on the cameras. I have searched this up, and it is apparently because there is enough bandwidth on the USB or because there isn’t enough space on the CPU/RoboRIO.

Additionally, it is not because of the USB ports. We have tried simply switching port numbers, but it is always the camera assigned to cam1 that does not work.

We get the same error without CvSink, but it works out in the end - most likely because it disables the other camera.

Is there any way we can eliminate this problem? Thanks.

This is the solution that our team found. It is functional for anything between 0-4 cameras and swaps near instantly.


ackage org.usfirst.frc.team4028.robot.sensors;

import java.nio.file.Files;
import java.nio.file.Paths;

import org.opencv.core.Mat;
import org.usfirst.frc.team4028.robot.utilities.CircularQueue;

import edu.wpi.cscore.CvSink;
import edu.wpi.cscore.CvSource;
import edu.wpi.cscore.MjpegServer;
import edu.wpi.cscore.UsbCamera;
import edu.wpi.first.wpilibj.CameraServer;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

//This class implements all functionality for operator/driver cameras
//=====> For Changes see ************* (javadotmakeitwork)
//=========================REVISION BLOCK==================================
//Rev		By			D/T				Description
// 0		Nick		2/27 8:47		Added 4th Camera and Added "Swapped to Next" method for increased organization
// 1		TomB		5.Mar.2017		Added code to handle unplugging & replugging cameras
// 2        Nick        9.Mar.2017      Fixed the Issue of not Knowing Which Camera is Which via sendable chooser   
//-------------------------------------------------------------
public class SwitchableCameraServer
{	
	// working variables
	private String _cameraName;
	private String _previousCameraName;
	private String _gearCameraName;
	private String _shooterCameraName;
	private String _climberCameraName;
	private String _driverCameraName;
	
	private boolean _isCam0Present;
	private boolean _isCam1Present;
	private boolean _isCam2Present;
	private boolean _isCam3Present;
	
	private CircularQueue<String> _camList;

	//============================================================================================
	// constructors follow
	//============================================================================================
	public SwitchableCameraServer(String cameraname)
	{	
		// check what cameras are plugged in
    	_isCam0Present = Files.exists(Paths.get("/dev/video0"));
    	_isCam1Present = Files.exists(Paths.get("/dev/video1"));
    	_isCam2Present = Files.exists(Paths.get("/dev/video2"));
    	_isCam3Present = Files.exists(Paths.get("/dev/viedo3"));
    	

    	// Display which cameras are active at the begining of the match
    	DriverStation.reportWarning("Cam0 is Connected? " + _isCam0Present, false);
    	DriverStation.reportWarning("Cam1 is Connected? " + _isCam1Present, false);
    	DriverStation.reportWarning("Cam2 is Connected? " + _isCam2Present, false);
    	DriverStation.reportWarning("Cam3 is Connected? " + _isCam3Present, false);
		
    	// build list of available cameras
		_camList = new CircularQueue<String>();
		
		if(_isCam0Present)	{ _camList.add("cam0"); }
		if(_isCam1Present)	{ _camList.add("cam1"); }
		if(_isCam2Present)	{ _camList.add("cam2"); }
		if(_isCam3Present)	{ _camList.add("cam3"); }
		
		// chg to the requested camera
		ChgToCamera(cameraname);
		
		// start the camera thread
		Thread cameraThread = new Thread(JavadotMakeItWork);
		cameraThread.start();
	}

	//============================================================================================
	// Methods follow
	//============================================================================================
	public void ChgToCamera(String cameraName) 
	{
		if(_previousCameraName != cameraName)		//check if there is more than 1 camera
		{
			// make sure the requested camera is available
			if(_camList.contains(cameraName))
			{
				_cameraName = cameraName;
			}	
			else
			{
				System.out.println("Camera not available: " + cameraName);
				DriverStation.reportError("Camera not available: " + _cameraName, false);
			}
		}
		else
		{
			System.out.println("Requested Camera is already current: " + cameraName);
		}
	}
	
	public void ChgToNextCamera()
	{		
		if(!_camList.isEmpty())		//check to see if there are cameras connected
		{
			ChgToCamera(_camList.getNext());
		}
		else
		{
			DriverStation.reportError("No Cameras Available", false);
		}
	}
	
	public void OutputToSmartDashboard()
	{
		SmartDashboard.putString("IsCam0Present:", Boolean.toString(_isCam0Present) + " (" + getCameraFunction("cam0") + ")");
		SmartDashboard.putString("IsCam1Present?", Boolean.toString(_isCam1Present) + " (" + getCameraFunction("cam1") + ")");
		SmartDashboard.putString("IsCam2Present?", Boolean.toString(_isCam2Present) + " (" + getCameraFunction("cam2") + ")");
		SmartDashboard.putString("IsCam3Present?", Boolean.toString(_isCam3Present) + " (" + getCameraFunction("cam3") + ")");
		if (_cameraName == null)		//give no camera name if there is nothing connected
		{
			_cameraName = "N/A";
		}

		SmartDashboard.putString("CurrentCameraName:", _cameraName);
	}
	
	private String getCameraFunction(String cameraName)		//display the expected camera name based on sendable choosers
	{
		if(_gearCameraName == cameraName)
		{
			return "Gear";
		}
		else if(_shooterCameraName == cameraName)
		{
			return "Shooter";
		}
		else if(_climberCameraName == cameraName)
		{
			return "Climber";
		}
		else if(_driverCameraName == cameraName)
		{
			return "Driver";
		}
		else
		{
			return "N/A";
		}
	}
	//============================================================================================
	// Property Accessors follow
	//============================================================================================
	public String getCurrentCameraName()
	{
		return _cameraName;
	}
	
	public void setGearCameraName(String cameraname)
	{
		_gearCameraName = cameraname;
	}
	
	public void setClimberCameraName(String cameraname)
	{
		_climberCameraName = cameraname;
	}
	
	public void setShooterCameraName(String cameraname)
	{
		_shooterCameraName = cameraname;
	}
	
	public void setDriverCameraName(String cameraname)
	{
		_driverCameraName = cameraname;
	}
	
	//============================================================================================
	// Task that is run on a separate thread
	//============================================================================================
	private Runnable JavadotMakeItWork = new Runnable()
	{
		@Override
		public void run() 
		{   

			// create instances of the all the cameras
            // create sinks for each camera
	    	UsbCamera cam0 = null;		
	    	UsbCamera cam1 = null;
	    	UsbCamera cam2 = null;
	    	UsbCamera cam3 = null;
	    	
	    	CvSink cvSink0 = null;
	    	CvSink cvSink1 = null;
	    	CvSink cvSink2 = null;
	    	CvSink cvSink3 = null;
	    	
	    	//declare instances of each camera if it exists
	    	if(_isCam0Present)
	    	{
	    		cam0 = new UsbCamera("cam0", 0); 				
	    		cvSink0 = CameraServer.getInstance().getVideo(cam0); 
	    		cvSink0.setEnabled(false);
	    	}
	    	
	    	if(_isCam1Present)
	    	{
	    		cam1 = new UsbCamera("cam1",  1); 	
	    		cvSink1 = CameraServer.getInstance().getVideo(cam1);
	    		cvSink1.setEnabled(false);
	    	}
	    	
		    if(_isCam2Present)
		    {
		    	cam2 = new UsbCamera("cam2", 2); 
		    	cvSink2 = CameraServer.getInstance().getVideo(cam2);
		    	cvSink2.setEnabled(false);
		    }
		    
		    if(_isCam3Present)
		    {
		    	cam3 = new UsbCamera("cam3", 3); 
		    	cvSink3 = CameraServer.getInstance().getVideo(cam3);
		    	cvSink3.setEnabled(false);
		    }
 
            // create an output stream
            CvSource outputStream = CameraServer.getInstance().putVideo("Switcher", 320, 240);
            
            // create a 2d array to hold the captured image
            Mat image = new Mat();
            
            // create a MjpegServer on port 1181
            MjpegServer server = new MjpegServer("server", 1181);
            
            // set the image source for the mjepg server to be the output stream
            server.setSource(outputStream);
                       
            boolean isImageAvailable = false;
            boolean isCameraAvailableLastScan = false;
            
            // =============================================================================
            // start looping
            // =============================================================================
            while(!Thread.interrupted()) 
            {            	
            	isImageAvailable = false;
            	
        		// enable this camera & configure it
        		if(_cameraName == "cam0")
        		{              
        			// make sure camera is still plugged in
        			_isCam0Present = Files.exists(Paths.get("/dev/video0"));
        			
        			if (_isCam0Present)
        			{
	          			try
	        			{        
	          				// if camera was jut swapped or unplugged & plugged back in
		        			if(_previousCameraName != _cameraName || !isCameraAvailableLastScan)
		        			{                	
		        				// disable the other cameras
		                		//	NOTE: Key point is to disable all other cameras BEFORE you enable the one
		                		//			you want to avoid USB bus overload!
		            			if(cvSink1 != null) { cvSink1.setEnabled(false); }
		            			
		            			if(cvSink2 != null) { cvSink2.setEnabled(false); }
		            			
		            			if(cvSink3 != null) { cvSink3.setEnabled(false); }
		            			
		            			//set properties for each camera
				                cvSink0.setEnabled(true);
			                	cam0.setFPS(60);
			               		cam0.setResolution(320, 240);
			               		cam0.setExposureManual(36);
			               		_previousCameraName = _cameraName;
			               		
			               		System.out.println("Camera Swapped to: " + _cameraName);
		        			}
		               		
		        			// grab the current frame from this camera and put it into the 2D array
		            		cvSink0.grabFrameNoTimeout(image);
		            		isImageAvailable = true;
		            		isCameraAvailableLastScan = true;
	        			}
	        			catch(Exception ex) 
	          			{ 
	        				isCameraAvailableLastScan = false;
	        				System.out.println("Camera Unplugged: " + _cameraName);
	        				DriverStation.reportError("Camera Unplugged: " + _cameraName, false);
	        			}
        			}
            	} 
        		// ===== CAM1 =======
        		else if(_cameraName == "cam1")
        		{              
        			// make sure camera is still plugged in
        			_isCam1Present = Files.exists(Paths.get("/dev/video1"));
        			
        			if (_isCam1Present)
        			{
	          			try
	        			{        
	          				// if camera was jut swapped or unplugged & plugged back in
		        			if(_previousCameraName != _cameraName || !isCameraAvailableLastScan)
		        			{                		
		        				// disable the other cameras
		                		//	NOTE: Key point is to disable all other cameras BEFORE you enable the one
		                		//			you want to avoid USB bus overload!
		            			if(cvSink0 != null) { cvSink0.setEnabled(false); }
		            			
		            			if(cvSink2 != null) { cvSink2.setEnabled(false); }
		            			
		            			if(cvSink3 != null) { cvSink3.setEnabled(false); }
		            			
		            			//define properties for camera 1
				                cvSink1.setEnabled(true);
			                	cam1.setFPS(60);
			                	cam1.setResolution(320, 240);			      
			                	cam1.setExposureManual(36);
			               		_previousCameraName = _cameraName;
			               		
			               		System.out.println("Camera Swapped to: " + _cameraName);
		        			}
		               		
		        			// grab the current frame from this camera and put it into the 2D array
		        			cvSink1.grabFrameNoTimeout(image);
		            		isImageAvailable = true;
		            		isCameraAvailableLastScan = true;
	        			}
	        			catch(Exception ex) 
	          			{ 
	        				isCameraAvailableLastScan = false;
	        				System.out.println("Camera Unplugged: " + _cameraName);
	        			}
        			}
            	} 
        		// ===== CAM2 =======
        		else if(_cameraName == "cam2")
        		{              
        			// make sure camera is still plugged in
        			_isCam2Present = Files.exists(Paths.get("/dev/video2"));
        			
        			if (_isCam2Present)
        			{
	          			try
	        			{        
	          				// if camera was jut swapped or unplugged & plugged back in
		        			if(_previousCameraName != _cameraName || !isCameraAvailableLastScan)
		        			{                		
		        				// disable the other cameras
		                		//	NOTE: Key point is to disable all other cameras BEFORE you enable the one
		                		//			you want to avoid USB bus overload!
		            			if(cvSink0 != null) { cvSink0.setEnabled(false); }
		            			
		            			if(cvSink1 != null) { cvSink1.setEnabled(false); }
		            			
		            			if(cvSink3 != null) { cvSink3.setEnabled(false); }
		            			
		            			//define properties for camera 2
				                cvSink2.setEnabled(true);
			                	cam2.setFPS(60);
			                	cam2.setResolution(320, 240);
			                	cam2.setExposureManual(36);
			               		_previousCameraName = _cameraName;
			               		
			               		System.out.println("Camera Swapped to: " + _cameraName);
		        			}
		               		
		        			// grab the current frame from this camera and put it into the 2D array
		        			cvSink2.grabFrameNoTimeout(image);
		            		isImageAvailable = true;
		            		isCameraAvailableLastScan = true;
	        			}
	        			catch(Exception ex) 
	          			{ 
	        				isCameraAvailableLastScan = false;
	        				System.out.println("Camera Unplugged: " + _cameraName);
	        			}
        			}
            	} 
        		// ===== CAM3 =======
        		else if(_cameraName == "cam3")
        		{              
        			// make sure camera is still plugged in
        			_isCam3Present = Files.exists(Paths.get("/dev/video3"));
        			
        			if (_isCam3Present)
        			{
	          			try
	        			{        
	          				// if camera was jut swapped or unplugged & plugged back in
		        			if(_previousCameraName != _cameraName || !isCameraAvailableLastScan)
		        			{                		
		        				// disable the other cameras
		                		//	NOTE: Key point is to disable all other cameras BEFORE you enable the one
		                		//			you want to avoid USB bus overload!
		            			if(cvSink0 != null) { cvSink0.setEnabled(false); }
		            			
		            			if(cvSink1 != null) { cvSink1.setEnabled(false); }
		            			
		            			if(cvSink2 != null) { cvSink2.setEnabled(false); }
		            			
		            			//define properties for camera 3
				                cvSink3.setEnabled(true);
			                	cam3.setFPS(60);
			                	cam3.setResolution(320, 240);
			                	cam3.setExposureManual(36);
			               		_previousCameraName = _cameraName;
			               		
			               		System.out.println("Camera Swapped to: " + _cameraName);
		        			}
		               		
		        			// grab the current frame from this camera and put it into the 2D array
		        			cvSink3.grabFrameNoTimeout(image);
		            		isImageAvailable = true;
		            		isCameraAvailableLastScan = true;
	        			}
	        			catch(Exception ex) 
	          			{ 
	        				isCameraAvailableLastScan = false;
	        				System.out.println("Camera Unplugged: " + _cameraName);
	        			}
        			}
            	} 
        		            	
        		if(isImageAvailable)
        		{
		           	// push the captured frame to the output stream
	           		outputStream.putFrame(image);
        		}
        		
        		// sleep each cycle to avoid Robot Code not updating often enough issues
        		try {
					Thread.sleep(10);
				} catch (InterruptedException e) {
					// TODO Auto-generated catch block
					e.printStackTrace();
				}
            }
	            	
		}
	};
}