Package ftclib.vision
Class FtcVision
java.lang.Object
ftclib.vision.FtcVision
This class creates an FTC Vision Portal to support multiple vision processors. It also provides methods to
configure camera settings.
-
Field Summary
FieldsModifier and TypeFieldDescriptionprivate org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName
private static final long
private static final long
private final String
private org.openftc.easyopencv.OpenCvCamera
final TrcDbgTrace
private final org.firstinspires.ftc.vision.VisionPortal
-
Constructor Summary
ConstructorsModifierConstructorDescriptionFtcVision
(org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection cameraDirection, int imageWidth, int imageHeight, boolean enableLiveView, boolean enableStatOverlay, org.firstinspires.ftc.vision.VisionProcessor... visionProcessors) Constructor: Create an instance of the object.FtcVision
(org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName webcam, int imageWidth, int imageHeight, boolean enableLiveView, boolean enableStatOverlay, org.firstinspires.ftc.vision.VisionProcessor... visionProcessors) Constructor: Create an instance of the object.FtcVision
(org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName webcam1, org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName webcam2, int imageWidth, int imageHeight, boolean enableLiveView, boolean enableStatOverlay, org.firstinspires.ftc.vision.VisionProcessor... visionProcessors) Constructor: Create an instance of the object.private
FtcVision
(org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName webcam1Name, org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName webcam2Name, org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection cameraDirection, int imageWidth, int imageHeight, boolean enableLiveView, boolean enableStatOverlay, org.firstinspires.ftc.vision.VisionProcessor... visionProcessors) Constructor: Create an instance of the object. -
Method Summary
Modifier and TypeMethodDescriptionvoid
close()
This method shuts down VisionPortal.org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName
This method returns the active webcam.org.firstinspires.ftc.vision.VisionPortal.CameraState
This method returns the camera state.long
This method returns the current camera exposure time in usec.int
This method returns the current camera gain.org.firstinspires.ftc.robotcore.external.hardware.camera.controls.ExposureControl.Mode
This method return the camera exposure mode.long[]
This method returns the camera min and max exposure setting.int[]
This method returns the camera min and max gain setting.org.openftc.easyopencv.OpenCvCamera
This method returns the OpenCvCamera object.org.firstinspires.ftc.vision.VisionPortal
This method returns the created vision portal.boolean
isVisionProcessorEnabled
(org.firstinspires.ftc.vision.VisionProcessor visionProcessor) This method checks if the vision processor is enabled.void
setActiveWebcam
(org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName webcamName) This method sets the active webcam if we have two webcams.boolean
setExposureMode
(org.firstinspires.ftc.robotcore.external.hardware.camera.controls.ExposureControl.Mode exposureMode) This method sets the exposure mode.void
setFpsMeterEnabled
(boolean enabled) This method enables/disables FPS meter on the viewport.boolean
setManualExposure
(long exposureUsec, Integer gain) This method sets the camera exposure and gain.void
setProcessorEnabled
(org.firstinspires.ftc.vision.VisionProcessor visionProcessor, boolean enabled) This method enables/disables the vision processor.
-
Field Details
-
moduleName
-
LOOP_INTERVAL_MS
private static final long LOOP_INTERVAL_MS- See Also:
-
MAX_LOOP_TIME_MS
private static final long MAX_LOOP_TIME_MS- See Also:
-
tracer
-
visionPortal
private final org.firstinspires.ftc.vision.VisionPortal visionPortal -
openCvCamera
private org.openftc.easyopencv.OpenCvCamera openCvCamera -
activeWebcam
private org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName activeWebcam
-
-
Constructor Details
-
FtcVision
private FtcVision(org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName webcam1Name, org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName webcam2Name, org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection cameraDirection, int imageWidth, int imageHeight, boolean enableLiveView, boolean enableStatOverlay, org.firstinspires.ftc.vision.VisionProcessor... visionProcessors) Constructor: Create an instance of the object.- Parameters:
webcam1Name
- specifies USB webcam1 name, null if using phone built-in camera.webcam2Name
- specifies USB webcam2 name, null if has only one webcam or using phone built-in camera.cameraDirection
- specifies the phone camera direction, null if using USB webcam.imageWidth
- specifies the camera image width in pixels.imageHeight
- specifies the camera image height in pixels.enableLiveView
- specifies true to enable camera live view, false to disable.enableStatOverlay
- specifies true to enable stat overlay, false to disable.visionProcessors
- specifies an array of vision processors to be added.
-
FtcVision
public FtcVision(org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName webcam1, org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName webcam2, int imageWidth, int imageHeight, boolean enableLiveView, boolean enableStatOverlay, org.firstinspires.ftc.vision.VisionProcessor... visionProcessors) Constructor: Create an instance of the object.- Parameters:
webcam1
- specifies USB webcam1.webcam2
- specifies USB webcam2, null if has only one webcam.imageWidth
- specifies the camera image width in pixels.imageHeight
- specifies the camera image height in pixels.enableLiveView
- specifies true to enable camera live view, false to disable.enableStatOverlay
- specifies true to enable stat overlay, false to disable.visionProcessors
- specifies an array of vision processors to be added.
-
FtcVision
public FtcVision(org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName webcam, int imageWidth, int imageHeight, boolean enableLiveView, boolean enableStatOverlay, org.firstinspires.ftc.vision.VisionProcessor... visionProcessors) Constructor: Create an instance of the object.- Parameters:
webcam
- specifies USB webcam.imageWidth
- specifies the camera image width in pixels.imageHeight
- specifies the camera image height in pixels.enableLiveView
- specifies true to enable camera live view, false to disable.enableStatOverlay
- specifies true to enable stat overlay, false to disable.visionProcessors
- specifies an array of vision processors to be added.
-
FtcVision
public FtcVision(org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection cameraDirection, int imageWidth, int imageHeight, boolean enableLiveView, boolean enableStatOverlay, org.firstinspires.ftc.vision.VisionProcessor... visionProcessors) Constructor: Create an instance of the object.- Parameters:
cameraDirection
- specifies the phone camera direction, null if using USB webcam.imageWidth
- specifies the camera image width in pixels.imageHeight
- specifies the camera image height in pixels.enableLiveView
- specifies true to enable camera live view, false to disable.enableStatOverlay
- specifies true to enable stat overlay, false to disable.visionProcessors
- specifies an array of vision processors to be added.
-
-
Method Details
-
getVisionPortal
public org.firstinspires.ftc.vision.VisionPortal getVisionPortal()This method returns the created vision portal.- Returns:
- created vision portal.
-
close
public void close()This method shuts down VisionPortal. -
getOpenCvCamera
public org.openftc.easyopencv.OpenCvCamera getOpenCvCamera()This method returns the OpenCvCamera object.- Returns:
- OpenCvCamera object.
-
setFpsMeterEnabled
public void setFpsMeterEnabled(boolean enabled) This method enables/disables FPS meter on the viewport.- Parameters:
enabled
- specifies true to enable FPS meter, false to disable.
-
getActiveWebcam
public org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName getActiveWebcam()This method returns the active webcam.- Returns:
- active webcam.
-
setActiveWebcam
public void setActiveWebcam(org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName webcamName) This method sets the active webcam if we have two webcams.- Parameters:
webcamName
- specifies the webcam to be the active webcam.- Throws:
UnsupportedOperationException
- – if you are not using a switchable webcam.
-
setProcessorEnabled
public void setProcessorEnabled(org.firstinspires.ftc.vision.VisionProcessor visionProcessor, boolean enabled) This method enables/disables the vision processor.- Parameters:
visionProcessor
- specifies the vision processor to enable/disable.enabled
- specifies true to enable the vision processor, false to disable.
-
isVisionProcessorEnabled
public boolean isVisionProcessorEnabled(org.firstinspires.ftc.vision.VisionProcessor visionProcessor) This method checks if the vision processor is enabled.- Parameters:
visionProcessor
- specifies the vision processor.- Returns:
- true if the vision processor is enabled, false if disabled.
-
getCameraState
public org.firstinspires.ftc.vision.VisionPortal.CameraState getCameraState()This method returns the camera state.- Returns:
- camera state.
-
getExposureMode
public org.firstinspires.ftc.robotcore.external.hardware.camera.controls.ExposureControl.Mode getExposureMode()This method return the camera exposure mode.- Returns:
- exposure mode, null if unsuccessful.
-
setExposureMode
public boolean setExposureMode(org.firstinspires.ftc.robotcore.external.hardware.camera.controls.ExposureControl.Mode exposureMode) This method sets the exposure mode.- Parameters:
exposureMode
- specifies the exposure mode.- Returns:
- true if successful, false otherwise.
-
getExposureSetting
public long[] getExposureSetting()This method returns the camera min and max exposure setting.- Returns:
- array containing min and max exposure times in usec, null if unsuccessful.
-
getCurrentExposure
public long getCurrentExposure()This method returns the current camera exposure time in usec.- Returns:
- current exposure time in usec, 0 if unsuccessful.
-
getGainSetting
public int[] getGainSetting()This method returns the camera min and max gain setting.- Returns:
- array containing min and max gain values, null if unsuccessful.
-
getCurrentGain
public int getCurrentGain()This method returns the current camera gain.- Returns:
- current gain, 0 if unsuccessful.
-
setManualExposure
This method sets the camera exposure and gain. This can only be done if the camera is in manual exposure mode. If the camera is not already in manual exposure mode, this method will switch the camera to manual exposure mode. Note: This is a synchronous call and may take some time, so it should only be called at robotInit time.- Parameters:
exposureUsec
- specifies the exposure time in usec.gain
- specifies the camera gain, null if setting exposure only.- Returns:
- true if successful, false otherwise.
-