Skip to content

Commit

Permalink
for roogies
Browse files Browse the repository at this point in the history
  • Loading branch information
siyoyoCode committed Sep 27, 2024
1 parent 4da4032 commit cf6e951
Show file tree
Hide file tree
Showing 4 changed files with 8 additions and 107 deletions.
Empty file.
10 changes: 5 additions & 5 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -465,9 +465,9 @@ private void configureBindings() {
/* ElEVATOR TEST */

dPadUp.onTrue(new ElevatorToTrapCommand(elevatorSubsystem));
dPadUp.onTrue(new InstantCommand(() -> intakePivotSubsystem.enablePowerLimit(false)));
//dPadUp.onTrue(new InstantCommand(() -> intakePivotSubsystem.enablePowerLimit(false)));
dPadDown.onTrue(new ElevatorToZeroCommand(elevatorSubsystem));
dPadDown.onTrue(new InstantCommand(() -> intakePivotSubsystem.enablePowerLimit(true)));
//dPadDown.onTrue(new InstantCommand(() -> intakePivotSubsystem.enablePowerLimit(true)));


dPadLeft.onTrue(new ElevatorToMidCommand(elevatorSubsystem));
Expand Down Expand Up @@ -520,7 +520,7 @@ private void configureBindings() {
// if elevator is up
new ElevatorToZeroCommand(elevatorSubsystem).alongWith(
Commands.runOnce(() -> {
intakePivotSubsystem.enablePowerLimit(true);
//intakePivotSubsystem.enablePowerLimit(true);
intakePivotSubsystem.setPosition(0);
}, intakePivotSubsystem)
), // stow the pivot
Expand All @@ -541,13 +541,13 @@ private void configureBindings() {
new ConditionalCommand(
new ElevatorToZeroCommand(elevatorSubsystem).alongWith(new InstantCommand(// lower the elevator
() -> {
intakePivotSubsystem.enablePowerLimit(true);
//intakePivotSubsystem.enablePowerLimit(true);
intakePivotSubsystem.setPosition(0);
}, intakePivotSubsystem)), // stow intake
new ConditionalCommand(
new ElevatorToTrapCommand(elevatorSubsystem).andThen(
new InstantCommand(() -> {
intakePivotSubsystem.enablePowerLimit(false);
//intakePivotSubsystem.enablePowerLimit(false);
intakePivotSubsystem.setPosition(.45);
})
),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,13 +3,8 @@
import static frc.robot.Constants.IntakeConstants;

import com.ctre.phoenix6.configs.Slot0Configs;
import com.ctre.phoenix6.configs.VoltageConfigs;
import com.ctre.phoenix6.controls.PositionVoltage;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.NeutralModeValue;
import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableEntry;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj2.command.SubsystemBase;


Expand All @@ -18,16 +13,8 @@ public class IntakePivotSubsystem extends SubsystemBase {

private final TalonFX pivotMotor;

private PositionVoltage request = new PositionVoltage(0).withSlot(0);
private VoltageConfigs voltageConfig = new VoltageConfigs();
private double setPos = 0;
private static final double FORWARD_VOLTAGE = 1.75;

private NetworkTableInstance ntInstance;
private NetworkTable motorsNTTable;
private NetworkTableEntry intake16CurrentEntry;
private NetworkTableEntry intake16VoltageEntry;
private NetworkTableEntry intake16TemperatureEntry;

/**
* Subsystem for controlling the pivot on the intake.
Expand All @@ -36,32 +23,14 @@ public IntakePivotSubsystem() {
pivotMotor = new TalonFX(IntakeConstants.PIVOT_MOTOR_ID);
pivotMotor.setNeutralMode(NeutralModeValue.Brake);

// intakeencoder = new Encoder(1, 2);
// extendedlimitswitch = new DigitalInput(extendedlimitswitchID);
// retractedlimitswitch = new DigitalInput(retractedlimitswitchID);

Slot0Configs slot0Configs = new Slot0Configs();

slot0Configs.kP = IntakeConstants.PIVOT_P;
slot0Configs.kI = IntakeConstants.PIVOT_I;
slot0Configs.kD = IntakeConstants.PIVOT_D;

voltageConfig.PeakForwardVoltage = FORWARD_VOLTAGE;
voltageConfig.PeakReverseVoltage = -16;


pivotMotor.getConfigurator().apply(slot0Configs);
pivotMotor.setPosition(0);
// pivotMotor.getConfigurator().apply(voltageConfig);


request.withLimitForwardMotion(false);

ntInstance = NetworkTableInstance.getDefault();
motorsNTTable = ntInstance.getTable("Motors");
intake16CurrentEntry = motorsNTTable.getEntry("Intake16Current");
intake16VoltageEntry = motorsNTTable.getEntry("Intake16Voltage");
intake16TemperatureEntry = motorsNTTable.getEntry("Intake16Temperature");
}

/**
Expand All @@ -71,7 +40,6 @@ public IntakePivotSubsystem() {
*/

public void setPosition(double position) {
pivotMotor.setControl(request.withPosition(position / IntakeConstants.PIVOT_CONVERSION_FACTOR));
setPos = position;
}

Expand Down Expand Up @@ -103,28 +71,9 @@ public void movePivot(double speed) {
pivotMotor.set(speed);
}

/**
* Enables/disables the pivot motor's forward voltage limit for deploying the intake.
* When enabled, the linkage will not slam down when deploying.
*
* @param enabled True enables the limit, false disables it.
*/
public void enablePowerLimit(boolean enabled) {
if (enabled) {
voltageConfig.PeakForwardVoltage = FORWARD_VOLTAGE;
} else {
voltageConfig.PeakForwardVoltage = 16;
}

// pivotMotor.getConfigurator().apply(voltageConfig);
}

@Override
public void periodic() {
pivotMotor.setControl(request.withPosition(setPos / IntakeConstants.PIVOT_CONVERSION_FACTOR));

intake16CurrentEntry.setDouble(pivotMotor.getSupplyCurrent().getValueAsDouble());
intake16VoltageEntry.setDouble(pivotMotor.getMotorVoltage().getValueAsDouble());
intake16TemperatureEntry.setDouble(pivotMotor.getDeviceTemp().getValueAsDouble());

}
}
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,7 @@
import com.revrobotics.ColorSensorV3;
import com.revrobotics.CANSparkBase.IdleMode;

import edu.wpi.first.networktables.BooleanPublisher;
import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableEntry;
import edu.wpi.first.networktables.NetworkTableInstance;

import edu.wpi.first.wpilibj.AnalogPotentiometer;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.DigitalOutput;
Expand All @@ -45,24 +42,6 @@ public class IntakeRollerSubsystem extends SubsystemBase {

private boolean prevFrontSensorValue = false;

private NetworkTableInstance ntInstance;
private NetworkTable ntTable;
private BooleanPublisher ntFrontPublisher;
private BooleanPublisher ntBackPublisher;

private NetworkTable motorsNTTable;
private NetworkTableEntry frontMotorCurrentEntry;
private NetworkTableEntry frontMotorVoltageEntry;
private NetworkTableEntry frontMotorTemperatureEntry;
private NetworkTableEntry integrationMotorCurrentEntry;
private NetworkTableEntry integrationMotorVoltageEntry;
private NetworkTableEntry integrationMotorTemperatureEntry;

private NetworkTable intakeNTTable;
private NetworkTableEntry frontSensorEntry;
private NetworkTableEntry rockwellSensorEntry;
private NetworkTableEntry ampSenSorEntry;

private final LightBarSubsystem lightBarSubsystem;

private Timer colorResetTimer;
Expand All @@ -80,22 +59,6 @@ public IntakeRollerSubsystem(LightBarSubsystem lightBarSubsystem) {
rockwellSensor = new DigitalInput(4);
ampSensor = new DigitalInput(5);

ntInstance = NetworkTableInstance.getDefault();
ntTable = ntInstance.getTable("RobotStatus");
intakeNTTable = ntInstance.getTable("Intake");
frontSensorEntry = intakeNTTable.getEntry("FrontSensor");
rockwellSensorEntry = intakeNTTable.getEntry("Rockwell");
ampSenSorEntry = intakeNTTable.getEntry("AMPSensor");
ntFrontPublisher = ntTable.getBooleanTopic("FrontSensor").publish();
ntBackPublisher = ntTable.getBooleanTopic("BackSensor").publish();

motorsNTTable = ntInstance.getTable("Motors");
frontMotorCurrentEntry = motorsNTTable.getEntry("Intake17Current");
frontMotorVoltageEntry = motorsNTTable.getEntry("Intake17Voltage");
frontMotorTemperatureEntry = motorsNTTable.getEntry("Intake17Temperature");
integrationMotorCurrentEntry = motorsNTTable.getEntry("Intake19Current");
integrationMotorVoltageEntry = motorsNTTable.getEntry("Intake19Voltage");
integrationMotorTemperatureEntry = motorsNTTable.getEntry("Intake19Temperature");
this.lightBarSubsystem = lightBarSubsystem;

// colorResetTimer = new Timer();
Expand Down Expand Up @@ -160,18 +123,7 @@ public boolean getAmpSensor() {

@Override
public void periodic() {
frontSensorEntry.setBoolean(getFrontSensorValue());
rockwellSensorEntry.setBoolean(getRockwellSensorValue());
ampSenSorEntry.setBoolean(getAmpSensor());

frontMotorCurrentEntry.setDouble(frontMotors.getOutputCurrent());
frontMotorVoltageEntry.setDouble(frontMotors.getBusVoltage());
frontMotorTemperatureEntry.setDouble(frontMotors.getMotorTemperature());
integrationMotorCurrentEntry.setDouble(integrationMotor.getSupplyCurrent());
integrationMotorVoltageEntry.setDouble(integrationMotor.getMotorOutputVoltage());
integrationMotorTemperatureEntry.setDouble(integrationMotor.getTemperature());

ntFrontPublisher.set(getFrontSensorReached());

prevFrontSensorValue = getFrontSensorValue();
if (getFrontSensorValue()) {
lightBarSubsystem.setLightBarStatus(LightBarStatus.HOLDING_NOTE, 2);
Expand Down

0 comments on commit cf6e951

Please sign in to comment.