mirror of
https://github.com/trc492/FtcTemplate.git
synced 2025-07-04 06:21:23 -07:00
Sync'd latest changes from IntoTheDeep.
Updated ftclib, trclib.
This commit is contained in:
@ -54,7 +54,7 @@ import trclib.timer.TrcTimer;
|
||||
* testing purposes. It provides numerous tests for diagnosing problems with the robot. It also provides tools
|
||||
* for tuning and calibration.
|
||||
*/
|
||||
@TeleOp(name="FtcTest", group="Ftcxxxx")
|
||||
@TeleOp(name="FtcTest", group="FtcTeam")
|
||||
public class FtcTest extends FtcTeleOp
|
||||
{
|
||||
private final String moduleName = getClass().getSimpleName();
|
||||
@ -232,10 +232,16 @@ public class FtcTest extends FtcTeleOp
|
||||
// Vision generally will impact performance, so we only enable it if it's needed.
|
||||
if (robot.vision.aprilTagVision != null)
|
||||
{
|
||||
robot.globalTracer.traceInfo(moduleName, "Enabling AprilTagVision.");
|
||||
robot.globalTracer.traceInfo(moduleName, "Enabling AprilTagVision for Webcam.");
|
||||
robot.vision.setAprilTagVisionEnabled(true);
|
||||
}
|
||||
|
||||
if (robot.vision.limelightVision != null)
|
||||
{
|
||||
robot.globalTracer.traceInfo(moduleName, "Enabling AprilTagVision for Limelight.");
|
||||
robot.vision.setLimelightVisionEnabled(0, true);
|
||||
}
|
||||
|
||||
if (robot.vision.redBlobVision != null)
|
||||
{
|
||||
robot.globalTracer.traceInfo(moduleName, "Enabling RedBlobVision.");
|
||||
@ -247,12 +253,6 @@ public class FtcTest extends FtcTeleOp
|
||||
robot.globalTracer.traceInfo(moduleName, "Enabling BlueBlobVision.");
|
||||
robot.vision.setColorBlobVisionEnabled(Vision.ColorBlobType.BlueBlob, true);
|
||||
}
|
||||
|
||||
if (robot.vision.limelightVision != null)
|
||||
{
|
||||
robot.globalTracer.traceInfo(moduleName, "Enabling LimelightVision.");
|
||||
robot.vision.setLimelightVisionEnabled(0, true);
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
@ -436,12 +436,12 @@ public class FtcTest extends FtcTeleOp
|
||||
{
|
||||
case SENSORS_TEST:
|
||||
case SUBSYSTEMS_TEST:
|
||||
doSensorsTest();
|
||||
doSensorsTest(lineNum);
|
||||
break;
|
||||
|
||||
case VISION_TEST:
|
||||
case TUNE_COLORBLOB_VISION:
|
||||
doVisionTest();
|
||||
doVisionTest(lineNum);
|
||||
break;
|
||||
|
||||
case X_TIMED_DRIVE:
|
||||
@ -617,6 +617,17 @@ public class FtcTest extends FtcTeleOp
|
||||
}
|
||||
passToTeleOp = false;
|
||||
}
|
||||
else if (testChoices.test == Test.VISION_TEST &&
|
||||
robot.vision != null && robot.vision.isLimelightVisionEnabled())
|
||||
{
|
||||
if (pressed)
|
||||
{
|
||||
int pipelineIndex = (robot.vision.limelightVision.getPipeline() + 1) %
|
||||
Vision.LimelightParams.NUM_PIPELINES;
|
||||
robot.vision.limelightVision.setPipeline(pipelineIndex);
|
||||
robot.globalTracer.traceInfo(moduleName, "Switch Limelight pipeline to " + pipelineIndex);
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case LeftBumper:
|
||||
@ -1015,10 +1026,11 @@ public class FtcTest extends FtcTeleOp
|
||||
* This method reads all sensors and prints out their values. This is a very useful diagnostic tool to check
|
||||
* if all sensors are working properly. For encoders, since test sensor mode is also teleop mode, you can
|
||||
* operate the gamepads to turn the motors and check the corresponding encoder counts.
|
||||
*
|
||||
* @param lineNum specifies the starting line number on the dashboard to display sensor states.
|
||||
*/
|
||||
private void doSensorsTest()
|
||||
private void doSensorsTest(int lineNum)
|
||||
{
|
||||
int lineNum = 9;
|
||||
//
|
||||
// Read all sensors and display on the dashboard.
|
||||
// Drive the robot around to sample different locations of the field.
|
||||
@ -1062,17 +1074,19 @@ public class FtcTest extends FtcTeleOp
|
||||
|
||||
/**
|
||||
* This method calls vision code to detect target objects and display their info.
|
||||
*
|
||||
* @param lineNum specifies the starting line number on the dashboard to display vision info.
|
||||
*/
|
||||
private void doVisionTest()
|
||||
private void doVisionTest(int lineNum)
|
||||
{
|
||||
if (robot.vision != null)
|
||||
{
|
||||
int lineNum = 9;
|
||||
|
||||
if (robot.vision.vision != null)
|
||||
if (robot.vision.limelightVision != null)
|
||||
{
|
||||
// displayExposureSettings is only available for VisionPortal.
|
||||
robot.vision.displayExposureSettings(lineNum++);
|
||||
robot.vision.getLimelightDetectedObject(
|
||||
robot.vision.limelightVision.getPipeline() == 0?
|
||||
FtcLimelightVision.ResultType.Fiducial: FtcLimelightVision.ResultType.Python,
|
||||
null, lineNum++);
|
||||
}
|
||||
|
||||
if (robot.vision.rawColorBlobVision != null)
|
||||
@ -1087,17 +1101,18 @@ public class FtcTest extends FtcTeleOp
|
||||
|
||||
if (robot.vision.redBlobVision != null)
|
||||
{
|
||||
robot.vision.getDetectedColorBlob(Vision.ColorBlobType.RedBlob, lineNum++);
|
||||
robot.vision.getDetectedColorBlob(Vision.ColorBlobType.RedBlob, 0.0, lineNum++);
|
||||
}
|
||||
|
||||
if (robot.vision.blueBlobVision != null)
|
||||
{
|
||||
robot.vision.getDetectedColorBlob(Vision.ColorBlobType.BlueBlob, lineNum++);
|
||||
robot.vision.getDetectedColorBlob(Vision.ColorBlobType.BlueBlob, 0.0, lineNum++);
|
||||
}
|
||||
|
||||
if (robot.vision.limelightVision != null)
|
||||
if (robot.vision.vision != null)
|
||||
{
|
||||
robot.vision.getLimelightDetectedObject(FtcLimelightVision.ResultType.Fiducial, null, lineNum++);
|
||||
// displayExposureSettings is only available for VisionPortal.
|
||||
robot.vision.displayExposureSettings(lineNum++);
|
||||
}
|
||||
}
|
||||
} //doVisionTest
|
||||
|
Reference in New Issue
Block a user