Difference between revisions of "Example Fiducial Square Binary"
From BoofCV
Jump to navigationJump to searchm  | 
				m  | 
				||
| Line 16: | Line 16: | ||
Relevant Examples/Tutorials:  | Relevant Examples/Tutorials:  | ||
* [[Tutorial_Fiducials|Tutorial Fiducials]]  | * [[Tutorial_Fiducials|Tutorial Fiducials]]  | ||
* [[Example_Fiducial_Square_Hamming|Example Fiducial Square Hamming]]  | |||
* [[Example_Fiducial_Square_Image|Example Fiducial Square Image]]  | * [[Example_Fiducial_Square_Image|Example Fiducial Square Image]]  | ||
* [[Example_Calibration_Target_Pose|Example Fiducial Calibration Target]]  | * [[Example_Calibration_Target_Pose|Example Fiducial Calibration Target]]  | ||
Revision as of 19:15, 8 October 2021
Demonstration how to detect square binary fiducials. Square binary fiducials encode a pattern in the fiducial's center which can describe up to 4096 unique targets.
Example Code:
Concepts:
- Fiducials
 - Pose estimation
 
Relevant Examples/Tutorials:
- Tutorial Fiducials
 - Example Fiducial Square Hamming
 - Example Fiducial Square Image
 - Example Fiducial Calibration Target
 
Videos
Example Code
/**
 * Detects square binary fiducials inside an image, writes out there pose, and visualizes a virtual flat cube
 * above them in the input image.
 *
 * These markers can have issues with noise and you might want to consider using ExampleFiducialHamming instead.
 *
 * @author Peter Abeles
 */
public class ExampleFiducialBinary {
	public static void main( String[] args ) {
		String directory = UtilIO.pathExample("fiducial/binary");
		// load the lens distortion parameters and the input image
		CameraPinholeBrown param = CalibrationIO.load(new File(directory, "intrinsic.yaml"));
		LensDistortionNarrowFOV lensDistortion = new LensDistortionBrown(param);
		BufferedImage input = UtilImageIO.loadImage(directory, "image0000.jpg");
//		BufferedImage input = UtilImageIO.loadImage(directory, "image0001.jpg");
//		BufferedImage input = UtilImageIO.loadImage(directory, "image0002.jpg");
		GrayF32 original = ConvertBufferedImage.convertFrom(input, true, ImageType.single(GrayF32.class));
		// Detect the fiducial
		FiducialDetector<GrayF32> detector = FactoryFiducial.squareBinary(
				new ConfigFiducialBinary(0.1), ConfigThreshold.local(ThresholdType.LOCAL_MEAN, 21), GrayF32.class);
//				new ConfigFiducialBinary(0.1), ConfigThreshold.fixed(100),GrayF32.class);
		detector.setLensDistortion(lensDistortion, param.width, param.height);
		detector.detect(original);
		// print the results
		Graphics2D g2 = input.createGraphics();
		Se3_F64 targetToSensor = new Se3_F64();
		Point2D_F64 locationPixel = new Point2D_F64();
		Polygon2D_F64 bounds = new Polygon2D_F64();
		for (int i = 0; i < detector.totalFound(); i++) {
			detector.getCenter(i, locationPixel);
			detector.getBounds(i, bounds);
			g2.setColor(new Color(50, 50, 255));
			g2.setStroke(new BasicStroke(10));
			VisualizeShapes.drawPolygon(bounds, true, 1.0, g2);
			if (detector.hasID())
				System.out.println("Target ID = " + detector.getId(i));
			if (detector.hasMessage())
				System.out.println("Message   = " + detector.getMessage(i));
			System.out.println("2D Image Location = " + locationPixel);
			if (detector.is3D()) {
				detector.getFiducialToCamera(i, targetToSensor);
				System.out.println("3D Location:");
				System.out.println(targetToSensor);
				VisualizeFiducial.drawCube(targetToSensor, param, detector.getWidth(i), 3, g2);
				VisualizeFiducial.drawLabelCenter(targetToSensor, param, "" + detector.getId(i), g2);
			} else {
				VisualizeFiducial.drawLabel(locationPixel, "" + detector.getId(i), g2);
			}
		}
		ShowImages.showWindow(input, "Fiducials", true);
	}
}