From: Saara21 <113394225+Saara21@users.noreply.github.com> Date: Mon, 9 Feb 2026 23:39:48 +0000 (-0800) Subject: ._. sim X-Git-Url: https://git.taranathan.com/?a=commitdiff_plain;h=e738e6dca4b1a4011abe9922ee6804b0dcb59581;p=FRC2026.git ._. sim --- diff --git a/src/main/java/frc/robot/constants/IntakeConstants.java b/src/main/java/frc/robot/constants/IntakeConstants.java index 3611a9c..adfef65 100644 --- a/src/main/java/frc/robot/constants/IntakeConstants.java +++ b/src/main/java/frc/robot/constants/IntakeConstants.java @@ -19,7 +19,7 @@ public class IntakeConstants { // Intake positions - public static final double maxExtension = 12; // in inches: convert to rotations later + public static final double maxExtension = 14.856; // in inches: convert to rotations later public static final double startingPoint = 0; public static final double rackPitch = 10; diff --git a/src/main/java/frc/robot/subsystems/Intake/Intake.java b/src/main/java/frc/robot/subsystems/Intake/Intake.java index b3babc1..1a83bc9 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Intake.java +++ b/src/main/java/frc/robot/subsystems/Intake/Intake.java @@ -8,6 +8,7 @@ import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.signals.MotorAlignmentValue; import com.ctre.phoenix6.signals.MotorArrangementValue; import com.ctre.phoenix6.signals.NeutralModeValue; +import com.ctre.phoenix6.signals.InvertedValue; import com.fasterxml.jackson.databind.ser.std.InetAddressSerializer; import com.revrobotics.spark.config.SparkMaxConfig; @@ -21,7 +22,10 @@ import edu.wpi.first.wpilibj.util.Color8Bit; import edu.wpi.first.wpilibj2.command.InstantCommand; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.constants.IntakeConstants; - +import edu.wpi.first.math.system.plant.LinearSystemId; +import edu.wpi.first.math.Num; +import edu.wpi.first.math.system.LinearSystem; +import org.ejml.simple.SimpleMatrix; public class Intake extends SubsystemBase { private final Mechanism2d mechanism; @@ -44,18 +48,29 @@ public class Intake extends SubsystemBase { leftMotor = new TalonFX(IntakeConstants.leftID); rollerMotor = new TalonFX(IntakeConstants.rollerID); DCMotor dcmotor = DCMotor.getKrakenX44(2); + + intakeSim = new DCMotorSim( + LinearSystemId.createDCMotorSystem( + DCMotor.getKrakenX44(2), // motor model + 0.001, // MOI (kg·m²) – tune later + IntakeConstants.gearRatio + ), + DCMotor.getKrakenX44(2) +); + rightMotor.getSimState().setSupplyVoltage(12.0); double mechFreeSpeed = 125.0/ IntakeConstants.gearRatio; maxVelocity = 0.5 * mechFreeSpeed; maxAcceleration = maxVelocity / 0.25; + // right motor configs TalonFXConfiguration Config = new TalonFXConfiguration(); var slot0Configs = Config.Slot0; //find values later //friction, maybe? - slot0Configs.kP = 0.1; + slot0Configs.kP = 0; slot0Configs.kI = 0; slot0Configs.kD = 0; slot0Configs.kV = 0;