Reorganized and cleaned up.

This commit is contained in:
Titan Robotics Club
2024-08-22 14:08:59 -07:00
parent 4b471601b8
commit 6fef9c6018
2 changed files with 48 additions and 33 deletions

View File

@ -48,6 +48,7 @@ public class FtcTeleOp extends FtcOpMode
protected FtcGamepad operatorGamepad; protected FtcGamepad operatorGamepad;
private double drivePowerScale; private double drivePowerScale;
private double turnPowerScale; private double turnPowerScale;
private boolean driverAltFunc = false;
private boolean operatorAltFunc = false; private boolean operatorAltFunc = false;
private boolean relocalizing = false; private boolean relocalizing = false;
private TrcPose2D robotFieldPose = null; private TrcPose2D robotFieldPose = null;
@ -248,6 +249,10 @@ public class FtcTeleOp extends FtcOpMode
switch (button) switch (button)
{ {
case A: case A:
case B:
break;
case X:
if (pressed) if (pressed)
{ {
robot.globalTracer.traceInfo(moduleName, ">>>>> CancelAll is pressed."); robot.globalTracer.traceInfo(moduleName, ">>>>> CancelAll is pressed.");
@ -259,11 +264,10 @@ public class FtcTeleOp extends FtcOpMode
} }
break; break;
case B:
case X:
break;
case Y: case Y:
// Toggle between field or robot oriented driving, only applicable for holonomic drive base.
if (driverAltFunc)
{
if (pressed && robot.robotDrive != null) if (pressed && robot.robotDrive != null)
{ {
if (robot.robotDrive.driveBase.isGyroAssistEnabled()) if (robot.robotDrive.driveBase.isGyroAssistEnabled())
@ -279,10 +283,9 @@ public class FtcTeleOp extends FtcOpMode
robot.robotDrive.driveBase.setGyroAssistEnabled(robot.robotDrive.pidDrive.getTurnPidCtrl()); robot.robotDrive.driveBase.setGyroAssistEnabled(robot.robotDrive.pidDrive.getTurnPidCtrl());
} }
} }
break; }
else
case LeftBumper: {
// Toggle between field or robot oriented driving, only applicable for holonomic drive base.
if (pressed && robot.robotDrive != null && robot.robotDrive.driveBase.supportsHolonomicDrive()) if (pressed && robot.robotDrive != null && robot.robotDrive.driveBase.supportsHolonomicDrive())
{ {
if (robot.robotDrive.driveBase.getDriveOrientation() != TrcDriveBase.DriveOrientation.FIELD) if (robot.robotDrive.driveBase.getDriveOrientation() != TrcDriveBase.DriveOrientation.FIELD)
@ -296,6 +299,12 @@ public class FtcTeleOp extends FtcOpMode
setDriveOrientation(TrcDriveBase.DriveOrientation.ROBOT); setDriveOrientation(TrcDriveBase.DriveOrientation.ROBOT);
} }
} }
}
break;
case LeftBumper:
robot.globalTracer.traceInfo(moduleName, ">>>>> DriverAltFunc=" + pressed);
driverAltFunc = pressed;
break; break;
case RightBumper: case RightBumper:
@ -321,12 +330,17 @@ public class FtcTeleOp extends FtcOpMode
break; break;
case Back: case Back:
if (pressed && robot.robotDrive != null && robot.robotDrive instanceof FtcSwerveDrive) if (pressed)
{
robot.globalTracer.traceInfo(moduleName, ">>>>> ZeroCalibrate pressed.");
robot.zeroCalibrate();
if (robot.robotDrive != null && robot.robotDrive instanceof FtcSwerveDrive)
{ {
// Drive base is a Swerve Drive, align all steering wheels forward. // Drive base is a Swerve Drive, align all steering wheels forward.
robot.globalTracer.traceInfo(moduleName, ">>>>> Set SteerAngle to zero."); robot.globalTracer.traceInfo(moduleName, ">>>>> Set SteerAngle to zero.");
((FtcSwerveDrive) robot.robotDrive).setSteerAngle(0.0, false, false); ((FtcSwerveDrive) robot.robotDrive).setSteerAngle(0.0, false, false);
} }
}
break; break;
case Start: case Start:
@ -371,14 +385,14 @@ public class FtcTeleOp extends FtcOpMode
case B: case B:
case X: case X:
case Y: case Y:
case LeftBumper:
break; break;
case RightBumper: case LeftBumper:
robot.globalTracer.traceInfo(moduleName, ">>>>> OperatorAltFunc=" + pressed); robot.globalTracer.traceInfo(moduleName, ">>>>> OperatorAltFunc=" + pressed);
operatorAltFunc = pressed; operatorAltFunc = pressed;
break; break;
case RightBumper:
case DpadUp: case DpadUp:
case DpadDown: case DpadDown:
case DpadLeft: case DpadLeft:

View File

@ -137,6 +137,7 @@ public class RobotParams
public static final boolean useTensorFlowVision = false; public static final boolean useTensorFlowVision = false;
public static final boolean showVisionView = !inCompetition; public static final boolean showVisionView = !inCompetition;
public static final boolean showVisionStat = false; public static final boolean showVisionStat = false;
public static final boolean showSubsystems = true;
// Drive Base // Drive Base
public static final boolean useDriveBase = false; public static final boolean useDriveBase = false;
public static final boolean useExternalOdometry = false; public static final boolean useExternalOdometry = false;