Skip to content

Commit

Permalink
Updated CommonLib.
Browse files Browse the repository at this point in the history
Updated FtcLib.
Sync'd latest changes.
  • Loading branch information
trc492 committed Sep 28, 2023
1 parent 907bd58 commit b709129
Show file tree
Hide file tree
Showing 7 changed files with 176 additions and 73 deletions.
3 changes: 2 additions & 1 deletion TeamCode/src/main/java/teamcode/FtcTeleOp.java
Original file line number Diff line number Diff line change
Expand Up @@ -146,6 +146,7 @@ public void periodic(double elapsedTime, boolean slowPeriodicLoop)
{
if (slowPeriodicLoop)
{
int lineNum = 1;
//
// DriveBase subsystem.
//
Expand All @@ -166,7 +167,7 @@ public void periodic(double elapsedTime, boolean slowPeriodicLoop)
robot.robotDrive.driveBase.arcadeDrive(inputs[1], inputs[2]);
}
robot.dashboard.displayPrintf(
1, "Pose:%s,x=%.2f,y=%.2f,rot=%.2f",
lineNum++, "Pose:%s,x=%.2f,y=%.2f,rot=%.2f",
robot.robotDrive.driveBase.getFieldPosition(), inputs[0], inputs[1], inputs[2]);
}
//
Expand Down
79 changes: 20 additions & 59 deletions TeamCode/src/main/java/teamcode/FtcTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -34,24 +34,18 @@

import TrcCommonLib.trclib.TrcElapsedTimer;
import TrcCommonLib.trclib.TrcGameController;
import TrcCommonLib.trclib.TrcOpenCvColorBlobPipeline;
import TrcCommonLib.trclib.TrcOpenCvDetector;
import TrcCommonLib.trclib.TrcPidController;
import TrcCommonLib.trclib.TrcPose2D;
import TrcCommonLib.trclib.TrcRobot;
import TrcCommonLib.trclib.TrcTimer;
import TrcCommonLib.trclib.TrcUtil;
import TrcCommonLib.trclib.TrcVisionTargetInfo;
import TrcFtcLib.ftclib.FtcChoiceMenu;
import TrcFtcLib.ftclib.FtcGamepad;
import TrcFtcLib.ftclib.FtcMenu;
import TrcFtcLib.ftclib.FtcPidCoeffCache;
import TrcFtcLib.ftclib.FtcValueMenu;
import TrcFtcLib.ftclib.FtcVisionAprilTag;
import TrcFtcLib.ftclib.FtcVisionTensorFlow;
import teamcode.drivebases.RobotDrive;
import teamcode.drivebases.SwerveDrive;
import teamcode.subsystems.BlinkinLEDs;

/**
* This class contains the Test Mode program. It extends FtcTeleOp so that we can teleop control the robot for
Expand Down Expand Up @@ -408,19 +402,19 @@ public void periodic(double elapsedTime, boolean slowPeriodicLoop)
prevTime = currTime;
prevVelocity = velocity;

robot.dashboard.displayPrintf(9, "Drive Vel: (%.1f/%.1f)", velocity, maxDriveVelocity);
robot.dashboard.displayPrintf(10, "Drive Accel: (%.1f/%.1f)", acceleration, maxDriveAcceleration);
robot.dashboard.displayPrintf(1, "Drive Vel: (%.1f/%.1f)", velocity, maxDriveVelocity);
robot.dashboard.displayPrintf(2, "Drive Accel: (%.1f/%.1f)", acceleration, maxDriveAcceleration);
}
break;

case X_TIMED_DRIVE:
case Y_TIMED_DRIVE:
if (!RobotParams.Preferences.noRobot)
{
robot.dashboard.displayPrintf(9, "Timed Drive: %.0f sec", testChoices.driveTime);
robot.dashboard.displayPrintf(10, "RobotPose=%s", robot.robotDrive.driveBase.getFieldPosition());
robot.dashboard.displayPrintf(1, "Timed Drive: %.0f sec", testChoices.driveTime);
robot.dashboard.displayPrintf(2, "RobotPose=%s", robot.robotDrive.driveBase.getFieldPosition());
robot.dashboard.displayPrintf(
11, "rawEnc=lf:%.0f,rf:%.0f,lb:%.0f,rb:%.0f",
3, "rawEnc=lf:%.0f,rf:%.0f,lb:%.0f,rb:%.0f",
robot.robotDrive.driveMotors[RobotDrive.INDEX_LEFT_FRONT].getPosition(),
robot.robotDrive.driveMotors[RobotDrive.INDEX_RIGHT_FRONT].getPosition(),
robot.robotDrive.driveMotors[RobotDrive.INDEX_LEFT_BACK].getPosition(),
Expand Down Expand Up @@ -457,13 +451,13 @@ public void periodic(double elapsedTime, boolean slowPeriodicLoop)
}

robot.dashboard.displayPrintf(
6, "RobotPose=%s,rawEnc=lf:%.0f,rf:%.0f,lb:%.0f,rb:%.0f",
1, "RobotPose=%s,rawEnc=lf:%.0f,rf:%.0f,lb:%.0f,rb:%.0f",
robot.robotDrive.driveBase.getFieldPosition(),
robot.robotDrive.driveMotors[RobotDrive.INDEX_LEFT_FRONT].getPosition(),
robot.robotDrive.driveMotors[RobotDrive.INDEX_RIGHT_FRONT].getPosition(),
robot.robotDrive.driveMotors[RobotDrive.INDEX_LEFT_BACK].getPosition(),
robot.robotDrive.driveMotors[RobotDrive.INDEX_RIGHT_BACK].getPosition());
int lineNum = 9;
int lineNum = 2;
if (xPidCtrl != null)
{
xPidCtrl.displayPidInfo(lineNum);
Expand Down Expand Up @@ -514,21 +508,21 @@ public void periodic(double elapsedTime, boolean slowPeriodicLoop)
swerveDrive.runSteeringCalibration();
if (swerveDrive.calibrationCount > 0)
{
robot.dashboard.displayPrintf(9, "Count = %d", swerveDrive.calibrationCount);
robot.dashboard.displayPrintf(1, "Count = %d", swerveDrive.calibrationCount);
robot.dashboard.displayPrintf(
10, "Encoder: lf=%.3f/%f",
2, "Encoder: lf=%.3f/%f",
swerveDrive.steerEncoders[SwerveDrive.INDEX_LEFT_FRONT].getRawPosition(),
swerveDrive.zeroPositions[SwerveDrive.INDEX_LEFT_FRONT]/swerveDrive.calibrationCount);
robot.dashboard.displayPrintf(
11, "Encoder: rf=%.3f/%f",
3, "Encoder: rf=%.3f/%f",
swerveDrive.steerEncoders[SwerveDrive.INDEX_RIGHT_FRONT].getRawPosition(),
swerveDrive.zeroPositions[SwerveDrive.INDEX_RIGHT_FRONT]/swerveDrive.calibrationCount);
robot.dashboard.displayPrintf(
12, "Encoder: lb=%.3f/%f",
4, "Encoder: lb=%.3f/%f",
swerveDrive.steerEncoders[SwerveDrive.INDEX_LEFT_BACK].getRawPosition(),
swerveDrive.zeroPositions[SwerveDrive.INDEX_LEFT_BACK]/swerveDrive.calibrationCount);
robot.dashboard.displayPrintf(
13, "Encoder: rb=%.3f/%f",
5, "Encoder: rb=%.3f/%f",
swerveDrive.steerEncoders[SwerveDrive.INDEX_RIGHT_BACK].getRawPosition(),
swerveDrive.zeroPositions[SwerveDrive.INDEX_RIGHT_BACK]/swerveDrive.calibrationCount);
}
Expand Down Expand Up @@ -810,7 +804,7 @@ public void operatorButtonEvent(TrcGameController gamepad, int button, boolean p
*/
private void updateColorThresholds()
{
robot.dashboard.displayPrintf(10, "Thresholds: %s", Arrays.toString(colorThresholds));
robot.dashboard.displayPrintf(8, "Thresholds: %s", Arrays.toString(colorThresholds));
} //updateColorThresholds

/**
Expand Down Expand Up @@ -1025,7 +1019,7 @@ private double getTuneKd()
*/
private void doSensorsTest()
{
int lineNum = 8;
int lineNum = 1;
//
// Read all sensors and display on the dashboard.
// Drive the robot around to sample different locations of the field.
Expand Down Expand Up @@ -1074,64 +1068,31 @@ private void doVisionTest()
{
if (robot.vision != null)
{
int lineNum = 9;
int lineNum = 1;

if (robot.vision.rawColorBlobVision != null)
{
TrcVisionTargetInfo<TrcOpenCvDetector.DetectedObject<?>> colorBlobInfo =
robot.vision.rawColorBlobVision.getBestDetectedTargetInfo(null, null, 0.0, 0.0);
robot.dashboard.displayPrintf(
lineNum++, "ColorBlob: %s", colorBlobInfo != null? colorBlobInfo: "Not found.");
robot.vision.getDetectedRawColorBlob(lineNum++);
}

if (robot.vision.aprilTagVision != null)
{
TrcVisionTargetInfo<FtcVisionAprilTag.DetectedObject> aprilTagInfo =
robot.vision.aprilTagVision.getBestDetectedTargetInfo(null);
robot.dashboard.displayPrintf(
lineNum++, "AprilTag: %s", aprilTagInfo != null? aprilTagInfo: "Not found.");
if (robot.blinkin != null)
{
robot.blinkin.setPatternState(BlinkinLEDs.APRIL_TAG, aprilTagInfo != null);
}
robot.vision.getDetectedAprilTag(null, lineNum++);
}

if (robot.vision.redBlobVision != null)
{
// TODO: figure out obj height and offset.
TrcVisionTargetInfo<TrcOpenCvColorBlobPipeline.DetectedObject> redBlobInfo =
robot.vision.redBlobVision.getBestDetectedTargetInfo(null, null, 0.0, 0.0);
robot.dashboard.displayPrintf(
lineNum++, "RedBlob: %s", redBlobInfo != null? redBlobInfo: "Not found.");
if (robot.blinkin != null)
{
robot.blinkin.setPatternState(BlinkinLEDs.RED_BLOB, redBlobInfo != null);
}
robot.vision.getDetectedRedBlob(lineNum++);
}

if (robot.vision.blueBlobVision != null)
{
// TODO: figure out obj height and offset.
TrcVisionTargetInfo<TrcOpenCvColorBlobPipeline.DetectedObject> blueBlobInfo =
robot.vision.blueBlobVision.getBestDetectedTargetInfo(null, null, 0.0, 0.0);
robot.dashboard.displayPrintf(
lineNum++, "BlueBlob: %s", blueBlobInfo != null? blueBlobInfo: "Not found.");
if (robot.blinkin != null)
{
robot.blinkin.setPatternState(BlinkinLEDs.BLUE_BLOB, blueBlobInfo != null);
}
robot.vision.getDetectedBlueBlob(lineNum++);
}

if (robot.vision.tensorFlowVision != null)
{
TrcVisionTargetInfo<FtcVisionTensorFlow.DetectedObject> tensorFlowInfo =
robot.vision.tensorFlowVision.getBestDetectedTargetInfo(null, null, null, 0.0, 0.0);
robot.dashboard.displayPrintf(
lineNum++, "TensorFlow: %s", tensorFlowInfo != null? tensorFlowInfo: "Not found.");
if (robot.blinkin != null)
{
robot.blinkin.setPatternState(BlinkinLEDs.TENSOR_FLOW, tensorFlowInfo != null);
}
robot.vision.getDetectedTensorFlowPixel(lineNum++);
}
}
} //doVisionTest
Expand Down
4 changes: 3 additions & 1 deletion TeamCode/src/main/java/teamcode/RobotParams.java
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ public static class Preferences
public static boolean useBatteryMonitor = false;
// Vision
public static boolean useWebCam = true;
public static boolean hasWebCam2 = false;
public static boolean useBuiltinCamBack = false;
public static boolean tuneColorBlobVision = false;
public static boolean useAprilTagVision = false;
Expand Down Expand Up @@ -78,7 +79,8 @@ public static class Preferences
//
// Miscellaneous.
public static final String HWNAME_IMU = "imu";
public static final String HWNAME_WEBCAM = "Webcam 1";
public static final String HWNAME_WEBCAM1 = "Webcam 1";
public static final String HWNAME_WEBCAM2 = "Webcam 2";
public static final String HWNAME_BLINKIN = "blinkin";
// Drive Base.
public static final String HWNAME_LFDRIVE_MOTOR = "lfDriveMotor";
Expand Down
10 changes: 10 additions & 0 deletions TeamCode/src/main/java/teamcode/subsystems/BlinkinLEDs.java
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,16 @@ public BlinkinLEDs(String instanceName)
setPatternPriorities(ledPatternPriorities);
} //BlinkinLEDs

/**
* This method sets the pattern ON for a period of time and turns off automatically afterwards.
*
* @param patternName specifies the name of the LED pattern to turn on.
*/
public void setDetectedPattern(String patternName)
{
setPatternState(patternName, true, 0.5);
} //setDetectedPattern

/**
* This method sets the LED to indicate the drive orientation mode of the robot.
*
Expand Down
Loading

0 comments on commit b709129

Please sign in to comment.