Merge branch 'New-Intake' of https://github.com/Team4388/2026KPopRobotHunters into New-Intake

This commit is contained in:
Shikhar
2026-03-31 19:01:23 -06:00
11 changed files with 172 additions and 35 deletions
+1
View File
@@ -185,3 +185,4 @@ compile_commands.json
# Eclipse generated file for annotation processors # Eclipse generated file for annotation processors
.factorypath .factorypath
src/main/java/frc4388/utility/compute/JankCoder copy.java
+5
View File
@@ -15,6 +15,8 @@ import org.littletonrobotics.junction.networktables.NT4Publisher;
import org.littletonrobotics.junction.wpilog.WPILOGReader; import org.littletonrobotics.junction.wpilog.WPILOGReader;
import org.littletonrobotics.junction.wpilog.WPILOGWriter; import org.littletonrobotics.junction.wpilog.WPILOGWriter;
import com.ctre.phoenix6.SignalLogger;
import edu.wpi.first.wpilibj.GenericHID.RumbleType; import edu.wpi.first.wpilibj.GenericHID.RumbleType;
import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler; import edu.wpi.first.wpilibj2.command.CommandScheduler;
@@ -50,6 +52,9 @@ public class Robot extends LoggedRobot {
// Start logging with AdvantageKit // Start logging with AdvantageKit
startLogging(); startLogging();
com.revrobotics.util.StatusLogger.disableAutoLogging();
SignalLogger.enableAutoLogging(false);
// Instantiate our RobotContainer. This will perform all our button bindings, and put our // Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard. // autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer(); m_robotContainer = new RobotContainer();
@@ -378,11 +378,14 @@ public class RobotContainer {
new JoystickButton(getDeadbandedOperatorController(), XboxController.Y_BUTTON) new JoystickButton(getDeadbandedOperatorController(), XboxController.Y_BUTTON)
.onTrue(new InstantCommand(() -> { .onTrue(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Retracting); m_robotIntake.setMode(IntakeMode.Retracting);
}))
.onFalse(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Idle);
})); }));
new Trigger(() -> getDeadbandedDriverController().getPOV() == 90) new Trigger(() -> getDeadbandedOperatorController().getPOV() == 90)
.onTrue(new InstantCommand(() -> { .onTrue(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.ExtendingIdle); m_robotIntake.setMode(IntakeMode.ExtendingIdle);
})) }))
@@ -390,13 +393,24 @@ public class RobotContainer {
m_robotIntake.setMode(IntakeMode.Idle); m_robotIntake.setMode(IntakeMode.Idle);
})); }));
new Trigger(() -> getDeadbandedDriverController().getPOV() == 270) new Trigger(() -> getDeadbandedOperatorController().getPOV() == 270)
.onTrue(new InstantCommand(() -> { .onTrue(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Retracting); m_robotIntake.setMode(IntakeMode.Retracting);
})) }))
.onFalse(new InstantCommand(() -> { .onFalse(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Idle); m_robotIntake.setMode(IntakeMode.Idle);
})); }));
new Trigger(() -> getDeadbandedOperatorController().getPOV() == 0)
.onTrue(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Bouncing);
}))
.onFalse(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Idle);
}));
// .onFalse(new InstantCommand(() -> { // .onFalse(new InstantCommand(() -> {
// m_robotIntake.setMode(IntakeMode.Idle); // m_robotIntake.setMode(IntakeMode.Idle);
// })); // }));
@@ -7,12 +7,12 @@ public final class BuildConstants {
public static final String MAVEN_GROUP = ""; public static final String MAVEN_GROUP = "";
public static final String MAVEN_NAME = "2026KPopRobotHunters"; public static final String MAVEN_NAME = "2026KPopRobotHunters";
public static final String VERSION = "unspecified"; public static final String VERSION = "unspecified";
public static final int GIT_REVISION = 190; public static final int GIT_REVISION = 189;
public static final String GIT_SHA = "3fe5d0e5a1cfe24710b755b489fa61255e307095"; public static final String GIT_SHA = "65c76aca95de81f342df7ff26a77e18856f22a83";
public static final String GIT_DATE = "2026-03-30 16:15:43 MDT"; public static final String GIT_DATE = "2026-03-28 15:56:54 MDT";
public static final String GIT_BRANCH = "New-Intake"; public static final String GIT_BRANCH = "New-Intake";
public static final String BUILD_DATE = "2026-03-31 18:51:12 MDT"; public static final String BUILD_DATE = "2026-03-30 19:50:05 MDT";
public static final long BUILD_UNIX_TIME = 1775004672077L; public static final long BUILD_UNIX_TIME = 1774921805228L;
public static final int DIRTY = 1; public static final int DIRTY = 1;
private BuildConstants(){} private BuildConstants(){}
@@ -119,7 +119,7 @@ public class Intake extends SubsystemBase {
case ExtendingRolling: case ExtendingRolling:
io.armOutput(IntakeConstants.ARM_EXTEND_PERCENT_OUTPUT.get()); io.armOutput(IntakeConstants.ARM_EXTEND_PERCENT_OUTPUT.get());
io.setRollerOutput(state, IntakeConstants.ARM_EXTEND_PERCENT_OUTPUT.get()); io.setRollerOutput(state, IntakeConstants.ROLLER_PERCENT_OUTPUT.get());
break; break;
case Retracting: case Retracting:
@@ -133,12 +133,13 @@ public class Intake extends SubsystemBase {
break; break;
case Bouncing: case Bouncing:
io.setRollerOutput(state, 0); // io.setRollerOutput(state, 0);
if( if(
state.armMotorCurrent.in(Amps) < IntakeConstants.INTAKE_BOUNCE_CURRENT_LIMIT.get() && state.armMotorCurrent.in(Amps) > IntakeConstants.INTAKE_BOUNCE_CURRENT_LIMIT.get()
state.armMotorVelocity.in(RotationsPerSecond) < IntakeConstants.INTAKE_BOUNCE_VELOCITY_LIMIT.get() // Math.abs(state.armMotorVelocity.in(RotationsPerSecond)) < IntakeConstants.INTAKE_BOUNCE_VELOCITY_LIMIT.get()
) { ) {
System.out.println("RESET BOUNCE");
this.state.currentBounceTime = Utils.getSystemTimeSeconds() + IntakeConstants.INTAKE_BOUNCE_HALF_PERIOD.get(); this.state.currentBounceTime = Utils.getSystemTimeSeconds() + IntakeConstants.INTAKE_BOUNCE_HALF_PERIOD.get();
} }
@@ -147,11 +148,11 @@ public class Intake extends SubsystemBase {
// Get the percentage through the bounce period (0 output means one half period has passed) // Get the percentage through the bounce period (0 output means one half period has passed)
double percentOutput = (currentTime / IntakeConstants.INTAKE_BOUNCE_HALF_PERIOD.get()) * IntakeConstants.INTAKE_BOUNCE_OUTPUT.get(); double percentOutput = (currentTime / IntakeConstants.INTAKE_BOUNCE_HALF_PERIOD.get()) * IntakeConstants.INTAKE_BOUNCE_OUTPUT.get();
// Clamp the output of the motor to some value // Clamp the output of the motor to some value
percentOutput = Math.max(Math.min(percentOutput, IntakeConstants.INTAKE_BOUNCE_MAX_OUTPUT.get()), -IntakeConstants.INTAKE_BOUNCE_MAX_OUTPUT.get()); percentOutput = -Math.max(Math.min(percentOutput, IntakeConstants.INTAKE_BOUNCE_MAX_OUTPUT.get()), -IntakeConstants.INTAKE_BOUNCE_MAX_OUTPUT.get());
io.armOutput(percentOutput); io.armOutput(percentOutput);
if(state.intakeEncoder.in(Rotations) > IntakeConstants.ARM_REVERSE_ROLLER_RANGE.get()) { if(percentOutput < 0) {
io.setRollerOutput(state, IntakeConstants.ROLLER_RETRACT_PERCENT_OUTPUT.get()); io.setRollerOutput(state, IntakeConstants.ROLLER_RETRACT_PERCENT_OUTPUT.get());
} else { } else {
io.setRollerOutput(state, 0); io.setRollerOutput(state, 0);
@@ -4,6 +4,7 @@ import com.revrobotics.spark.FeedbackSensor;
import com.revrobotics.spark.config.SparkMaxConfig; import com.revrobotics.spark.config.SparkMaxConfig;
import com.revrobotics.spark.config.LimitSwitchConfig.Behavior; import com.revrobotics.spark.config.LimitSwitchConfig.Behavior;
import com.revrobotics.spark.config.LimitSwitchConfig.Type; import com.revrobotics.spark.config.LimitSwitchConfig.Type;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
import frc4388.utility.configurable.ConfigurableDouble; import frc4388.utility.configurable.ConfigurableDouble;
import frc4388.utility.status.CanDevice; import frc4388.utility.status.CanDevice;
@@ -13,15 +14,15 @@ public class IntakeConstants {
public static final double ARM_MOTOR_GEAR_RATIO = 125; public static final double ARM_MOTOR_GEAR_RATIO = 125;
public static final double ROLLER_MOTOR_GEAR_RATIO = 3; public static final double ROLLER_MOTOR_GEAR_RATIO = 3;
public static final double ARM_ENCODER_OFFSET = -0.466; public static final ConfigurableDouble ARM_ENCODER_OFFSET = new ConfigurableDouble("Arm Encoder Offset", 0);
public static final ConfigurableDouble INTAKE_BOUNCE_HALF_PERIOD = new ConfigurableDouble("Bounce Half Period", 5.); public static final ConfigurableDouble INTAKE_BOUNCE_HALF_PERIOD = new ConfigurableDouble("Bounce Half Period", 5.);
public static final ConfigurableDouble INTAKE_BOUNCE_OUTPUT = new ConfigurableDouble("Bounce Output", 0.2); public static final ConfigurableDouble INTAKE_BOUNCE_OUTPUT = new ConfigurableDouble("Bounce Output", 0.1);
public static final ConfigurableDouble INTAKE_BOUNCE_MAX_OUTPUT = new ConfigurableDouble("Bounce Max Output", 0.5); public static final ConfigurableDouble INTAKE_BOUNCE_MAX_OUTPUT = new ConfigurableDouble("Bounce Max Output", 0.2);
public static final ConfigurableDouble INTAKE_BOUNCE_CURRENT_LIMIT = new ConfigurableDouble("Intake Bounce Current Limit", 20); public static final ConfigurableDouble INTAKE_BOUNCE_CURRENT_LIMIT = new ConfigurableDouble("Intake Bounce Current Limit", 16);
public static final ConfigurableDouble INTAKE_BOUNCE_VELOCITY_LIMIT = new ConfigurableDouble("Intake Bounce Velocity Limit", 20); public static final ConfigurableDouble INTAKE_BOUNCE_VELOCITY_LIMIT = new ConfigurableDouble("Intake Bounce Velocity Limit", 4);
//squeeze constants //squeeze constants
@@ -47,11 +48,11 @@ public class IntakeConstants {
// public static final Angle ARM_LIMIT_UPPER = Degrees.of(-90); // public static final Angle ARM_LIMIT_UPPER = Degrees.of(-90);
public static final ConfigurableDouble ARM_LIMIT_RETRACTED = new ConfigurableDouble("Arm angle retracted", 0.); public static final ConfigurableDouble ARM_LIMIT_RETRACTED = new ConfigurableDouble("Arm angle retracted", 0.);
public static final ConfigurableDouble ARM_LIMIT_EXTENDED = new ConfigurableDouble("Arm angle extended", 1.8); public static final ConfigurableDouble ARM_LIMIT_EXTENDED = new ConfigurableDouble("Arm angle extended", 1.5);
public static final ConfigurableDouble ARM_EXTEND_PERCENT_OUTPUT = new ConfigurableDouble("Arm extend % output", 0.1); public static final ConfigurableDouble ARM_EXTEND_PERCENT_OUTPUT = new ConfigurableDouble("Arm extend % output", 0.2);
public static final ConfigurableDouble ARM_RETRACT_PERCENT_OUTPUT = new ConfigurableDouble("Arm retract % output", -0.1); public static final ConfigurableDouble ARM_RETRACT_PERCENT_OUTPUT = new ConfigurableDouble("Arm retract % output", -0.2);
public static final ConfigurableDouble ARM_REVERSE_ROLLER_RANGE = new ConfigurableDouble("Arm reverse roller range", 2.0); public static final ConfigurableDouble ARM_REVERSE_ROLLER_RANGE = new ConfigurableDouble("Arm reverse roller range", 1.17);
public static final ConfigurableDouble ROLLER_PERCENT_OUTPUT = new ConfigurableDouble("Roller Percent Output", .80); public static final ConfigurableDouble ROLLER_PERCENT_OUTPUT = new ConfigurableDouble("Roller Percent Output", .80);
public static final ConfigurableDouble ROLLER_RETRACT_PERCENT_OUTPUT = new ConfigurableDouble("Roller Retract Output", .40); public static final ConfigurableDouble ROLLER_RETRACT_PERCENT_OUTPUT = new ConfigurableDouble("Roller Retract Output", .40);
@@ -95,6 +96,11 @@ public class IntakeConstants {
.reverseLimitSwitchType(Type.kNormallyClosed) .reverseLimitSwitchType(Type.kNormallyClosed)
.reverseLimitSwitchPosition(0) .reverseLimitSwitchPosition(0)
.reverseLimitSwitchTriggerBehavior(Behavior.kStopMovingMotorAndSetPosition); .reverseLimitSwitchTriggerBehavior(Behavior.kStopMovingMotorAndSetPosition);
ARM_MOTOR_CONFIG.idleMode(IdleMode.kBrake);
ROLELR_MOTOR_CONFIG.idleMode(IdleMode.kCoast);
} }
// public static final TalonFXConfiguration ARM_MOTOR_CONFIG = new TalonFXConfiguration() // public static final TalonFXConfiguration ARM_MOTOR_CONFIG = new TalonFXConfiguration()
@@ -20,6 +20,8 @@ public interface IntakeIO {
boolean retractedLimitSwitch = false; boolean retractedLimitSwitch = false;
boolean extendedSoftLimit = false; boolean extendedSoftLimit = false;
boolean retractedSoftLimit = false; boolean retractedSoftLimit = false;
boolean encoderConnected = false;
Angle intakeEncoder = Rotations.of(0); Angle intakeEncoder = Rotations.of(0);
Angle armAngle = Rotations.of(0); Angle armAngle = Rotations.of(0);
@@ -119,6 +119,8 @@ public class IntakeReal implements IntakeIO {
state.extendedSoftLimit = extendedLimit(); state.extendedSoftLimit = extendedLimit();
state.intakeEncoder = m_encoder.getRotations(); state.intakeEncoder = m_encoder.getRotations();
state.encoderConnected = m_encoder.isConnected();
state.retractedLimitSwitch = m_armMotor.getReverseLimitSwitch().isPressed(); state.retractedLimitSwitch = m_armMotor.getReverseLimitSwitch().isPressed();
if(state.retractedLimitSwitch) { if(state.retractedLimitSwitch) {
@@ -128,6 +130,7 @@ public class IntakeReal implements IntakeIO {
@Override @Override
public void updateGains() { public void updateGains() {
m_encoder.loadRotations();
// IntakeConstants.ARM_PID.kP = IntakeConstants.arm_kP.get(); // IntakeConstants.ARM_PID.kP = IntakeConstants.arm_kP.get();
// IntakeConstants.ARM_PID.kI = IntakeConstants.arm_kI.get(); // IntakeConstants.ARM_PID.kI = IntakeConstants.arm_kI.get();
@@ -0,0 +1,100 @@
package frc4388.utility.compute;
import static edu.wpi.first.units.Units.Rotations;
import java.io.FileInputStream;
import java.io.FileOutputStream;
import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.wpilibj.DutyCycleEncoder;
public class JankCoder {
DutyCycleEncoder m_encoder;
boolean loaded_rotations = false;
double lastRotation = 0;
double offset = 0;
public JankCoder(int dio_channel) {
m_encoder = new DutyCycleEncoder(dio_channel);
loadRotations();
}
public JankCoder(int dio_channel, double _offset) {
m_encoder = new DutyCycleEncoder(dio_channel);
loadRotations();
}
public void update() {
if(!m_encoder.isConnected()) {
return;
}
if(!loaded_rotations) {
loadRotations();
} else {
double curRot = m_encoder.get();
if(lastRotation - curRot > 0.5) {
offset += 1;
saveRotations();
} else if (curRot - lastRotation > 0.5) {
offset -= 1;
saveRotations();
}
lastRotation = curRot;
}
}
public double get() {
return (double) offset + m_encoder.get();
}
public Angle getRotations() {
return Rotations.of(get());
}
public int getRotationCount() {
return (int) offset;
}
public void resetRotation() {
setRotation(0);
}
public void setRotation(double rotation) {
offset = rotation - m_encoder.get();
saveRotations();
}
private void saveRotations() {
try (FileOutputStream stream = new FileOutputStream("/home/lvuser/encoder" + m_encoder.getSourceChannel())) {
stream.write(DataUtils.doubleToByteArray(offset));
} catch (Exception e) {
// e.printStackTrace();
System.out.println("ENCODER: Unable to write to trim file `" + m_encoder.getSourceChannel() + "`!?!");
}
}
private boolean loadRotations() {
lastRotation = m_encoder.get();
this.loaded_rotations = true;
try (FileInputStream stream = new FileInputStream("/home/lvuser/encoder" + m_encoder.getSourceChannel())) {
offset = DataUtils.byteArrayToDouble(stream.readNBytes(4));
// clampModify();
// modified = false;
// if (fileValue != currentValue) {
// // System.out.println("TRIMS: Loaded trim `" + trimName + "` has a value that is higher than or less than the bounds set for the trim, clamping...");
// // modified = true;
// }
return true;
} catch (Exception e) {
// e.printStackTrace();
System.out.println("ENCODER: Unable to read encoder `" + m_encoder.getSourceChannel() + "`, using current value...");
return false;
}
}
}
@@ -7,6 +7,7 @@ import java.io.FileOutputStream;
import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.wpilibj.DutyCycleEncoder; import edu.wpi.first.wpilibj.DutyCycleEncoder;
import frc4388.utility.configurable.ConfigurableDouble;
public class JankCoder { public class JankCoder {
DutyCycleEncoder m_encoder; DutyCycleEncoder m_encoder;
@@ -14,23 +15,18 @@ public class JankCoder {
boolean loaded_rotations = false; boolean loaded_rotations = false;
int rotations = 0; int rotations = 0;
double lastRotation = 0; double lastRotation = 0;
final double offset; final ConfigurableDouble offset;
public JankCoder(int dio_channel) { public JankCoder(int dio_channel, ConfigurableDouble offset) {
this.offset = 0;
m_encoder = new DutyCycleEncoder(dio_channel);
loadRotations();
}
public JankCoder(int dio_channel, double offset) {
this.offset = offset; this.offset = offset;
m_encoder = new DutyCycleEncoder(dio_channel); m_encoder = new DutyCycleEncoder(dio_channel);
loadRotations(); loadRotations();
} }
public void update() { public void update() {
if(!m_encoder.isConnected()) { // if(!m_encoder.isConnected()) {
return; // return;
} // }
if(!loaded_rotations) { if(!loaded_rotations) {
loadRotations(); loadRotations();
@@ -49,7 +45,7 @@ public class JankCoder {
} }
public double get() { public double get() {
return (double) rotations + m_encoder.get() + offset; return (double) rotations + m_encoder.get() + offset.get();
} }
public Angle getRotations() { public Angle getRotations() {
@@ -61,6 +57,7 @@ public class JankCoder {
} }
public void resetRotations() { public void resetRotations() {
offset.set(-m_encoder.get());
setRotations(0); setRotations(0);
} }
@@ -69,7 +66,11 @@ public class JankCoder {
saveRotations(); saveRotations();
} }
private void saveRotations() { public boolean isConnected() {
return m_encoder.isConnected();
}
public void saveRotations() {
try (FileOutputStream stream = new FileOutputStream("/home/lvuser/encoder" + m_encoder.getSourceChannel())) { try (FileOutputStream stream = new FileOutputStream("/home/lvuser/encoder" + m_encoder.getSourceChannel())) {
stream.write(DataUtils.intToByteArray(rotations)); stream.write(DataUtils.intToByteArray(rotations));
} catch (Exception e) { } catch (Exception e) {
@@ -78,7 +79,7 @@ public class JankCoder {
} }
} }
private boolean loadRotations() { public boolean loadRotations() {
lastRotation = m_encoder.get(); lastRotation = m_encoder.get();
this.loaded_rotations = true; this.loaded_rotations = true;
@@ -20,4 +20,8 @@ public class ConfigurableDouble {
public double get() { public double get() {
return SmartDashboard.getNumber(name, defualtValue); return SmartDashboard.getNumber(name, defualtValue);
} }
public void set(double value) {
SmartDashboard.putNumber(name, value);
}
} }