WPILIB Camera Code Crashing JVM

Hi All,

We’re coding in Java and started experiencing problems with the robot becoming disabled after a random interval. Checking the logs from the dashboard we saw that we were getting a message. Checking the message we found that the JVM was crashing when getting an image using the WPILib native libraries…


# If you would like to submit a bug report, please visit:
#   http://bugreport.sun.com/bugreport/crash.jsp
# The crash happened outside the Java Virtual Machine in native code.
# See problematic frame for where to report the bug.
#
Stack: [0xb68e1000,0xb6931000],  sp=0xb692f590,  free space=313k
Native frames: (J=compiled Java code, j=interpreted, Vv=VM code, C=native code)
C  [libnivissvc.so.13+0x258f2c]  ProfilerPushLabeledTimer+0x53980

[error occurred during error reporting (printing native stack), id 0xb]

Java frames: (J=compiled Java code, j=interpreted, Vv=VM code)
J 361  com.ni.vision.NIVision._Priv_ReadJPEGString_C(JJI)V (0 bytes) @ 0xb4815038 [0xb4814fe0+0x58]
J 357 C1 edu.wpi.first.wpilibj.vision.AxisCamera.getImage(Lcom/ni/vision/NIVision$Image;)Z (47 bytes) @ 0xb4813b88 [0xb48138f0+0x298]
J 326 C1 org.usfirst.frc3932.Robot.runCamera()V (42 bytes) @ 0xb480bac8 [0xb480ba90+0x38]
J 324 C1 org.usfirst.frc3932.Robot.teleopPeriodic()V (15 bytes) @ 0xb480b3b0 [0xb480b180+0x230]
j  edu.wpi.first.wpilibj.IterativeRobot.startCompetition()V+240
j  edu.wpi.first.wpilibj.RobotBase.main([Ljava/lang/String;)V+322
v  ~StubRoutines::call_stub

---------------  P R O C E S S  ---------------

Java Threads: ( => current thread )
  0xb67a7400 JavaThread "CameraServer Send Thread" [_thread_in_native, id=1733, stack(0xab632000,0xab682000)]
  0xad9e7800 JavaThread "Timer-1" [_thread_blocked, id=1591, stack(0xab970000,0xab9c0000)]
  0xad9e1c00 JavaThread "Thread-4" [_thread_blocked, id=1590, stack(0xab9c0000,0xaba10000)]
  0xabb0c400 JavaThread "Thread-3" [_thread_in_native, id=1589, stack(0xaba10000,0xaba60000)]
  0xabb0b000 JavaThread "Thread-2" [_thread_blocked, id=1588, stack(0xaba60000,0xabab0000)]
  0xabb0a000 JavaThread "Thread-1" [_thread_in_native, id=1587, stack(0xabab0000,0xabb00000)]
  0xad9f8800 JavaThread "Timer-0" [_thread_blocked, id=1586, stack(0xabc1f000,0xabc6f000)]
  0xad9f0800 JavaThread "NTListener" daemon [_thread_in_native, id=1585, stack(0xabc6f000,0xabcaf000)]
  0xad9bf800 JavaThread "FRCDriverStation" [_thread_in_native, id=1582, stack(0xabdc4000,0xabe14000)]
  0xb6799400 JavaThread "Service Thread" daemon [_thread_blocked, id=1570, stack(0xada9e000,0xadaee000)]
  0xb6796800 JavaThread "C1 CompilerThread0" daemon [_thread_blocked, id=1569, stack(0xadaee000,0xadb6e000)]
  0xb6795000 JavaThread "Signal Dispatcher" daemon [_thread_blocked, id=1568, stack(0xadf0d000,0xadf5d000)]
  0xb6773000 JavaThread "Finalizer" daemon [_thread_blocked, id=1566, stack(0xadfb0000,0xae000000)]
  0xb6771800 JavaThread "Reference Handler" daemon [_thread_blocked, id=1565, stack(0xb4603000,0xb4653000)]
=>0xb6705800 JavaThread "main" [_thread_in_native, id=1548, stack(0xb68e1000,0xb6931000)]

…anyone else having a problem like this?

CPU is at around 75% before the crash, drops to about 50, then 50 15 within a second or 2 until the code gets reloaded. I’ve attached the log file. Anyone we can talk to since the problem is outside our code? It seems to happen after a random interval between 3 and 8 minutes while the robot is enabled, even if sitting idle.

This is a chunk of our Robot.java, pardon the duplicated code - it’s a work in progress. Calling camera.getImage shouldn’t crash the JVM on us. Eating the exception isn’t a good idea either, including both to give the picture of what we actually have right now…


    public void robotInit() {
    RobotMap.init();
        // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS
        driveSystem = new DriveSystem();
        platform = new Platform();
        camera = new Camera();
        cannon = new Cannon();
        onBoardCompressor = new OnBoardCompressor();
        shooterWheels = new ShooterWheels();
        powerDistributionBoard = new PowerDistributionBoard();

    // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS
        // OI must be constructed after subsystems. If the OI creates Commands
        //(which it very likely will), subsystems are not guaranteed to be
        // constructed yet. Thus, their requires() statements may grab null
        // pointers. Bad news. Don't move it.
        oi = new OI();

        // instantiate the command used for the autonomous period
        // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=AUTONOMOUS

        autonomousCommand = new DriveTenFeetAuto();

    // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=AUTONOMOUS
        
		image = NIVision.imaqCreateImage(NIVision.ImageType.IMAGE_RGB, 0);
		
		axis13 = initCamera("10.39.32.14");
		
		axis11 = initCamera("10.39.32.11");
		
		axis12 = initCamera("10.39.32.13");
		

		
		
		// Let's detect if that third camera's there
		try {
			axis13.getImage(image);
			// Hooray, it worked!
			thirdCamera = true;
		}
		catch (Exception e){
			// Third camera's not there
//			axis13 = null;
			thirdCamera = false;
		}
		
		SmartDashboard.putString("Camera 3", axis13+"");
		currentCamera = axis11;
		
		
		ahrs = new AHRS(SPI.Port.kMXP);
		
		rangefinder = new LIDAR(I2C.Port.kMXP);
		rangefinder.start();
		
		camera.lightOn();

    }

    public void teleopPeriodic() {
        Scheduler.getInstance().run();
        
        
//        checkCompressor();
        runCamera();
        writeLIDAR();
    }

    /**
     * This function is called periodically during operator control
     */
    
	
	private void runCamera(){
		try {
			currentCamera.getImage(image);
			CameraServer.getInstance().setImage(image);
		} catch (Exception e) {
			System.err.println("Failed to get image from camera");
			System.err.println(e.getStackTrace());
		}
	}

    public static boolean hasCameraThree() {
    	try {
    		axis13.getImage(image);
    		return true;
    	}
    	catch (Exception e){
    		return false;
    	}
    }

Any help appreciated!

Not sure if this is related or not to your issue, but we had a problem with exhausting memory when grabbing images that would cause the robot code to crash and burn after running for a certain time period.

We found a fix (or work around) by invoking the free() method on the image objects returned after we were done with the image. The following provides an idea of what we did.


    // Grab image from USB camera and push out to camera server
    // for smart dashboard display
    Image frame = NIVision.imaqCreateImage(ImageType.IMAGE_RGB, 0);
    usbCamera.getImage(frame);
    cameraServer.setImage(frame);

    // Program crashes with out of memory issue if we remove this line
    frame.free();

I’m not really sure if calling free() is required on image objects (in Java you would hope that resources would be automatically freed by the garbage collector), I just know that our problem went away once we started invoking free().

Again, not sure if this is related to the problem you are seeing (I didn’t see anything in your error messages about running out of memory), but it might be something to try.

Good luck.

Thanks for the advice, certainly worth a try. The WPI lib for imaging is all native alls, not pure java, so anything is possible…

We used to have a C++ library that has a vision target class. It allocates a frame buffer to process each camera image it receives. When we switched over to Java, we ported this class to Java. We thought since Java has a garbage collector, so we took out all the “free” calls in the code. It surprised us when we hit the “Java VM ran out of memory” exception. So the moral of the story is, although Java has a garbage collector that reclaims unused memory, it’s an expensive operation and does not do well if a large number of memory allocations are required (i.e. the allocation out paced garbage collection). So it is possible to exhaust the Java memory pool. We ended up re-architected that part of the code and pre-allocated two frame buffers and doing ping-pong on only these two buffers. That took care of the “out-of-memory” exception.

In Java, the only resources released by the GC is GC-managed memory. The free call might be needed because if there are non-Java (C/C++/LabVIEW/files/etc.) resources held within an Image object, they will not be freed by the GC. This problem is the rationale for the try-with-resources (Java 7+). C++ has RAII to prevent this from ever being a problem.

The free didn’t help. If we were holding out a resource I’d expect to see the application (robot) start throwing out of memory errors, although it is possible that if the JVM is allocating memory and has been started with enough memory allocated that it’s exhausting the OS’s available memory it’s being killed by the oom killer (beware the oom killer!). I’m not sure if that would create a crash report.

Maybe something in /var/logs could provide a clue? Even if I find it I’m not sure we’ll be able to fix it since it’s in WPI’s native libraries somewhere. Any thoughts on who to contact for support on the WPI lib?

To provide some clarity, we can see from the stack from the JVM that we’re in com.ni.vision.NIVision._Priv_ReadJPEGString in wpi’s lib when the jvm crashes…

Java frames: (J=compiled Java code, j=interpreted, Vv=VM code)
J 361  com.ni.vision.NIVision._Priv_ReadJPEGString_C(JJI)V (0 bytes) @ 0xb4815038 [0xb4814fe0+0x58]
J 357 C1 edu.wpi.first.wpilibj.vision.AxisCamera.getImage(Lcom/ni/vision/NIVision$Image;)Z (47 bytes) @ 0xb4813b88 [0xb48138f0+0x298]
J 326 C1 org.usfirst.frc3932.Robot.runCamera()V (42 bytes) @ 0xb480bac8 [0xb480ba90+0x38]
J 324 C1 org.usfirst.frc3932.Robot.teleopPeriodic()V (15 bytes) @ 0xb480b3b0 [0xb480b180+0x230]
j  edu.wpi.first.wpilibj.IterativeRobot.startCompetition()V+240
j  edu.wpi.first.wpilibj.RobotBase.main(Ljava/lang/String;)V+322

…and our runCamera method from that stack is…


public static AxisCamera currentCamera;
.
.
.
	private void runCamera(){
		try {
			currentCamera.getImage(image);
			CameraServer.getInstance().setImage(image);
		} catch (Exception e) {
			System.err.println("Failed to get image from camera");
			System.err.println(e.getStackTrace());
		}
	}
.
.
.

…so from our Robot.java class the last touch point for us is currentCamera.getImage in this case.

Looking at the source for NIVision I think the .free() will work if used in a finally block. When we tried it the first time it didn’t end up in a finally block and the image was being used as a member variable.

The NIVision class is calling C libraries that allocate memory outside the JVM so the correct steps we need are (pseudo code):

  • Image image;
  • try
  • allocate image - image = NIVision.imaqCreateImage(NIVision.ImageType.IMAGE_RGB, 0);
  • use image - CameraServer.getInstance().setImage(image);
  • finally
  • free image - image.free();

Will repost when we understand better.

Still crashing.

Here’s the JVM version…

gsmin@roboRIO-3932-FRC:/usr/local/frc/bin# /usr/local/frc/JRE/bin/java -version -XX:+PrintCommandLineFlag
java version "1.8.0_06"
Java(TM) SE Embedded Runtime Environment (build 1.8.0_06-b23, profile compact2, headless)
Java HotSpot(TM) Embedded Client VM (build 25.6-b23, mixed mode)
admin@roboRIO-3932-FRC:/usr/local/frc/bin# cd /usr/local/frc/JRE/bin    
admin@roboRIO-3932-FRC:/usr/local/frc/JRE/bin# ls
java         keytool      rmid         rmiregistry
admin@roboRIO-3932-FRC:/usr/local/frc/JRE/bin# cd

…stats from top at time of crash…

Mem: 176600K used, 75372K free, 0K shrd, 93K buff, 3067729088K cached
CPU:   9% usr  12% sys   0% nic  76% idle   0% io   0% irq   0% sirq
Load average: 2.22 2.15 2.30 4/290 8550

Here is our latest and cleanest code with all the logic encapsulated in a single class. This still crashes the JVM…

public class CameraConfig {
	private AxisCamera camera;
	private String URL;
	
	public CameraConfig(String URL){
		this.URL = URL;
		this.camera = new AxisCamera(this.URL);
    	camera.writeExposurePriority(50);
	}
	
	public void sendImage() {
		Image image = NIVision.imaqCreateImage(NIVision.ImageType.IMAGE_RGB, 0);
		try {
			camera.getImage(image);
			CameraServer.getInstance().setImage(image);		
		} catch (Exception e) {
			System.err.println("Failed to get image from camera");
			System.err.println(e.getStackTrace());
		} finally {
			image.free();
		}
	}
	
	public boolean exists() {
    	boolean flag = false;
    	Image image = NIVision.imaqCreateImage(NIVision.ImageType.IMAGE_RGB, 0);
    	try {
    		camera.getImage(image);
    		flag = true;
    	}
    	catch (Exception e){
    		
    	}
    	finally {
    		image.free();
    	}
    	return flag;
	}
}

What happens if you make image a class variable? Allocating and deallocating it are expensive.

It also looks like you are using last years JRE.

We originally had Image as a class variable, but after looking at how it was used we made it local. Image is used to allocate memory for the native call way down the line so having it as a member variable leads to concerns about not being able to release the memory, thus the finally block. Having it as a member variable could potentially result in a memory leak which would first hurt performance and could ultimately crash the program with an out of memory exception.

We flashed all our roboRIOs this year, what makes you think it’s last years Java version? I’ll check on our end to make sure the RIOs are all running build 1.8.0_06-b23, I don’t think they would work at all if we hadn’t flashed them. Can you post a link or provide info. on why you think the JVM version is wrong and where/how we’d get the right one?

Thanks for your help!

Why do you have to create a new image every time you do a getImage? You can pre-allocate it one time as a class variable and just keep re-using the same created image buffer. That’s how we did it in our code. Actually, since we are using a separate thread for processing the image, we pre-allocated two image buffers so when one thread is accessing the image, the other thread won’t overwrite it with a fresh image. We just atomically swap the buffers when a new image is available.

The way native libraries work in Java is usually that you must call some sort of cleanup method manually. The garbage collector will clean up java objects, but not memory from native libraries and as you know, C(++) does not have a garbage collector.

(there must be a good reason that wpilib isn’t using finalize() to call free() - maybe finalize is unreliable?)

Anyway, I have to go with the previously stated recommendation, that you reuse the same image object. NI vision allows you to do that.