/** * Computes a score (0-100) comparing the aspect ratio to the ideal aspect ratio for the target. * This method uses the equivalent rectangle sides to determine aspect ratio as it performs better * as the target gets skewed by moving to the left or right. The equivalent rectangle is the * rectangle with sides x and y where particle area= x*y and particle perimeter= 2x+2y * * @param image The image containing the particle to score, needed to perform additional * measurements * @param report The Particle Analysis Report for the particle, used for the width, height, and * particle number * @param outer Indicates whether the particle aspect ratio should be compared to the ratio for * the inner target or the outer * @return The aspect ratio score (0-100) */ public double scoreAspectRatio( BinaryImage image, ParticleAnalysisReport report, int particleNumber, boolean outer) throws NIVisionException { double rectLong, rectShort, aspectRatio, idealAspectRatio; rectLong = NIVision.MeasureParticle( image.image, particleNumber, false, MeasurementType.IMAQ_MT_EQUIVALENT_RECT_LONG_SIDE); rectShort = NIVision.MeasureParticle( image.image, particleNumber, false, MeasurementType.IMAQ_MT_EQUIVALENT_RECT_SHORT_SIDE); idealAspectRatio = outer ? (62 / 29) : (62 / 20); // Dimensions of goal opening + 4 inches on all 4 sides for reflective tape // Divide width by height to measure aspect ratio if (report.boundingRectWidth > report.boundingRectHeight) { // particle is wider than it is tall, divide long by short aspectRatio = 100 * (1 - Math.abs((1 - ((rectLong / rectShort) / idealAspectRatio)))); } else { // particle is taller than it is wide, divide short by long aspectRatio = 100 * (1 - Math.abs((1 - ((rectShort / rectLong) / idealAspectRatio)))); } return (Math.max(0, Math.min(aspectRatio, 100.0))); // force to be in range 0-100 }
/** * Computes the distance away from the target * * @param image The image containing the particle to score * @param report The Particle Analysis Report for the particle * @param particleNumber Particle number in the analysis * @param outer Indicates whether the particle aspect ratio should be compared to the ratio for * the inner target or the outer * @return Approximate distance from the target * @throws NIVisionException */ double computeDistance( BinaryImage image, ParticleAnalysisReport report, int particleNumber, boolean outer) throws NIVisionException { double rectShort, height; int targetHeight; angle = CommandBase.shooterPitch.getPosition(); rectShort = NIVision.MeasureParticle( image.image, particleNumber, false, MeasurementType.IMAQ_MT_EQUIVALENT_RECT_SHORT_SIDE); // using the smaller of the estimated rectangle short side and the bounding rectangle height // results in better performance // on skewed rectangles height = Math.min(report.boundingRectHeight, rectShort); targetHeight = outer ? 29 : 21; return X_IMAGE_RES * targetHeight / (height * 12 * 2 * Math.tan(angle * Math.PI / (180 * 2))); }
/** * Computes a score based on the match between a template profile and the particle profile in the * Y direction. This method uses the the row averages and the profile defined at the top of the * sample to look for the solid horizontal edges with a hollow center * * @param image The image to use, should be the image before the convex hull is performed * @param report The Particle Analysis Report for the particle * @return The Y Edge score (0-100) */ public double scoreYEdge(BinaryImage image, ParticleAnalysisReport report) throws NIVisionException { double total = 0; LinearAverages averages; Rect rect = new Rect( report.boundingRectTop, report.boundingRectLeft, report.boundingRectHeight, report.boundingRectWidth); averages = NIVision.getLinearAverages( image.image, LinearAverages.LinearAveragesMode.IMAQ_ROW_AVERAGES, rect); float rowAverages[] = averages.getRowAverages(); for (int i = 0; i < (rowAverages.length); i++) { if (yMin[(i * (YMINSIZE - 1) / rowAverages.length)] < rowAverages[i] && rowAverages[i] < yMax[i * (YMAXSIZE - 1) / rowAverages.length]) { total++; } } total = 100 * total / (rowAverages.length); return total; }
/** * Computes a score based on the match between a template profile and the particle profile in the * X direction. This method uses the the column averages and the profile defined at the top of the * sample to look for the solid vertical edges with a hollow center. * * @param image The image to use, should be the image before the convex hull is performed * @param report The Particle Analysis Report for the particle * @return The X Edge Score (0-100) */ public double scoreXEdge(BinaryImage image, ParticleAnalysisReport report) throws NIVisionException { double total = 0; LinearAverages averages; NIVision.Rect rect = new NIVision.Rect( report.boundingRectTop, report.boundingRectLeft, report.boundingRectHeight, report.boundingRectWidth); averages = NIVision.getLinearAverages( image.image, LinearAverages.LinearAveragesMode.IMAQ_COLUMN_AVERAGES, rect); float columnAverages[] = averages.getColumnAverages(); for (int i = 0; i < (columnAverages.length); i++) { if (xMin[(i * (XMINSIZE - 1) / columnAverages.length)] < columnAverages[i] && columnAverages[i] < xMax[i * (XMAXSIZE - 1) / columnAverages.length]) { total++; } } total = 100 * total / (columnAverages.length); return total; }