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
@@ -180,6 +180,8 @@ public class BoomBoom extends SubsystemBase {
public void runDrumShooter(double speed) {
m_shooterFalconLeft.set(TalonFXControlMode.PercentOutput, speed + speed2);
SmartDashboard.putNumber("BoomBoom percent speed", speed + speed2);
SmartDashboard.putNumber("BoomBoom current stator", m_shooterFalconLeft.getStatorCurrent());
SmartDashboard.putNumber("BoomBoom current supply", m_shooterFalconLeft.getSupplyCurrent());
}
@@ -208,4 +210,8 @@ public class BoomBoom extends SubsystemBase {
{
speed2 = speed2 + amount;
}
public double getCurrent(){
return m_shooterFalconLeft.getSupplyCurrent() + m_shooterFalconRight.getSupplyCurrent();
}
}
@@ -23,4 +23,8 @@ public class Climber extends SubsystemBase {
public void periodic() {
// This method will be called once per scheduler run
}
public double getCurrent() {
return m_climberElbow.getSupplyCurrent();
}
}
@@ -95,4 +95,8 @@ public double m_fireAngle;
public double getAnglePositionDegrees(){
return 0.0;//((m_angleEncoder.getPosition() - ShooterConstants.HOOD_MOTOR_POS_AT_ZERO_ROT) * 360/ShooterConstants.HOOD_MOTOR_ROTS_PER_ROT) - 90;
}
public double getCurrent(){
return m_angleAdjusterMotor.getOutputCurrent();
}
}
@@ -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();
}
}
@@ -57,4 +57,5 @@ public class LED extends SubsystemBase {
public LEDPatterns getPattern() {
return m_currentPattern;
}
}
@@ -48,4 +48,7 @@ public class Serializer extends SubsystemBase{
public boolean getSerializerState() {
return serializerState;
}
public double getCurrent(){
return m_serializerBelt.getOutputCurrent();
}
}
@@ -65,4 +65,7 @@ public class Storage extends SubsystemBase {
public void periodic() {
//manageStorage();
}
public double getCurrent(){
return m_storageMotor.getOutputCurrent();
}
}
@@ -258,4 +258,8 @@ public class SwerveDrive extends SubsystemBase {
speedAdjust = SwerveDriveConstants.JOYSTICK_TO_METERS_PER_SECOND_SLOW;
}
}
public double getCurrent(){
return m_leftFront.getCurrent() + m_rightFront.getCurrent() + m_rightBack.getCurrent() + m_leftBack.getCurrent();
}
}
@@ -120,7 +120,7 @@ public class SwerveModule extends SubsystemBase {
double desiredTicks = currentTicks + deltaTicks;
if (!ignoreAngle) {
angleMotor.set(TalonFXControlMode.Position, desiredTicks);
}
@@ -192,5 +192,7 @@ public class SwerveModule extends SubsystemBase {
canCoder.setPositionToAbsolute();
// canCoder.configSensorInitializationStrategy(initializationStrategy)
}
public double getCurrent(){
return angleMotor.getSupplyCurrent() + driveMotor.getSupplyCurrent();
}
}
@@ -109,4 +109,8 @@ public class Turret extends SubsystemBase {
/ ShooterConstants.TURRET_MOTOR_ROTS_PER_ROT;
}
public double getCurrent(){
return m_boomBoomRotateMotor.getOutputCurrent();
}
}