Skip to content

Commit

Permalink
[#541] increase limit
Browse files Browse the repository at this point in the history
  • Loading branch information
Vilok1 committed Apr 13, 2024
1 parent 9f1559d commit 0e35e55
Show file tree
Hide file tree
Showing 4 changed files with 18 additions and 2 deletions.
1 change: 1 addition & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -366,6 +366,7 @@ public class MusicConstants {
public class CollectorConstants {
public static final boolean COLLECTOR_MOTOR_INVERTED = true;
public static final int COLLECTOR_MOTOR_STATOR_CURRENT_LIMIT = 70;
public static final int AUTON_COLLECTOR_STATOR_LIMIT = 200;
public static final boolean COLLECTOR_MOTOR_BRAKE_MODE = false;

public static final double MOTOR_KP = 0;
Expand Down
4 changes: 4 additions & 0 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,8 @@ public void autonomousInit() {

RobotContainer container = (RobotContainer) getContainer();
container.drivetrain.disableVision();

container.collector.setAutonCurrentLimit();
}

@Override
Expand All @@ -59,5 +61,7 @@ public void teleopInit() {

RobotContainer container = (RobotContainer) getContainer();
container.drivetrain.enableVision();

container.collector.setTeleopCurrentLimit();
}
}
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,7 @@ public class RobotContainer extends LightningContainer {
// Subsystems
public Swerve drivetrain;
private Limelights limelights;
private Collector collector;
public Collector collector;
private Flywheel flywheel;
public Pivot pivot;
private Indexer indexer;
Expand Down
13 changes: 12 additions & 1 deletion src/main/java/frc/robot/subsystems/Collector.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@
import edu.wpi.first.math.filter.Debouncer;
import edu.wpi.first.util.datalog.BooleanLogEntry;

import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.controls.VelocityVoltage;

import edu.wpi.first.wpilibj.DigitalInput;
Expand Down Expand Up @@ -39,7 +41,6 @@ public Collector() {
CollectorConstants.COLLECTOR_MOTOR_INVERTED,
CollectorConstants.COLLECTOR_MOTOR_STATOR_CURRENT_LIMIT,
CollectorConstants.COLLECTOR_MOTOR_BRAKE_MODE);

motor.configPIDF(0, CollectorConstants.MOTOR_KP, CollectorConstants.MOTOR_KI,
CollectorConstants.MOTOR_KD, CollectorConstants.MOTOR_KS, CollectorConstants.MOTOR_KV);

Expand Down Expand Up @@ -121,4 +122,14 @@ public boolean hasPiece() {
public void stop() {
setPower(0d);
}

public void setAutonCurrentLimit(){
motor.applyConfig(new TalonFXConfiguration().withCurrentLimits(
new CurrentLimitsConfigs().withStatorCurrentLimit(CollectorConstants.AUTON_COLLECTOR_STATOR_LIMIT)));
}

public void setTeleopCurrentLimit(){
motor.applyConfig(new TalonFXConfiguration().withCurrentLimits(
new CurrentLimitsConfigs().withStatorCurrentLimit(CollectorConstants.COLLECTOR_MOTOR_STATOR_CURRENT_LIMIT)));
}
}

0 comments on commit 0e35e55

Please sign in to comment.