Skip to content

Commit

Permalink
Updated FtcLib.
Browse files Browse the repository at this point in the history
Added switchActiveCamera method to vision for switchable webcams.
  • Loading branch information
trc492 committed Oct 3, 2023
1 parent 1683b91 commit 365d756
Show file tree
Hide file tree
Showing 2 changed files with 36 additions and 11 deletions.
2 changes: 1 addition & 1 deletion TeamCode/src/main/java/TrcFtcLib
45 changes: 35 additions & 10 deletions TeamCode/src/main/java/teamcode/vision/Vision.java
Original file line number Diff line number Diff line change
Expand Up @@ -92,6 +92,9 @@ public class Vision
private FtcEocvColorBlobProcessor blueBlobProcessor;
public FtcVisionTensorFlow tensorFlowVision;
private TfodProcessor tensorFlowProcessor;
private WebcamName webcamName1;
private WebcamName webcamName2;
private WebcamName activeCamera;
private FtcVision vision;

/**
Expand All @@ -103,6 +106,7 @@ public class Vision
public Vision(Robot robot, TrcDbgTrace tracer)
{
FtcOpMode opMode = FtcOpMode.getInstance();

this.robot = robot;
if (RobotParams.Preferences.tuneColorBlobVision)
{
Expand Down Expand Up @@ -185,18 +189,26 @@ public Vision(Robot robot, TrcDbgTrace tracer)

VisionProcessor[] visionProcessors = new VisionProcessor[visionProcessorsList.size()];
visionProcessorsList.toArray(visionProcessors);
vision = RobotParams.Preferences.useWebCam ?
new FtcVision(
opMode.hardwareMap.get(WebcamName.class, RobotParams.HWNAME_WEBCAM1),
RobotParams.Preferences.hasWebCam2?
opMode.hardwareMap.get(WebcamName.class, RobotParams.HWNAME_WEBCAM2): null,
RobotParams.CAM_IMAGE_WIDTH, RobotParams.CAM_IMAGE_HEIGHT,
RobotParams.Preferences.showVisionView, visionProcessors) :
new FtcVision(
RobotParams.Preferences.useBuiltinCamBack ?
BuiltinCameraDirection.BACK : BuiltinCameraDirection.FRONT,
if (RobotParams.Preferences.useWebCam)
{
webcamName1 = opMode.hardwareMap.get(WebcamName.class, RobotParams.HWNAME_WEBCAM1);
webcamName2 =
RobotParams.Preferences.hasWebCam2 ?
opMode.hardwareMap.get(WebcamName.class, RobotParams.HWNAME_WEBCAM2) : null;
vision = new FtcVision(
webcamName1, webcamName2, RobotParams.CAM_IMAGE_WIDTH, RobotParams.CAM_IMAGE_HEIGHT,
RobotParams.Preferences.showVisionView, visionProcessors);
// Initialize the active camera to webcamName1.
switchActiveCamera();
}
else
{
vision = new FtcVision(
RobotParams.Preferences.useBuiltinCamBack?
BuiltinCameraDirection.BACK: BuiltinCameraDirection.FRONT,
RobotParams.CAM_IMAGE_WIDTH, RobotParams.CAM_IMAGE_HEIGHT,
RobotParams.Preferences.showVisionView, visionProcessors);
}
// Disable all vision processors until they are needed.
setRawColorBlobVisionEnabled(false);
setAprilTagVisionEnabled(false);
Expand All @@ -206,6 +218,19 @@ public Vision(Robot robot, TrcDbgTrace tracer)
}
} //Vision

/**
* This method switch between the two webcams.
*/
public void switchActiveCamera()
{
// Only do this if we have two webcams.
if (webcamName1 != null && webcamName2 != null)
{
activeCamera = activeCamera == null || activeCamera == webcamName2? webcamName1: webcamName2;
vision.getVisionPortal().setActiveCamera(activeCamera);
}
} //switchActiveCamera

/**
* This method returns the color threshold values of rawColorBlobVision.
*
Expand Down

0 comments on commit 365d756

Please sign in to comment.