Skip to content

Commit

Permalink
Updated to 2025.1.1-2, other fixes
Browse files Browse the repository at this point in the history
Fixed Spelling mistakes & driving logic errors
  • Loading branch information
rechsby committed Dec 9, 2024
1 parent 28779e4 commit a1b64a3
Show file tree
Hide file tree
Showing 5 changed files with 14 additions and 11 deletions.
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-2"
}

java {
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Constants/GlobalConstants.java
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.robot.constants;
package frc.robot.Constants;

public class GlobalConstants {

Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Constants/TunerConstants.java
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.robot.constants;
package frc.robot.Constants;

import static edu.wpi.first.units.Units.*;

Expand Down
17 changes: 10 additions & 7 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,9 @@
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction;
import frc.lib.controller.LogitechController;
import frc.lib.controller.ThrustmasterJoystick;
import frc.robot.constants.GlobalConstants;
import frc.robot.constants.TunerConstants;
import frc.robot.constants.GlobalConstants.ControllerConstants;
import frc.robot.Constants.GlobalConstants;
import frc.robot.Constants.TunerConstants;
import frc.robot.Constants.GlobalConstants.ControllerConstants;
import frc.robot.subsystems.CommandSwerveDrivetrain;

public class RobotContainer {
Expand Down Expand Up @@ -58,13 +58,16 @@ private void configureBindings() {
drivetrain.setDefaultCommand(
// Drivetrain will execute this command periodically
drivetrain.applyRequest(() ->
drive.driveRobotRelative(-leftDriveController.getYAxis().get() * GlobalConstants.MAX_TRANSLATIONAL_SPEED, -leftDriveController.getXAxis().get() * GlobalConstants.MAX_TRANSLATIONAL_SPEED, -rightDriveController.getXAxis().get() * GlobalConstants.MAX_ROTATIONAL_SPEED);
// drive.withVelocityX(-leftDriveController.getYAxis().get() * GlobalConstants.MAX_TRANSLATIONAL_SPEED) // Drive forward with negative Y (forward)
// .withVelocityY(-leftDriveController.getXAxis().get() * GlobalConstants.MAX_TRANSLATIONAL_SPEED) // Drive left with negative X (left)
// .withRotationalRate(-rightDriveController.getXAxis().get() * GlobalConstants.MAX_ROTATIONAL_SPEED) // Drive counterclockwise with negative X (left)
drive.withVelocityX(leftDriveController.getYAxis().get() * GlobalConstants.MAX_TRANSLATIONAL_SPEED)
.withVelocityY(-leftDriveController.getXAxis().get() * GlobalConstants.MAX_TRANSLATIONAL_SPEED)
.withRotationalRate(rightDriveController.getXAxis().get() * GlobalConstants.MAX_ROTATIONAL_SPEED)
)
);

// drive.withVelocityX(-leftDriveController.getYAxis().get() * GlobalConstants.MAX_TRANSLATIONAL_SPEED) // Drive forward with negative Y (forward)
// .withVelocityY(-leftDriveController.getXAxis().get() * GlobalConstants.MAX_TRANSLATIONAL_SPEED) // Drive left with negative X (left)
// .withRotationalRate(-rightDriveController.getXAxis().get() * GlobalConstants.MAX_ROTATIONAL_SPEED) // Drive counterclockwise with negative X (left)

operatorController.getA().whileTrue(drivetrain.applyRequest(() -> brake));
operatorController.getB().whileTrue(drivetrain.applyRequest(() ->
point.withModuleDirection(new Rotation2d(-operatorController.getLeftYAxis().get(), -operatorController.getLeftXAxis().get()))
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -235,7 +235,7 @@ public SwerveRequest driveRobotRelative(ChassisSpeeds speeds) {
public SwerveRequest driveRobotRelative(double xVelocity, double yVelocity, double rotationRate) {
// Note: it is important to not discretize speeds before or after
// using the setpoint generator, as it will discretize them for you
new ChassisSpeeds speeds = ChassisSpeeds(xVelocity, yVelocity, rotationRate);
ChassisSpeeds speeds = new ChassisSpeeds(xVelocity, yVelocity, rotationRate);
previousSetpoint = setpointGenerator.generateSetpoint(
previousSetpoint, // The previous setpoint
speeds, // The desired target speeds
Expand Down

0 comments on commit a1b64a3

Please sign in to comment.