Skip to content

Commit

Permalink
testing changes 3/4 (small stuff no big)
Browse files Browse the repository at this point in the history
  • Loading branch information
shinthebinn committed Mar 5, 2024
1 parent ff51051 commit 6a4dec5
Show file tree
Hide file tree
Showing 5 changed files with 13 additions and 14 deletions.
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -216,10 +216,10 @@ private void configureBindings() {

testController.rightBumper()
.whileTrue(Commands
.runEnd(() -> intake.setMotorVoltage(intakeSpeedEntry.getDouble(0) * 12), () -> intake.stopMotor(), intake)
.runEnd(() -> intake.setMotorSpeed(intakeSpeedEntry.getDouble(0)), () -> intake.stopMotor(), intake)
.until(() -> intake.inputs.noteSensor).unless(() -> intake.inputs.noteSensor));
testController.leftBumper().whileTrue(
new StartEndCommand(() -> intake.setMotorVoltage(indexSpeedEntry.getDouble(0) * 12), () -> intake.stopMotor(),
new StartEndCommand(() -> intake.setMotorSpeed(indexSpeedEntry.getDouble(0)), () -> intake.stopMotor(),
intake));

testController.rightStick().whileTrue(new ManualArmControl(arm, testController::getLeftY));
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/constants/ArmConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,9 @@ public final class ArmConstants {
public static final double shaftEncoderOffset_deg = 4.22; // needs to be tuned

// pid
public static final double kP = .000090;
public static final double kP = .000095;
public static final double kI = 0;
public static final double kD = .0000016;
public static final double kD = .00000165;

public static final double maxOutput = .5;
public static final double minOutput = -maxOutput;
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/constants/IntakeConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,5 +5,5 @@ public class IntakeConstants {
public static final int sensorId = 0;

public static final double intakeSpeed = 0.95;
public static final double indexSpeed = 0.75;
public static final double indexSpeed = 0.85;
}
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/constants/SwerveConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,10 @@
public final class SwerveConstants {
// FL, FR, BL, BR (matches AdvantageScope convention)
public static final SwerveModuleConstants moduleConstants[] = {
new SwerveModuleConstants(21, 22, .697),
new SwerveModuleConstants(23, 24, 1.883),
new SwerveModuleConstants(25, 26, 6.27),
new SwerveModuleConstants(27, 28, 2.891)
new SwerveModuleConstants(21, 22, .691),
new SwerveModuleConstants(23, 24, 1.836),
new SwerveModuleConstants(25, 26, 3.788),
new SwerveModuleConstants(27, 28, 2.859)
};

// the left-to-right distance between the drivetrain wheels, should be measured from center to center
Expand Down
9 changes: 4 additions & 5 deletions src/main/java/frc/robot/subsystems/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

import static frc.robot.constants.IntakeConstants.*;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

Expand All @@ -19,6 +20,7 @@ public class Intake extends SubsystemBase {

public Intake() {
motor.setIdleMode(IdleMode.kBrake);
motor.enableVoltageCompensation(12);
}

@Override
Expand All @@ -28,11 +30,8 @@ public void periodic() {
}

public void setMotorSpeed(double speed) {
motor.set(speed);
}

public void setMotorVoltage(double voltage_V) {
motor.setVoltage(voltage_V);
speed = MathUtil.clamp(speed, -1, 1);
motor.setVoltage(speed * 12);
}

@AutoLog
Expand Down

0 comments on commit 6a4dec5

Please sign in to comment.