⚠ This page is served via a proxy. Original site: https://github.com
This service does not collect credentials or authentication data.
Skip to content
3 changes: 1 addition & 2 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,6 @@
import frc.robot.subsystems.intake.Intake;
import frc.robot.subsystems.intake.IntakeRollerIO;
import frc.robot.subsystems.intake.IntakeRollerIOSim;
import frc.robot.subsystems.intake.IntakeRollerIOTalonFX;
import frc.robot.subsystems.launcher.FlywheelIO;
import frc.robot.subsystems.launcher.FlywheelIOSim;
import frc.robot.subsystems.launcher.HoodIO;
Expand Down Expand Up @@ -132,7 +131,7 @@ public Robot() {
new TurretIOSpark(),
new FlywheelIOSim(),
new HoodIOSimHardwareless());
intake = new Intake(new IntakeRollerIOTalonFX());
intake = new Intake(new IntakeRollerIO() {});
feeder = new Feeder(new SpindexerIO() {}, new KickerIO() {});
break;

Expand Down
5 changes: 4 additions & 1 deletion src/main/java/frc/robot/subsystems/drive/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,7 @@ public class Drive extends SubsystemBase {
private final SwerveModuleState[] emptyModuleStates = new SwerveModuleState[] {};
private SwerveModulePosition[] modulePositions = new SwerveModulePosition[4];
private SwerveModulePosition[] moduleDeltas = new SwerveModulePosition[4];
private ChassisSpeeds chassisSpeeds;

// PID controllers for following Choreo trajectories
private final PIDController xController = new PIDController(5.0, 0.0, 0.0);
Expand Down Expand Up @@ -201,6 +202,8 @@ public void periodic() {

// Apply update
visionPose.updateWithTime(sampleTimestamps[i], rawGyroRotation, modulePositions);

chassisSpeeds = kinematics.toChassisSpeeds(getModuleStates());
}

// Update gyro alert
Expand Down Expand Up @@ -307,7 +310,7 @@ private SwerveModulePosition[] getModulePositions() {
/** Returns the measured chassis speeds of the robot. */
@AutoLogOutput(key = "SwerveChassisSpeeds/Measured")
public ChassisSpeeds getRobotRelativeChassisSpeeds() {
return kinematics.toChassisSpeeds(getModuleStates());
return chassisSpeeds;
}

/** Returns the position of each module in radians. */
Expand Down
9 changes: 2 additions & 7 deletions src/main/java/frc/robot/subsystems/launcher/HoodIOSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -51,12 +51,7 @@ public HoodIOSim() {
.velocityConversionFactor(encoderVelocityFactor)
.averageDepth(2);

hoodConfig
.closedLoop
.feedbackSensor(FeedbackSensor.kAbsoluteEncoder)
.positionWrappingEnabled(true)
.positionWrappingInputRange(minInput, maxInput)
.pid(kPSim, 0.0, kDSim);
hoodConfig.closedLoop.feedbackSensor(FeedbackSensor.kAbsoluteEncoder).pid(kPSim, 0.0, kDSim);

hoodConfig
.signals
Expand Down Expand Up @@ -100,7 +95,7 @@ public void setOpenLoop(double output) {

@Override
public void setPosition(Rotation2d rotation, AngularVelocity angularVelocity) {
double setpoint = MathUtil.inputModulus(rotation.getRadians(), minInput, maxInput);
double setpoint = MathUtil.inputModulus(rotation.getRadians(), 0.0, 2.0 * Math.PI);
double feedforwardVolts =
RobotConstants.kNominalVoltage
* angularVelocity.in(RadiansPerSecond)
Expand Down
9 changes: 2 additions & 7 deletions src/main/java/frc/robot/subsystems/launcher/HoodIOSpark.java
Original file line number Diff line number Diff line change
Expand Up @@ -53,12 +53,7 @@ public HoodIOSpark() {
.velocityConversionFactor(encoderVelocityFactor)
.averageDepth(2);

hoodConfig
.closedLoop
.feedbackSensor(FeedbackSensor.kAbsoluteEncoder)
.positionWrappingEnabled(true)
.positionWrappingInputRange(minInput, maxInput)
.pid(kPReal, 0.0, 0.0);
hoodConfig.closedLoop.feedbackSensor(FeedbackSensor.kAbsoluteEncoder).pid(kPReal, 0.0, 0.0);

hoodConfig
.signals
Expand Down Expand Up @@ -98,7 +93,7 @@ public void setOpenLoop(double output) {

@Override
public void setPosition(Rotation2d rotation, AngularVelocity angularVelocity) {
double setpoint = MathUtil.inputModulus(rotation.getRadians(), minInput, maxInput);
double setpoint = MathUtil.inputModulus(rotation.getRadians(), 0.0, 2.0 * Math.PI);
double feedforwardVolts =
RobotConstants.kNominalVoltage
* angularVelocity.in(RadiansPerSecond)
Expand Down
Loading