Difference between revisions of "Example Fiducial Square Image"
From BoofCV
Jump to navigationJump to searchm |
m |
||
Line 17: | Line 17: | ||
* [[Tutorial_Fiducials|Tutorial Fiducials]] | * [[Tutorial_Fiducials|Tutorial Fiducials]] | ||
* [[Example_Fiducial_Square_Binary|Example Fiducial Square Binary]] | * [[Example_Fiducial_Square_Binary|Example Fiducial Square Binary]] | ||
* [[Example_Fiducial_Square_Hamming|Example Fiducial Square Hamming]] | |||
* [[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 image fiducials. After the fiducial detector has been created a description of each image it detects is passed in. These images are converted into binary images and resized if needed. A large number of unique fiducials can be detected with a linear growth in computational time.
Example Code:
Concepts:
- Fiducials
- Pose estimation
Relevant Examples/Tutorials:
- Tutorial Fiducials
- Example Fiducial Square Binary
- Example Fiducial Square Hamming
- 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.
*
* @author Peter Abeles
*/
public class ExampleFiducialImage {
public static void main( String[] args ) {
String imagePath = UtilIO.pathExample("fiducial/image/examples/");
String patternPath = UtilIO.pathExample("fiducial/image/patterns/");
// String imageName = "image00.jpg";
String imageName = "image01.jpg";
// String imageName = "image02.jpg";
// load the lens distortion parameters and the input image
CameraPinholeBrown param = CalibrationIO.load(new File(imagePath, "intrinsic.yaml"));
LensDistortionNarrowFOV lensDistortion = new LensDistortionBrown(param);
BufferedImage input = UtilImageIO.loadImage(imagePath, imageName);
GrayF32 original = ConvertBufferedImage.convertFrom(input, true, ImageType.single(GrayF32.class));
// Detect the fiducial
SquareImage_to_FiducialDetector<GrayF32> detector = FactoryFiducial.squareImage(
new ConfigFiducialImage(), ConfigThreshold.local(ThresholdType.LOCAL_MEAN, 21), GrayF32.class);
// new ConfigFiducialImage(), ConfigThreshold.fixed(100), GrayF32.class);
// give it a description of all the targets
double width = 4; // 4 cm
detector.addPatternImage(loadImage(patternPath, "ke.png", GrayF32.class), 100, width);
detector.addPatternImage(loadImage(patternPath, "dog.png", GrayF32.class), 100, width);
detector.addPatternImage(loadImage(patternPath, "yu.png", GrayF32.class), 100, width);
detector.addPatternImage(loadImage(patternPath, "yu_inverted.png", GrayF32.class), 100, width);
detector.addPatternImage(loadImage(patternPath, "pentarose.png", GrayF32.class), 100, width);
detector.addPatternImage(loadImage(patternPath, "text_boofcv.png", GrayF32.class), 100, width);
detector.addPatternImage(loadImage(patternPath, "leaf01.png", GrayF32.class), 100, width);
detector.addPatternImage(loadImage(patternPath, "leaf02.png", GrayF32.class), 100, width);
detector.addPatternImage(loadImage(patternPath, "hand01.png", GrayF32.class), 100, width);
detector.addPatternImage(loadImage(patternPath, "chicken.png", GrayF32.class), 100, width);
detector.addPatternImage(loadImage(patternPath, "h2o.png", GrayF32.class), 100, width);
detector.addPatternImage(loadImage(patternPath, "yinyang.png", GrayF32.class), 100, width);
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);
}
}