Skip to content

Commit

Permalink
temp
Browse files Browse the repository at this point in the history
  • Loading branch information
keckothedragon committed May 9, 2024
1 parent d0f4632 commit 56330b5
Show file tree
Hide file tree
Showing 6 changed files with 126 additions and 0 deletions.
4 changes: 4 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,10 @@ public static final class ShooterConstants {
new Constraints(kFlywheelVelocity, kFlywheelAcceleration));
}

public static final class IntakeConstants {
public static final double kPivotGearRatio = 36.0 / 16;
}

public static final class Ports {
public static final int kShooterPivotLeader = 0;
public static final int kShooterPivotFollower = 0;
Expand Down
16 changes: 16 additions & 0 deletions src/main/java/frc/robot/subsystems/intake/pivot/IntakePivotIO.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
package frc.robot.subsystems.intake.pivot;

import edu.wpi.first.math.geometry.Rotation2d;

public interface IntakePivotIO {
public static class IntakePivotInputs {
public double curAngle;
public double[] curVelocity;
public double[] curVoltage;
public double[] curAmps;
}

public void setVoltage(double voltage);

public Rotation2d getCurrentAngle();
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
package frc.robot.subsystems.intake.pivot;

import com.revrobotics.AbsoluteEncoder;
import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder;

import frc.robot.Constants.IntakeConstants;

public class IntakePivotIONeo implements IntakePivotIO {
private CANSparkMax m_motor;
private AbsoluteEncoder m_encoder;

public IntakePivotIONeo(int port) {
m_motor = new CANSparkMax(port, CANSparkMax.MotorType.kBrushless);
m_encoder = m_motor.getAbsoluteEncoder();
m_encoder.setPositionConversionFactor(IntakeConstants.kPivotGearRatio);
}
}
16 changes: 16 additions & 0 deletions src/main/java/frc/robot/subsystems/intake/roller/RollerIO.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
package frc.robot.subsystems.intake.roller;

import org.littletonrobotics.junction.AutoLog;

import frc.lib.advantagekit.LoggedIO;

public interface RollerIO extends LoggedIO<RollerIO.RollerInputs> {
@AutoLog
public static class RollerInputs {
public double curVelocity;
public double curVoltage;
public double curAmps;
}

public void setVoltage(double voltage);
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
package frc.robot.subsystems.intake.roller;

import com.ctre.phoenix6.BaseStatusSignal;
import com.ctre.phoenix6.StatusSignal;
import com.ctre.phoenix6.hardware.TalonFX;

import edu.wpi.first.math.util.Units;

public class RollerIOKraken implements RollerIO {
private TalonFX m_motor;
private StatusSignal<Double> m_voltageSignal;
private StatusSignal<Double> m_currentSignal;
private StatusSignal<Double> m_velocitySignal;

public RollerIOKraken(int port) {
m_motor = new TalonFX(port);
m_voltageSignal = m_motor.getMotorVoltage();
m_currentSignal = m_motor.getSupplyCurrent();
m_velocitySignal = m_motor.getVelocity();
}

@Override
public void updateInputs(RollerInputs inputs) {
BaseStatusSignal.refreshAll(
m_voltageSignal,
m_currentSignal,
m_velocitySignal
);

inputs.curVoltage = m_voltageSignal.getValueAsDouble();
inputs.curAmps = m_currentSignal.getValueAsDouble();
inputs.curVelocity = Units.rotationsToRadians(m_velocitySignal.getValueAsDouble());
}

@Override
public void setVoltage(double voltage) {
m_motor.setVoltage(voltage);
}
}
33 changes: 33 additions & 0 deletions src/main/java/frc/robot/subsystems/intake/roller/RollerIOSim.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
package frc.robot.subsystems.intake.roller;

import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.wpilibj.simulation.DCMotorSim;

public class RollerIOSim implements RollerIO {
private DCMotorSim m_sim;
private double m_voltage;

public RollerIOSim() {
m_sim = new DCMotorSim(
DCMotor.getKrakenX60(1),
3,
1
);
m_voltage = 0.0;
}

@Override
public void updateInputs(RollerInputs inputs) {
m_sim.update(0.02);

inputs.curVoltage = m_voltage;
inputs.curAmps = m_sim.getCurrentDrawAmps();
inputs.curVelocity = m_sim.getAngularVelocityRadPerSec();
}

@Override
public void setVoltage(double voltage) {
m_sim.setInputVoltage(voltage);
m_voltage = voltage;
}
}

0 comments on commit 56330b5

Please sign in to comment.