Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions src/main/java/frc/robot/Indexer.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot;

/** Add your docs here. */
public class Indexer {}
1 change: 1 addition & 0 deletions src/main/java/frc/robot/Main.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
package frc.robot;

import edu.wpi.first.wpilibj.RobotBase;
import frc.robot.indexer.Indexer;

/**
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
Expand Down
53 changes: 53 additions & 0 deletions src/main/java/frc/robot/indexer/Indexer.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
package frc.robot.indexer;
import com.ctre.phoenix6.StatusSignal;
import com.ctre.phoenix6.configs.MotorOutputConfigs;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.InvertedValue;

import edu.wpi.first.units.measure.Current;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class Indexer extends SubsystemBase{
public static class Settings {
static int kTalonID = 10;
static final double kMaxVoltage = 12.0;
static final int kCurrentLimit = 200;
static final int kCurrentThreshold = 100;
}

private static Indexer mInstance;
private TalonFX mKraken;

public Indexer() {
mKraken = new TalonFX(Settings.kTalonID);

var talonFXConfigurator = mKraken.getConfigurator();
var motorConfigs = new MotorOutputConfigs();

motorConfigs.Inverted = InvertedValue.Clockwise_Positive;
talonFXConfigurator.apply(motorConfigs);

}

public static Indexer getInstance() {
if (mInstance == null) {
mInstance = new Indexer();
}
return mInstance;
}

public void setOutput(double percentOut) {
mKraken.setVoltage(percentOut * Settings.kMaxVoltage);
}

public Boolean hasAlgae() {
//needs testing
return (mKraken.getStatorCurrent().getValueAsDouble() > Settings.kCurrentThreshold);
}

@Override
public void periodic() {
SmartDashboard.putBoolean("Indexer Has Algae", hasAlgae());
}
}
10 changes: 10 additions & 0 deletions src/main/java/frc/robot/indexer/commands/IndexerCommands.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
package frc.robot.indexer.commands;

import edu.wpi.first.wpilibj2.command.Command;
import java.util.function.DoubleSupplier;

public class IndexerCommands {
public static Command setOutput(DoubleSupplier outputSupplier) {
return new SetOutputIndexer(outputSupplier);
}
}
27 changes: 27 additions & 0 deletions src/main/java/frc/robot/indexer/commands/SetOutputIndexer.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
package frc.robot.indexer.commands;

import java.util.function.DoubleSupplier;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.indexer.Indexer;

public class SetOutputIndexer extends Command {
private final Indexer indexer;
private final DoubleSupplier supplier;

public SetOutputIndexer(DoubleSupplier supplier) {
indexer = Indexer.getInstance();
this.supplier = supplier;
addRequirements(indexer);
}

@Override
public void execute() {
indexer.setOutput(supplier.getAsDouble());
}

@Override
public void end(boolean interrupted) {
indexer.setOutput(0);
}
}