mirror of
https://github.com/trc492/FtcTemplate.git
synced 2025-07-01 13:01:24 -07:00
Updated ftclib.
Removed all TensorFlow support.
This commit is contained in:
Submodule TeamCode/src/main/java/ftclib updated: 542c65c802...52c7b712bc
@ -182,12 +182,6 @@ public class FtcAuto extends FtcOpMode
|
||||
// {
|
||||
// robot.globalTracer.traceInfo(moduleName, "Enabling BlueBlobVision.");
|
||||
// robot.vision.setBlueBlobVisionEnabled(true);
|
||||
// }
|
||||
//
|
||||
// if (robot.vision.tensorFlowVision != null)
|
||||
// {
|
||||
// robot.globalTracer.traceInfo(moduleName, "Enabling TensorFlowVision.");
|
||||
// robot.vision.setTensorFlowVisionEnabled(true);
|
||||
// }
|
||||
}
|
||||
|
||||
@ -235,16 +229,6 @@ public class FtcAuto extends FtcOpMode
|
||||
//
|
||||
robot.startMode(nextMode);
|
||||
|
||||
if (robot.vision != null)
|
||||
{
|
||||
// We are done with detecting object with TensorFlow, shut it down.
|
||||
if (robot.vision.tensorFlowVision != null)
|
||||
{
|
||||
robot.globalTracer.traceInfo(moduleName, "Disabling TensorFlowVision.");
|
||||
robot.vision.setTensorFlowVisionEnabled(false);
|
||||
}
|
||||
}
|
||||
|
||||
if (robot.battery != null)
|
||||
{
|
||||
robot.battery.setEnabled(true);
|
||||
|
@ -209,14 +209,6 @@ public class FtcTest extends FtcTeleOp
|
||||
}
|
||||
break;
|
||||
}
|
||||
//
|
||||
// Only VISION_TEST needs TensorFlow, shut it down for all other tests.
|
||||
//
|
||||
if (robot.vision != null && robot.vision.tensorFlowVision != null && testChoices.test != Test.VISION_TEST)
|
||||
{
|
||||
robot.globalTracer.traceInfo(moduleName, "Disabling TensorFlowVision.");
|
||||
robot.vision.setTensorFlowVisionEnabled(false);
|
||||
}
|
||||
} //robotInit
|
||||
|
||||
//
|
||||
@ -258,12 +250,6 @@ public class FtcTest extends FtcTeleOp
|
||||
robot.globalTracer.traceInfo(moduleName, "Enabling BlueBlobVision.");
|
||||
robot.vision.setBlueBlobVisionEnabled(true);
|
||||
}
|
||||
|
||||
if (robot.vision.tensorFlowVision != null)
|
||||
{
|
||||
robot.globalTracer.traceInfo(moduleName, "Enabling TensorFlowVison.");
|
||||
robot.vision.setTensorFlowVisionEnabled(true);
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
@ -1099,11 +1085,6 @@ public class FtcTest extends FtcTeleOp
|
||||
{
|
||||
robot.vision.getDetectedBlueBlob(lineNum++);
|
||||
}
|
||||
|
||||
if (robot.vision.tensorFlowVision != null)
|
||||
{
|
||||
robot.vision.getDetectedTensorFlowPixel(lineNum++);
|
||||
}
|
||||
}
|
||||
} //doVisionTest
|
||||
|
||||
|
@ -85,8 +85,7 @@ public class Robot
|
||||
if (RobotParams.Preferences.useVision &&
|
||||
(RobotParams.Preferences.tuneColorBlobVision ||
|
||||
RobotParams.Preferences.useAprilTagVision ||
|
||||
RobotParams.Preferences.useColorBlobVision ||
|
||||
RobotParams.Preferences.useTensorFlowVision))
|
||||
RobotParams.Preferences.useColorBlobVision))
|
||||
{
|
||||
vision = new Vision(this);
|
||||
}
|
||||
@ -219,11 +218,6 @@ public class Robot
|
||||
vision.setBlueBlobVisionEnabled(false);
|
||||
}
|
||||
|
||||
if (vision.tensorFlowVision != null)
|
||||
{
|
||||
globalTracer.traceInfo(moduleName, "Disabling TensorFlowVision.");
|
||||
vision.setTensorFlowVisionEnabled(false);
|
||||
}
|
||||
vision.close();
|
||||
}
|
||||
|
||||
|
@ -146,7 +146,6 @@ public class RobotParams
|
||||
public static final boolean tuneColorBlobVision = false;
|
||||
public static final boolean useAprilTagVision = false;
|
||||
public static final boolean useColorBlobVision = false;
|
||||
public static final boolean useTensorFlowVision = false;
|
||||
public static final boolean showVisionView = !inCompetition;
|
||||
public static final boolean showVisionStat = false;
|
||||
// Drive Base
|
||||
|
@ -36,7 +36,6 @@ public class BlinkinLEDs extends FtcRevBlinkin
|
||||
public static final String APRIL_TAG = "AprilTag";
|
||||
public static final String RED_BLOB = "RedBlob";
|
||||
public static final String BLUE_BLOB = "BlueBlob";
|
||||
public static final String TENSOR_FLOW = "TensorFlow";
|
||||
public static final String DRIVE_ORIENTATION_FIELD = "FieldMode";
|
||||
public static final String DRIVE_ORIENTATION_ROBOT = "RobotMode";
|
||||
public static final String DRIVE_ORIENTATION_INVERTED = "InvertedMode";
|
||||
@ -56,7 +55,6 @@ public class BlinkinLEDs extends FtcRevBlinkin
|
||||
new TrcRevBlinkin.Pattern(APRIL_TAG, RevLedPattern.SolidAqua),
|
||||
new TrcRevBlinkin.Pattern(RED_BLOB, RevLedPattern.SolidRed),
|
||||
new TrcRevBlinkin.Pattern(BLUE_BLOB, RevLedPattern.SolidBlue),
|
||||
new TrcRevBlinkin.Pattern(TENSOR_FLOW, RevLedPattern.SolidYellow),
|
||||
new TrcRevBlinkin.Pattern(DRIVE_ORIENTATION_FIELD, RevLedPattern.SolidViolet),
|
||||
new TrcRevBlinkin.Pattern(DRIVE_ORIENTATION_ROBOT, RevLedPattern.SolidWhite),
|
||||
new TrcRevBlinkin.Pattern(DRIVE_ORIENTATION_INVERTED, RevLedPattern.SolidGray),
|
||||
|
@ -28,7 +28,6 @@ import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.vision.VisionProcessor;
|
||||
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;
|
||||
import org.firstinspires.ftc.vision.tfod.TfodProcessor;
|
||||
import org.opencv.imgproc.Imgproc;
|
||||
import org.openftc.easyopencv.OpenCvCamera;
|
||||
import org.openftc.easyopencv.OpenCvCameraFactory;
|
||||
@ -42,7 +41,6 @@ import ftclib.vision.FtcRawEocvVision;
|
||||
import ftclib.vision.FtcVision;
|
||||
import ftclib.vision.FtcVisionAprilTag;
|
||||
import ftclib.vision.FtcVisionEocvColorBlob;
|
||||
import ftclib.vision.FtcVisionTensorFlow;
|
||||
import teamcode.Robot;
|
||||
import teamcode.RobotParams;
|
||||
import teamcode.subsystems.BlinkinLEDs;
|
||||
@ -53,7 +51,7 @@ import trclib.vision.TrcOpenCvDetector;
|
||||
import trclib.vision.TrcVisionTargetInfo;
|
||||
|
||||
/**
|
||||
* This class implements AprilTag/TensorFlow/Eocv Vision for the game season. It creates and initializes all the
|
||||
* This class implements AprilTag/Eocv Vision for the game season. It creates and initializes all the
|
||||
* vision target info as well as providing info for the robot, camera and the field. It also provides methods to get
|
||||
* the location of the robot and detected targets.
|
||||
*/
|
||||
@ -93,8 +91,6 @@ public class Vision
|
||||
private FtcEocvColorBlobProcessor redBlobProcessor;
|
||||
public FtcVisionEocvColorBlob blueBlobVision;
|
||||
private FtcEocvColorBlobProcessor blueBlobProcessor;
|
||||
public FtcVisionTensorFlow tensorFlowVision;
|
||||
private TfodProcessor tensorFlowProcessor;
|
||||
public FtcVision vision;
|
||||
|
||||
/**
|
||||
@ -184,17 +180,6 @@ public class Vision
|
||||
visionProcessorsList.add(blueBlobProcessor);
|
||||
}
|
||||
|
||||
if (RobotParams.Preferences.useTensorFlowVision)
|
||||
{
|
||||
tracer.traceInfo(moduleName, "Starting TensorFlowVision...");
|
||||
tensorFlowVision = new FtcVisionTensorFlow(
|
||||
null, true, TFOD_MODEL_ASSET, TFOD_TARGET_LABELS, robot.robotInfo.webCam1.cameraRect,
|
||||
robot.robotInfo.webCam1.worldRect);
|
||||
tensorFlowProcessor = tensorFlowVision.getVisionProcessor();
|
||||
tensorFlowProcessor.setMinResultConfidence(TFOD_MIN_CONFIDENCE);
|
||||
visionProcessorsList.add(tensorFlowProcessor);
|
||||
}
|
||||
|
||||
VisionProcessor[] visionProcessors = new VisionProcessor[visionProcessorsList.size()];
|
||||
visionProcessorsList.toArray(visionProcessors);
|
||||
if (RobotParams.Preferences.useWebCam)
|
||||
@ -571,54 +556,6 @@ public class Vision
|
||||
return colorBlobInfo;
|
||||
} //getDetectedBlueBlob
|
||||
|
||||
/**
|
||||
* This method enables/disables TensorFlow vision.
|
||||
*
|
||||
* @param enabled specifies true to enable, false to disable.
|
||||
*/
|
||||
public void setTensorFlowVisionEnabled(boolean enabled)
|
||||
{
|
||||
if (tensorFlowProcessor != null)
|
||||
{
|
||||
vision.setProcessorEnabled(tensorFlowProcessor, enabled);
|
||||
}
|
||||
} //setTensorFlowVisionEnabled
|
||||
|
||||
/**
|
||||
* This method checks if TensorFlow vision is enabled.
|
||||
*
|
||||
* @return true if enabled, false if disabled.
|
||||
*/
|
||||
public boolean isTensorFlowVisionEnabled()
|
||||
{
|
||||
return tensorFlowProcessor != null && vision.isVisionProcessorEnabled(tensorFlowProcessor);
|
||||
} //isTensorFlowVisionEnabled
|
||||
|
||||
/**
|
||||
* This method calls TensorFlow vision to detect the Pixel objects.
|
||||
*
|
||||
* @param lineNum specifies the dashboard line number to display the detected object info, -1 to disable printing.
|
||||
* @return detected Pixel object info.
|
||||
*/
|
||||
public TrcVisionTargetInfo<FtcVisionTensorFlow.DetectedObject> getDetectedTensorFlowPixel(int lineNum)
|
||||
{
|
||||
TrcVisionTargetInfo<FtcVisionTensorFlow.DetectedObject> tensorFlowInfo =
|
||||
tensorFlowVision.getBestDetectedTargetInfo(TFOD_OBJECT_LABEL, null, this::compareConfidence, 0.0, 0.0);
|
||||
|
||||
if (tensorFlowInfo != null && robot.blinkin != null)
|
||||
{
|
||||
robot.blinkin.setDetectedPattern(BlinkinLEDs.TENSOR_FLOW);
|
||||
}
|
||||
|
||||
if (lineNum != -1)
|
||||
{
|
||||
robot.dashboard.displayPrintf(
|
||||
lineNum, "%s: %s", BlinkinLEDs.TENSOR_FLOW, tensorFlowInfo != null? tensorFlowInfo: "Not found.");
|
||||
}
|
||||
|
||||
return tensorFlowInfo;
|
||||
} //getDetectedTensorFlowPixel
|
||||
|
||||
/**
|
||||
* This method is called by the Arrays.sort to sort the target object by increasing distance.
|
||||
*
|
||||
@ -634,19 +571,4 @@ public class Vision
|
||||
return (int)((b.objPose.y - a.objPose.y)*100);
|
||||
} //compareDistance
|
||||
|
||||
/**
|
||||
* This method is called by the Arrays.sort to sort the target object by decreasing confidence.
|
||||
*
|
||||
* @param a specifies the first target
|
||||
* @param b specifies the second target.
|
||||
* @return negative value if a has higher confidence than b, 0 if a and b have equal confidence, positive value
|
||||
* if a has lower confidence than b.
|
||||
*/
|
||||
private int compareConfidence(
|
||||
TrcVisionTargetInfo<FtcVisionTensorFlow.DetectedObject> a,
|
||||
TrcVisionTargetInfo<FtcVisionTensorFlow.DetectedObject> b)
|
||||
{
|
||||
return (int)((b.detectedObj.confidence - a.detectedObj.confidence)*100);
|
||||
} //compareConfidence
|
||||
|
||||
} //class Vision
|
||||
|
Reference in New Issue
Block a user