current limits

This commit is contained in:
Ryan Manley
2022-03-12 11:36:10 -07:00
parent e237f14537
commit 03485c1063
14 changed files with 77 additions and 7 deletions
@@ -10,6 +10,7 @@ import com.revrobotics.SparkMaxLimitSwitch;
import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import com.revrobotics.CANSparkMax;
@@ -52,6 +53,8 @@ public class Intake extends SubsystemBase {
*/
public void runWithTriggers(double leftTrigger, double rightTrigger) {
m_intakeMotor.set((rightTrigger - leftTrigger) * 0.3);
SmartDashboard.putNumber("Intake Current Supply", m_intakeMotor.getSupplyCurrent());
SmartDashboard.putNumber("Intake Current Stator", m_intakeMotor.getStatorCurrent());
}
/**
* Runs The Extender-
@@ -74,4 +77,8 @@ public class Intake extends SubsystemBase {
toggle = !toggle;
runExtender(toggle);
}
public double getCurrent(){
return m_intakeMotor.getSupplyCurrent() + m_extenderMotor.getOutputCurrent();
}
}