4 Commits

3 changed files with 43 additions and 2 deletions

View File

@@ -46,10 +46,20 @@ public class RobotContainer {
driver::getLeftY,
driver::getLeftX,
driver::getRightX,
() -> true
() -> false
)
);
driver.start().and(driver.x()).whileTrue(drivetrain.runFrontLeft(1, 0));
driver.start().and(driver.y()).whileTrue(drivetrain.runFrontRight(1, 0));
driver.start().and(driver.a()).whileTrue(drivetrain.runRearLeft(1, 0));
driver.start().and(driver.b()).whileTrue(drivetrain.runRearRight(1, 0));
driver.start().negate().and(driver.x()).whileTrue(drivetrain.runFrontLeft(0, 45));
driver.start().negate().and(driver.y()).whileTrue(drivetrain.runFrontRight(0, 45));
driver.start().negate().and(driver.a()).whileTrue(drivetrain.runRearLeft(0, 45));
driver.start().negate().and(driver.b()).whileTrue(drivetrain.runRearRight(0, 45));
driver.rightBumper().whileTrue(drivetrain.setX());
//drivetrain.setDefaultCommand(drivetrain.disableOutputs());
configureShiftDisplay();

View File

@@ -90,7 +90,8 @@ public class ModuleConstants {
turningConfig
.idleMode(kTurnIdleMode)
.smartCurrentLimit(kTurnMotorCurrentLimit);
.smartCurrentLimit(kTurnMotorCurrentLimit)
.inverted(true);
turningConfig.encoder
//.inverted(true)
.positionConversionFactor(kTurningFactor)
@@ -101,5 +102,6 @@ public class ModuleConstants {
.outputRange(-1, 1)
.positionWrappingEnabled(true)
.positionWrappingInputRange(0, 2 * Math.PI);
}
}

View File

@@ -134,6 +134,35 @@ public class Drivetrain extends SubsystemBase {
Logger.recordOutput("Drivetrain/Heading", getHeading());
}
public Command runFrontLeft(double staticSpeed, double staticAngleDegrees) {
return run(() -> {
frontLeft.setDesiredState(new SwerveModuleState(
staticSpeed,
Rotation2d.fromDegrees(staticAngleDegrees)));
});
}
public Command runFrontRight(double staticSpeed, double staticAngleDegrees) {
return run(() -> {
frontRight.setDesiredState(new SwerveModuleState(
staticSpeed,
Rotation2d.fromDegrees(staticAngleDegrees)));
});
}
public Command runRearLeft(double staticSpeed, double staticAngleDegrees) {
return run(() -> {
rearLeft.setDesiredState(new SwerveModuleState(
staticSpeed,
Rotation2d.fromDegrees(staticAngleDegrees)));
});
}
public Command runRearRight(double staticSpeed, double staticAngleDegrees) {
return run(() -> {
rearRight.setDesiredState(new SwerveModuleState(
staticSpeed,
Rotation2d.fromDegrees(staticAngleDegrees)));
});
}
public Command disableOutputs() {
return run(() -> {
frontLeft.disableOutput();