Skip to content

Commit

Permalink
Limit current caps to add to below sustainable current
Browse files Browse the repository at this point in the history
Also, remove climb from brownout calculations as it will be dormant outside of climb and during climb we don't want to be limiting it.
  • Loading branch information
ky28059 authored and e3l committed Feb 20, 2022
1 parent a047ae2 commit 779bf09
Show file tree
Hide file tree
Showing 7 changed files with 8 additions and 35 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ public void robotPeriodic() {
CommandScheduler.getInstance().run();

// Calculate current limits for subsystems
//robotContainer.getPowerController().calculateLimits();
robotContainer.getPowerController().calculateLimits();
}

/** This function is called once each time the robot enters Disabled mode. */
Expand Down
5 changes: 1 addition & 4 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ public class RobotContainer {
// private final ClimbSubsystem climbSubsystem;

private final JetsonConnection jetson = null;
private final PowerController powerController = null;
private final PowerController powerController;

// Controllers and buttons
private final XboxController driveController = new XboxController(0);
Expand Down Expand Up @@ -81,15 +81,12 @@ public RobotContainer() {
// climbSubsystem = new ClimbSubsystem();

// Instantiate power controller
/*
powerController = new PowerController(
tankSubsystem,
turretSubsystem,
internalSubsystem,
intakeSubsystem
//, climbSubsystem
);
*/

// Instantiate commands
// Drive an S-shaped curve from the origin to 3 meters in front through 2 waypoints
Expand Down
28 changes: 2 additions & 26 deletions src/main/java/frc/robot/subsystems/ClimbSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
import com.ctre.phoenix.motorcontrol.ControlMode;
import com.ctre.phoenix.motorcontrol.FeedbackDevice;
import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.SupplyCurrentLimitConfiguration;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;

import com.revrobotics.CANSparkMax;
Expand All @@ -18,14 +17,12 @@
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj2.command.CommandBase;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.WaitUntilCommand;

import frc.robot.GRTSubsystem;
import frc.robot.brownout.PowerController;

import static frc.robot.Constants.ClimbConstants.*;

public class ClimbSubsystem extends GRTSubsystem {
public class ClimbSubsystem extends SubsystemBase {
private final CANSparkMax six;
private final RelativeEncoder sixEncoder;
private final SparkMaxPIDController sixPidController;
Expand Down Expand Up @@ -71,9 +68,6 @@ public class ClimbSubsystem extends GRTSubsystem {
private final NetworkTableEntry shuffleboardFifteenDEntry;

public ClimbSubsystem() {
// TODO: measure this
super(20);

// Initialize six point arm NEO, encoder PID, and solenoid brake
six = new CANSparkMax(sixMotorPort, MotorType.kBrushless);
six.restoreFactoryDefaults();
Expand Down Expand Up @@ -261,22 +255,4 @@ public SequentialCommandGroup climb() {
new ClimbPhase3Command()
);
}

@Override
public double getTotalCurrentDrawn() {
return PowerController.getCurrentDrawnFromPDH(
sixMotorPort, sixBrakePort, tenMotorPort, tenBrakePort,
fifteenLeftPort, fifteenRightPort, tenLeftSolenoidPort, tenRightSolenoidPort
);
}

@Override
public void setCurrentLimit(double limit) {
// TODO: do the solenoids draw significant power? should they be factored in to the limit calculation?
int motorLimit = (int) Math.floor(limit / 4);

six.setSmartCurrentLimit(motorLimit);
ten.setSmartCurrentLimit(motorLimit);
fifteenMain.configSupplyCurrentLimit(new SupplyCurrentLimitConfiguration(true, motorLimit, 0, 0));
}
}
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/IntakeSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ private IntakePosition(double value) {

public IntakeSubsystem(InternalSubsystem internalSubsystem /* , JetsonConnection jetson */) {
// TODO: measure this
super(50);
super(20);

this.internalSubsystem = internalSubsystem;
// this.jetson = jetson;
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/TurretSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ public enum ModuleState {

public TurretSubsystem(TankSubsystem tankSubsystem, JetsonConnection connection) {
// TODO: measure this
super(50);
super(40);

this.tankSubsystem = tankSubsystem;
this.jetson = connection;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ public class InternalSubsystem extends GRTSubsystem {

public InternalSubsystem(TurretSubsystem turretSubsystem) {
// TODO: measure this
super(50);
super(20);

this.turretSubsystem = turretSubsystem;

Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/tank/TankSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ public class TankSubsystem extends GRTSubsystem {

public TankSubsystem() {
// TODO: measure this
super(50);
super(40);

// Init left main and follower motors and encoders
leftMain = new CANSparkMax(fLeftMotorPort, MotorType.kBrushless);
Expand Down

0 comments on commit 779bf09

Please sign in to comment.