Difference between revisions of "Example Sparse Bundle Adjustment"

From BoofCV
Jump to navigationJump to search
m
m
 
(6 intermediate revisions by the same user not shown)
Line 8: Line 8:


Example Code:
Example Code:
* [https://github.com/lessthanoptimal/BoofCV/blob/v0.33/examples/src/main/java/boofcv/examples/sfm/ExampleBundleAdjustment.java ExampleBundleAdjustment.java]
* [https://github.com/lessthanoptimal/BoofCV/blob/v0.41/examples/src/main/java/boofcv/examples/sfm/ExampleBundleAdjustment.java ExampleBundleAdjustment.java]


Concepts:
Concepts:
Line 14: Line 14:
* Multiple Views
* Multiple Views
* Scene Reconstruction
* Scene Reconstruction
Related:
* [[Example_Bundle_Adjustment_Graph||Bundle Adjustment Graph Construction]].


= Example Code =
= Example Code =
Line 29: Line 32:
  * modest problems shows performance that's comparable to Ceres Solver. BoofCV has yet to be applied to what would
  * modest problems shows performance that's comparable to Ceres Solver. BoofCV has yet to be applied to what would
  * be now considered a truly large scale problem that takes day(s) to solve.
  * be now considered a truly large scale problem that takes day(s) to solve.
*
* To see how you create the scene graph look at {@link ExampleBundleAdjustmentGraph}. This code skips over
* that part since it's loaded from disk.
  *
  *
  * @author Peter Abeles
  * @author Peter Abeles
  */
  */
public class ExampleBundleAdjustment {
public class ExampleBundleAdjustment {
public static void main(String[] args) throws IOException {
public static void main( String[] args ) throws IOException {
 
// Because the Bundle Adjustment in the Large data set is popular, a file reader and writer is included
// Because the Bundle Adjustment in the Large data set is popular, a file reader and writer is included
// with BoofCV. BoofCV uses two data types to describe the parameters in a bundle adjustment problem
// with BoofCV. BoofCV uses two data types to describe the parameters in a bundle adjustment problem
// BundleAdjustmentSceneStructure is used for camera parameters, camera locations, and 3D points
// SceneStructureMetric is used for camera parameters, camera locations, and 3D points
// BundleAdjustmentObservations for image observations of 3D points
// SceneObservations for pixel observations of 3D points in each image.
// ExampleMultiViewSceneReconstruction gives a better feel for these data structures or you can look
// ExampleMultiViewSceneReconstruction gives a better feel for these data structures or you can look
// at the source code of CodecBundleAdjustmentInTheLarge
// at the source code of CodecBundleAdjustmentInTheLarge
CodecBundleAdjustmentInTheLarge parser = new CodecBundleAdjustmentInTheLarge();
var parser = new CodecBundleAdjustmentInTheLarge();


parser.parse(new File(UtilIO.pathExample("sfm/problem-16-22106-pre.txt")));
parser.parse(new File(UtilIO.pathExample("sfm/problem-16-22106-pre.txt")));


// Print information which gives you an idea of the problem's scale
// Print information which gives you an idea of the problem's scale
System.out.println("Optimizing "+parser.scene.getParameterCount()+
System.out.println("Optimizing " + parser.scene.getParameterCount() +
" parameters with "+parser.observations.getObservationCount()+" observations\n\n");
" parameters with " + parser.observations.getObservationCount() + " observations\n\n");


// Configure the sparse Levenberg-Marquardt solver
// Configure the sparse Levenberg-Marquardt solver
ConfigLevenbergMarquardt configLM = new ConfigLevenbergMarquardt();
var configLM = new ConfigLevenbergMarquardt();
// Important tuning parameter. Won't converge to a good solution if picked improperly. Small changes
// Important tuning parameter. Won't converge to a good solution if picked improperly. Small changes
// to this problem and speed up or slow down convergence and change the final result. This is true for
// to this problem and speed up or slow down convergence and change the final result. This is true for
Line 58: Line 63:
configLM.hessianScaling = true;
configLM.hessianScaling = true;


ConfigBundleAdjustment configSBA = new ConfigBundleAdjustment();
var configSBA = new ConfigBundleAdjustment();
configSBA.configOptimizer = configLM;
configSBA.configOptimizer = configLM;


Line 64: Line 69:
BundleAdjustment<SceneStructureMetric> bundleAdjustment = FactoryMultiView.bundleSparseMetric(configSBA);
BundleAdjustment<SceneStructureMetric> bundleAdjustment = FactoryMultiView.bundleSparseMetric(configSBA);
// prints out useful debugging information that lets you know how well it's converging
// prints out useful debugging information that lets you know how well it's converging
bundleAdjustment.setVerbose(System.out,0);
bundleAdjustment.setVerbose(System.out, null);
// Specifies convergence criteria
// Specifies convergence criteria
bundleAdjustment.configure(1e-6, 1e-6, 50);
bundleAdjustment.configure(1e-6, 1e-6, 50);
Line 70: Line 75:
// Scaling each variable type so that it takes on a similar numerical value. This aids in optimization
// Scaling each variable type so that it takes on a similar numerical value. This aids in optimization
// Not important for this problem but is for others
// Not important for this problem but is for others
ScaleSceneStructure bundleScale = new ScaleSceneStructure();
var bundleScale = new ScaleSceneStructure();
bundleScale.applyScale(parser.scene, parser.observations);
bundleScale.applyScale(parser.scene, parser.observations);
bundleAdjustment.setParameters(parser.scene, parser.observations);
bundleAdjustment.setParameters(parser.scene, parser.observations);
Line 77: Line 82:
long startTime = System.currentTimeMillis();
long startTime = System.currentTimeMillis();
double errorBefore = bundleAdjustment.getFitScore();
double errorBefore = bundleAdjustment.getFitScore();
if( !bundleAdjustment.optimize(parser.scene) ) {
if (!bundleAdjustment.optimize(parser.scene)) {
throw new RuntimeException("Bundle adjustment failed?!?");
throw new RuntimeException("Bundle adjustment failed?!?");
}
}
Line 83: Line 88:
// Print out how much it improved the model
// Print out how much it improved the model
System.out.println();
System.out.println();
System.out.printf("Error reduced by %.1f%%\n",(100.0*(errorBefore/bundleAdjustment.getFitScore()-1.0)));
System.out.printf("Error reduced by %.1f%%\n", (100.0*(errorBefore/bundleAdjustment.getFitScore() - 1.0)));
System.out.println(BoofMiscOps.milliToHuman(System.currentTimeMillis()-startTime));
System.out.println(BoofMiscOps.milliToHuman(System.currentTimeMillis() - startTime));


// Return parameters to their original scaling. Can probably skip this step.
// Return parameters to their original scaling. Can probably skip this step.
Line 93: Line 98:
}
}


private static void visualizeInPointCloud(SceneStructureMetric structure ) {
private static void visualizeInPointCloud( SceneStructureMetric structure ) {
 
List<Point3D_F64> cloudXyz = new ArrayList<>();
List<Point3D_F64> cloudXyz = new ArrayList<>();
Point3D_F64 world = new Point3D_F64();
Point3D_F64 world = new Point3D_F64();
Point3D_F64 camera = new Point3D_F64();
Point3D_F64 camera = new Point3D_F64();


for( int i = 0; i < structure.points.length; i++ ) {
for (int i = 0; i < structure.points.size; i++) {
// Get 3D location
// Get 3D location
SceneStructureMetric.Point p = structure.points[i];
SceneStructureCommon.Point p = structure.points.get(i);
p.get(world);
p.get(world);


// Project point into an arbitrary view
// Project point into an arbitrary view
for (int j = 0; j < p.views.size; j++) {
for (int j = 0; j < p.views.size; j++) {
int viewIdx = p.views.get(j);
int viewIdx = p.views.get(j);
SePointOps_F64.transform(structure.views[viewIdx].worldToView,world,camera);
SePointOps_F64.transform(structure.getParentToView(viewIdx), world, camera);
cloudXyz.add( world.copy() );
cloudXyz.add(world.copy());
break;
break;
}
}
Line 115: Line 119:
PointCloudViewer viewer = VisualizeData.createPointCloudViewer();
PointCloudViewer viewer = VisualizeData.createPointCloudViewer();
viewer.setFog(true);
viewer.setFog(true);
viewer.setColorizer(new SingleAxisRgb.Z().fperiod(20)); // makes it easier to see points without RGB color
viewer.setClipDistance(70); // done for visualization to make it easier to separate objects with the fog
viewer.setClipDistance(70); // done for visualization to make it easier to separate objects with the fog
viewer.setDotSize(1);
viewer.setDotSize(1);
Line 122: Line 127:


// Give it a good initial pose. This was determined through trial and error
// Give it a good initial pose. This was determined through trial and error
Se3_F64 cameraToWorld = new Se3_F64();
var cameraToWorld = new Se3_F64();
cameraToWorld.T.set(-10.848385, -6.957626, 2.9747992);
cameraToWorld.T.setTo(-10.848385, -6.957626, 2.9747992);
ConvertRotation3D_F64.eulerToMatrix(EulerType.XYZ,-2.734419,-0.27446,-0.24310,cameraToWorld.R);
ConvertRotation3D_F64.eulerToMatrix(EulerType.XYZ, -2.734419, -0.27446, -0.24310, cameraToWorld.R);
viewer.setCameraToWorld(cameraToWorld);
viewer.setCameraToWorld(cameraToWorld);


SwingUtilities.invokeLater(()->{
SwingUtilities.invokeLater(() -> {
viewer.getComponent().setPreferredSize(new Dimension(600,600));
viewer.getComponent().setPreferredSize(new Dimension(600, 600));
ShowImages.showWindow(viewer.getComponent(), "Refined Scene", true);
ShowImages.showWindow(viewer.getComponent(), "Refined Scene", true);
});
});
}
}
}
}
</syntaxhighlight>
</syntaxhighlight>

Latest revision as of 17:49, 2 September 2022

Bundle Adjustment is the typical last step in almost every algorithm which involve reconstruction of a scene from three or more images. Bundle Adjustment is a non-linear batch optimization where feature locations, camera positions, and intrinsic camera parameters are all optimized at once. Sparse Bundle Adjustment (SBA) refers to algorithms which take advantage of the sparsity, speeding up the computation many, many times. In this example, 67,000 parameters are optimized and the reprojection error is reduced by about 7000% in 2 minutes using a single thread.

Example Code:

Concepts:

  • Bundle Adjustment
  • Multiple Views
  • Scene Reconstruction

Related:

Example Code

/**
 * Demonstration for running sparse bundle adjustment in BoofCV. Bundle adjustment is a problem where a
 * a batch optimization is applied to camera pose, camera parameters, and point locations are all optimized.
 * It's the last step in scene reconstruction and is a very important step. In recent years, applying bundle
 * adjustment to very large scale problems has become important.
 *
 * In this example, data from the "Bundle Adjustment in the Large" paper is used. These data sets are often used
 * to compare different bundle adjustment algorithms against each other. Which is why BoofCV provides a parser
 * and camera model for their dataset. The algorithms in BoofCV are in the early stage of development but on more
 * modest problems shows performance that's comparable to Ceres Solver. BoofCV has yet to be applied to what would
 * be now considered a truly large scale problem that takes day(s) to solve.
 *
 * To see how you create the scene graph look at {@link ExampleBundleAdjustmentGraph}. This code skips over
 * that part since it's loaded from disk.
 *
 * @author Peter Abeles
 */
public class ExampleBundleAdjustment {
	public static void main( String[] args ) throws IOException {
		// Because the Bundle Adjustment in the Large data set is popular, a file reader and writer is included
		// with BoofCV. BoofCV uses two data types to describe the parameters in a bundle adjustment problem
		// SceneStructureMetric is used for camera parameters, camera locations, and 3D points
		// SceneObservations for pixel observations of 3D points in each image.
		// ExampleMultiViewSceneReconstruction gives a better feel for these data structures or you can look
		// at the source code of CodecBundleAdjustmentInTheLarge
		var parser = new CodecBundleAdjustmentInTheLarge();

		parser.parse(new File(UtilIO.pathExample("sfm/problem-16-22106-pre.txt")));

		// Print information which gives you an idea of the problem's scale
		System.out.println("Optimizing " + parser.scene.getParameterCount() +
				" parameters with " + parser.observations.getObservationCount() + " observations\n\n");

		// Configure the sparse Levenberg-Marquardt solver
		var configLM = new ConfigLevenbergMarquardt();
		// Important tuning parameter. Won't converge to a good solution if picked improperly. Small changes
		// to this problem and speed up or slow down convergence and change the final result. This is true for
		// basically all solvers.
		configLM.dampeningInitial = 1e-3;
		// Improves Jacobian matrix's condition. Recommended in general but not important in this problem
		configLM.hessianScaling = true;

		var configSBA = new ConfigBundleAdjustment();
		configSBA.configOptimizer = configLM;

		// Create and configure the bundle adjustment solver
		BundleAdjustment<SceneStructureMetric> bundleAdjustment = FactoryMultiView.bundleSparseMetric(configSBA);
		// prints out useful debugging information that lets you know how well it's converging
		bundleAdjustment.setVerbose(System.out, null);
		// Specifies convergence criteria
		bundleAdjustment.configure(1e-6, 1e-6, 50);

		// Scaling each variable type so that it takes on a similar numerical value. This aids in optimization
		// Not important for this problem but is for others
		var bundleScale = new ScaleSceneStructure();
		bundleScale.applyScale(parser.scene, parser.observations);
		bundleAdjustment.setParameters(parser.scene, parser.observations);

		// Runs the solver. This will take a few minutes. 7 iterations takes about 3 minutes on my computer
		long startTime = System.currentTimeMillis();
		double errorBefore = bundleAdjustment.getFitScore();
		if (!bundleAdjustment.optimize(parser.scene)) {
			throw new RuntimeException("Bundle adjustment failed?!?");
		}

		// Print out how much it improved the model
		System.out.println();
		System.out.printf("Error reduced by %.1f%%\n", (100.0*(errorBefore/bundleAdjustment.getFitScore() - 1.0)));
		System.out.println(BoofMiscOps.milliToHuman(System.currentTimeMillis() - startTime));

		// Return parameters to their original scaling. Can probably skip this step.
		bundleScale.undoScale(parser.scene, parser.observations);

		// Visualize the results using a point cloud viewer
		visualizeInPointCloud(parser.scene);
	}

	private static void visualizeInPointCloud( SceneStructureMetric structure ) {
		List<Point3D_F64> cloudXyz = new ArrayList<>();
		Point3D_F64 world = new Point3D_F64();
		Point3D_F64 camera = new Point3D_F64();

		for (int i = 0; i < structure.points.size; i++) {
			// Get 3D location
			SceneStructureCommon.Point p = structure.points.get(i);
			p.get(world);

			// Project point into an arbitrary view
			for (int j = 0; j < p.views.size; j++) {
				int viewIdx = p.views.get(j);
				SePointOps_F64.transform(structure.getParentToView(viewIdx), world, camera);
				cloudXyz.add(world.copy());
				break;
			}
		}

		PointCloudViewer viewer = VisualizeData.createPointCloudViewer();
		viewer.setFog(true);
		viewer.setColorizer(new SingleAxisRgb.Z().fperiod(20)); // makes it easier to see points without RGB color
		viewer.setClipDistance(70); // done for visualization to make it easier to separate objects with the fog
		viewer.setDotSize(1);
		viewer.setTranslationStep(0.05);
		viewer.addCloud(cloudXyz);
		viewer.setCameraHFov(UtilAngle.radian(60));

		// Give it a good initial pose. This was determined through trial and error
		var cameraToWorld = new Se3_F64();
		cameraToWorld.T.setTo(-10.848385, -6.957626, 2.9747992);
		ConvertRotation3D_F64.eulerToMatrix(EulerType.XYZ, -2.734419, -0.27446, -0.24310, cameraToWorld.R);
		viewer.setCameraToWorld(cameraToWorld);

		SwingUtilities.invokeLater(() -> {
			viewer.getComponent().setPreferredSize(new Dimension(600, 600));
			ShowImages.showWindow(viewer.getComponent(), "Refined Scene", true);
		});
	}
}