Skip to content

Commit

Permalink
IntakeAdvantageKit
Browse files Browse the repository at this point in the history
  • Loading branch information
Ishan1522 committed Jan 13, 2025
1 parent fd73d50 commit 82683cf
Show file tree
Hide file tree
Showing 7 changed files with 82 additions and 29 deletions.
27 changes: 14 additions & 13 deletions build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@

plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2025.1.1"
id "edu.wpi.first.GradleRIO" version "2025.2.1"
id "com.peterabeles.gversion" version "1.10"
id "com.diffplug.spotless" version "6.25.0"
id "pmd"
Expand Down Expand Up @@ -66,16 +67,16 @@ wpi.java.debugJni = false
def includeDesktopSupport = true

// Configuration for AdvantageKit
// repositories {
// maven {
// url = uri("https://maven.pkg.github.com/Mechanical-Advantage/AdvantageKit")
// credentials {
// username = "Mechanical-Advantage-Bot"
// password = "\u0067\u0068\u0070\u005f\u006e\u0056\u0051\u006a\u0055\u004f\u004c\u0061\u0079\u0066\u006e\u0078\u006e\u0037\u0051\u0049\u0054\u0042\u0032\u004c\u004a\u006d\u0055\u0070\u0073\u0031\u006d\u0037\u004c\u005a\u0030\u0076\u0062\u0070\u0063\u0051"
// }
// }
// mavenLocal()
// }
repositories {
maven {
url = uri("https://maven.pkg.github.com/Mechanical-Advantage/AdvantageKit")
credentials {
username = "Mechanical-Advantage-Bot"
password = "\u0067\u0068\u0070\u005f\u006e\u0056\u0051\u006a\u0055\u004f\u004c\u0061\u0079\u0066\u006e\u0078\u006e\u0037\u0051\u0049\u0054\u0042\u0032\u004c\u004a\u006d\u0055\u0070\u0073\u0031\u006d\u0037\u004c\u005a\u0030\u0076\u0062\u0070\u0063\u0051"
}
}
mavenLocal()
}

// task(replayWatch, type: JavaExec) {
// mainClass = "org.littletonrobotics.junction.ReplayWatch"
Expand Down Expand Up @@ -108,8 +109,8 @@ dependencies {
testImplementation 'org.junit.jupiter:junit-jupiter:5.10.1'
testRuntimeOnly 'org.junit.platform:junit-platform-launcher'

// def akitJson = new groovy.json.JsonSlurper().parseText(new File(projectDir.getAbsolutePath() + "/vendordeps/AdvantageKit.json").text)
// annotationProcessor "org.littletonrobotics.akit:akit-autolog:$akitJson.version"
def akitJson = new groovy.json.JsonSlurper().parseText(new File(projectDir.getAbsolutePath() + "/vendordeps/AdvantageKit.json").text)
annotationProcessor "org.littletonrobotics.akit:akit-autolog:$akitJson.version"
}

test {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
package frc.robot.subsystems.intake;

public final class IntakeConstants {

public static final int intakeMotorID = 0;
}
Original file line number Diff line number Diff line change
Expand Up @@ -6,17 +6,17 @@ public interface IntakeInterface {
@AutoLog
public static class IntakeInputs {
public boolean isConnected = true;
public double intakeSpeed = 0.0;
public double intakeVelocity = 0.0;
public double intakeTemp = 0.0;
public double appliedVolts = 0.0;
public double currentAmps = 0.0;
}

default void updateInputs(IntakeInputs inputs){}

default void setSpeed(double speed){}
default void setIntakeSpeed(double speed){}

default double getSpeed(){
default double getIntakeSpeed(){
return 0.0;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -7,20 +7,18 @@
import org.littletonrobotics.junction.Logger;

import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.subsystems.intake.IntakeInterface.IntakeInputs;

public class IntakeSubsystem extends SubsystemBase {
private IntakeInterface intakeInterface;
private IntakeInputs inputs = new IntakeInputs();
private IntakeInputsAutoLogged inputs = new IntakeInputsAutoLogged();

public IntakeSubsystem(IntakeInterface intakeInterface) {
this.intakeInterface = intakeInterface;
}

public void setSpeed(double speed){
intakeInterface.setSpeed(speed);
public void setIntakeSpeed(double speed) {
intakeInterface.setIntakeSpeed(speed);
}

@Override
public void periodic(){
intakeInterface.updateInputs(inputs);
Expand Down
32 changes: 29 additions & 3 deletions src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,16 +4,42 @@
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;

import edu.wpi.first.units.measure.AngularVelocity;
import frc.robot.Constants.HardwareConstants;

public class PhysicalIntake implements IntakeInterface{
private final TalonFX motor = new TalonFX(0);
private final StatusSignal<AngularVelocity> intakeSpeed;
private final TalonFX motor = new TalonFX(IntakeConstants.intakeMotorID);
private final StatusSignal<AngularVelocity> intakeVelocity = motor.getVelocity();
private final TalonFXConfiguration intakeConfig = new TalonFXConfiguration();

public PhysicalIntake(){
intakeConfig.MotorOutput.Inverted = InvertedValue.CounterClockwise_Positive;

intakeConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake;
intakeConfig.MotorOutput.DutyCycleNeutralDeadband = HardwareConstants.MIN_FALCON_DEADBAND;

intakeConfig.CurrentLimits.StatorCurrentLimit = 0.0;
intakeConfig.CurrentLimits.StatorCurrentLimitEnable = true;
intakeConfig.CurrentLimits.SupplyCurrentLimit = 0.0;
intakeConfig.CurrentLimits.StatorCurrentLimitEnable = true;

motor.getConfigurator().apply(intakeConfig);
}

@Override
public void updateInputs(IntakeInputs intakeInputs){
intakeInputs.intakeVelocity = intakeVelocity.getValueAsDouble();
}

@Override
public void setIntakeSpeed(double speed){
motor.set(speed);
}

@Override
public double getIntakeSpeed(){
motor.getVelocity().refresh();
return motor.getVelocity().getValueAsDouble();
}
}
32 changes: 32 additions & 0 deletions src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
package frc.robot.subsystems.intake;

import static edu.wpi.first.units.Units.RadiansPerSecond;
import static edu.wpi.first.units.Units.RotationsPerSecond;

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

public class SimulatedIntake implements IntakeInterface{
DCMotorSim simIntake = new DCMotorSim(LinearSystemId.createDCMotorSystem(
DCMotor.getFalcon500(1), 0.01, 1),
DCMotor.getFalcon500(1), 0);

private double intakeAppliedVolts = 0.0;

public SimulatedIntake(){}

@Override
public void updateInputs(IntakeInputs intakeInputs){
simIntake.update(0.02);

intakeInputs.intakeVelocity = RadiansPerSecond.of(simIntake.getAngularVelocityRadPerSec()).in(RotationsPerSecond);
intakeInputs.currentAmps = simIntake.getCurrentDrawAmps();
intakeInputs.appliedVolts = intakeAppliedVolts;
}

@Override
public double getIntakeSpeed(){
return RadiansPerSecond.of(simIntake.getAngularVelocityRadPerSec()).in(RotationsPerSecond);
}
}
4 changes: 0 additions & 4 deletions src/main/java/frc/robot/subsystems/swerve/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -77,10 +77,6 @@ public double getTurnVelocity() {
return inputs.turnVelocity;
}

public double xthing() {
return inputs.Angle
}

/** Returns the current drive position of the module in meters. */
public double getDrivePositionMeters() {
return ModuleConstants.WHEEL_CIRCUMFERENCE_METERS * inputs.drivePosition;
Expand Down

0 comments on commit 82683cf

Please sign in to comment.