Difference between revisions of "Example Stereo Visual Odometry"

From BoofCV
Jump to navigationJump to search
m
Line 21: Line 21:
Related Tutorials/Example Code:  
Related Tutorials/Example Code:  
* [[Tutorial_Geometric_Vision| Tutorial Geometric Vision]]
* [[Tutorial_Geometric_Vision| Tutorial Geometric Vision]]
= Example Code =


<syntaxhighlight lang="java">
<syntaxhighlight lang="java">

Revision as of 21:20, 20 June 2013

Stereo visual odometry estimates the camera's egomotion using a pair of calibrated cameras. Stereo camera systems are inheritly more stable than monocular ones because the stereo pair provides good triangulation of image features and resolves the scale ambiguity. The example below shows how to use a high level interface with visual odometyr algorithms. The basic high level interface hides internal data structures which are useful in many applications, which is why an optional interface is provided for accessing some of those structures.

Example File: ExampleStereoVisualOdometry.java

Concepts:

  • Structure from Motion
  • Geometric Vision
  • Feature Tracking

Relevant Applets:

Related Tutorials/Example Code:

Example Code

/**
 * Bare bones example showing how to estimate the camera's ego-motion using a stereo camera system. Additional
 * information on the scene can be optionally extracted from the algorithm if it implements AccessPointTracks3D.
 *
 * @author Peter Abeles
 */
public class ExampleStereoVisualOdometry {

	public static void main( String args[] ) {

		MediaManager media = DefaultMediaManager.INSTANCE;

		String directory = "../data/applet/vo/backyard/";

		// load camera description and the video sequence
		StereoParameters stereoParam = BoofMiscOps.loadXML(media.openFile(directory+"stereo.xml"));
		SimpleImageSequence<ImageUInt8> video1 = media.openVideo(directory + "left.mjpeg", ImageDataType.single(ImageUInt8.class));
		SimpleImageSequence<ImageUInt8> video2 = media.openVideo(directory+"right.mjpeg",ImageDataType.single(ImageUInt8.class));

		// specify how the image features are going to be tracked
		PkltConfig<ImageUInt8, ImageSInt16> configKlt = PkltConfig.createDefault(ImageUInt8.class, ImageSInt16.class);
		configKlt.pyramidScaling = new int[]{1, 2, 4, 8};
		configKlt.templateRadius = 3;

		PointTrackerTwoPass<ImageUInt8> tracker =
				FactoryPointTrackerTwoPass.klt(configKlt, new ConfigGeneralDetector(600, 3, 1));

		// computes the depth of each point
		StereoDisparitySparse<ImageUInt8> disparity =
				FactoryStereoDisparity.regionSparseWta(0, 150, 3, 3, 30, -1, true, ImageUInt8.class);

		// declares the algorithm
		StereoVisualOdometry<ImageUInt8> visualOdometry = FactoryVisualOdometry.stereoDepth(1.5,120, 2,200,50,true,
				disparity, tracker, ImageUInt8.class);

		// Pass in intrinsic/extrinsic calibration.  This can be changed in the future.
		visualOdometry.setCalibration(stereoParam);

		// Process the video sequence and output the location plus number of inliers
		while( video1.hasNext() ) {
			ImageUInt8 left = video1.next();
			ImageUInt8 right = video2.next();

			if( !visualOdometry.process(left,right) ) {
				throw new RuntimeException("VO Failed!");
			}

			Se3_F64 leftToWorld = visualOdometry.getLeftToWorld();
			Vector3D_F64 T = leftToWorld.getT();

			System.out.printf("Location %8.2f %8.2f %8.2f      inliers %s\n", T.x, T.y, T.z, inlierPercent(visualOdometry));
		}
	}

	/**
	 * If the algorithm implements AccessPointTracks3D, then count the number of inlier features
	 * and return a string.
	 */
	public static String inlierPercent(StereoVisualOdometry alg) {
		if( !(alg instanceof AccessPointTracks3D))
			return "";

		AccessPointTracks3D access = (AccessPointTracks3D)alg;

		int count = 0;
		int N = access.getAllTracks().size();
		for( int i = 0; i < N; i++ ) {
			if( access.isInlier(i) )
				count++;
		}

		return String.format("%%%5.3f", 100.0 * count / N);
	}
}