Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions src/main/deploy/constants/comp/DrivetrainConstants.json
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
"allowLineupFinishWithCachedObservation": true,
"otfPoseDistanceLimit": 0.5,
"otfFarWarmupDistance": 2.5,
"otfTeleopFarWarmupDistance": 2.0,
"otfWarmupDistance": 1.5,
"otfVisionAlongTrackThreshold": 0.3,
"otfVisionCrossTrackThreshold": 0.25,
Expand Down Expand Up @@ -354,6 +355,10 @@
"OTFMaxLinearAccel": 4.0,
"OTFMaxAngularVelocity": 3.141592653589793,
"OTFMaxAngularAccel": 1.5707963267948966,
"TeleopOTFMaxLinearVelocity": 3.5,
"TeleopOTFMaxLinearAccel": 2.0,
"TeleopOTFMaxAngularVelocity": 3.141592653589793,
"TeleopOTFMaxAngularAccel": 1.5707963267948966,
"DrivetrainConstants": {
"CANBusName": "canivore",
"Pigeon2Id": 13
Expand Down
12 changes: 6 additions & 6 deletions src/main/java/frc/robot/BuildConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,12 +5,12 @@ public final class BuildConstants {
public static final String MAVEN_GROUP = "";
public static final String MAVEN_NAME = "2025-Robot-Code";
public static final String VERSION = "unspecified";
public static final int GIT_REVISION = 65;
public static final String GIT_SHA = "ea2a1e73b3ff08497493d4ab43e657f2294c19a4";
public static final String GIT_DATE = "2025-03-15 17:48:52 EDT";
public static final String GIT_BRANCH = "main";
public static final String BUILD_DATE = "2025-03-15 18:26:38 EDT";
public static final long BUILD_UNIX_TIME = 1742077598364L;
public static final int GIT_REVISION = 63;
public static final String GIT_SHA = "682e8efd7ca411c368a84c3ae2a7b7acce1aa707";
public static final String GIT_DATE = "2025-03-15 10:59:11 EDT";
public static final String GIT_BRANCH = "otf-teleop-slowdown";
public static final String BUILD_DATE = "2025-03-16 09:29:04 EDT";
public static final long BUILD_UNIX_TIME = 1742131744476L;
public static final int DIRTY = 1;

private BuildConstants() {}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -119,6 +119,7 @@ public class DrivetrainConstants {
public final Double otfVisionCrossTrackThreshold = 0.5;

public final Double otfFarWarmupDistance = 2.5;
public final Double otfTeleopFarWarmupDistance = 2.0;

public final Double otfWarmupDistance = 1.5;

Expand Down Expand Up @@ -185,6 +186,12 @@ public class DrivetrainConstants {
public final Double OTFMaxAngularVelocity = Math.PI;
public final Double OTFMaxAngularAccel = Math.PI / 2;

// OTF Max speed / accel
public final Double TeleopOTFMaxLinearVelocity = 3.5;
public final Double TeleopOTFMaxLinearAccel = 2.0;
public final Double TeleopOTFMaxAngularVelocity = Math.PI;
public final Double TeleopOTFMaxAngularAccel = Math.PI / 2;

// These are only used for simulation
@JSONExclude public final MomentOfInertia kSteerInertia = KilogramSquareMeters.of(0.01);
@JSONExclude public final MomentOfInertia kDriveInertia = KilogramSquareMeters.of(0.01);
Expand Down
13 changes: 9 additions & 4 deletions src/main/java/frc/robot/subsystems/drive/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -616,10 +616,15 @@ public boolean isDriveCloseToFinalLineupPose() {

@AutoLogOutput(key = "Drive/OTF/isDriveCloseForFarWarmup")
public boolean isDriveCloseForFarWarmup() {
return this.getPose()
.getTranslation()
.getDistance(OTFState.findOTFPoseFromDesiredLocation(this).getTranslation())
< JsonConstants.drivetrainConstants.otfFarWarmupDistance;
return (DriverStation.isAutonomous()
&& this.getPose()
.getTranslation()
.getDistance(OTFState.findOTFPoseFromDesiredLocation(this).getTranslation())
< JsonConstants.drivetrainConstants.otfFarWarmupDistance)
|| this.getPose()
.getTranslation()
.getDistance(OTFState.findOTFPoseFromDesiredLocation(this).getTranslation())
< JsonConstants.drivetrainConstants.otfTeleopFarWarmupDistance;
}

public boolean isDriveCloseForWarmup() {
Expand Down
14 changes: 13 additions & 1 deletion src/main/java/frc/robot/subsystems/drive/states/OTFState.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
import coppercore.controls.state_machine.state.PeriodicStateInterface;
import coppercore.controls.state_machine.transition.Transition;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.constants.JsonConstants;
import frc.robot.subsystems.drive.Drive;
Expand Down Expand Up @@ -208,6 +209,15 @@ public Command getDriveToPoseCommand() {
JsonConstants.drivetrainConstants.OTFMaxAngularAccel);
}

if (DriverStation.isTeleop()) {
constraints =
new PathConstraints(
JsonConstants.drivetrainConstants.TeleopOTFMaxLinearVelocity,
JsonConstants.drivetrainConstants.TeleopOTFMaxLinearAccel,
JsonConstants.drivetrainConstants.TeleopOTFMaxAngularVelocity,
JsonConstants.drivetrainConstants.TeleopOTFMaxAngularAccel);
}

return AutoBuilder.pathfindToPose(
otfPose,
constraints,
Expand All @@ -228,7 +238,9 @@ public void periodic() {

if (drive.isDriveCloseForWarmup() && ScoringSubsystem.getInstance() != null) {
ScoringSubsystem.getInstance().fireTrigger(ScoringTrigger.StartWarmup);
} else if (drive.isDriveCloseForFarWarmup() && ScoringSubsystem.getInstance() != null) {
} else if (drive.isDriveCloseForFarWarmup()
&& ScoringSubsystem.getInstance() != null
&& DriverStation.isAutonomous()) {
ScoringSubsystem.getInstance().fireTrigger(ScoringTrigger.StartFarWarmup);
}

Expand Down
Loading