Skip to content

Commit

Permalink
more fixes
Browse files Browse the repository at this point in the history
Signed-off-by: Jade Turner <[email protected]>
  • Loading branch information
spacey-sooty committed Jan 24, 2025
1 parent 980a48c commit f93695f
Show file tree
Hide file tree
Showing 3 changed files with 11 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@ public class IntakeConstants {
public static double intakeVolts = 8;
public static int intakeCurrentLimit = 40;
public static double motorReduction = 1.0;
public static double intakeMoi = 1.0;
public static int intakeMotorId = 99;
public static int intakeFrontSensorPort = 99;
public static int intakeBackSensorPort = 99;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,15 +4,19 @@

import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
import com.revrobotics.spark.config.SparkMaxConfig;
import edu.wpi.first.wpilibj.DigitalInput;

public class IntakeIONEO implements IntakeIO {
private final SparkMax intakeNeo = new SparkMax(intakeMotorId, MotorType.kBrushless);
private final DigitalInput frontSensor = new DigitalInput(intakeFrontSensorPort);
private final DigitalInput backSensor = new DigitalInput(intakeBackSensorPort);

// TODO apply configs
public IntakeIONEO() {}
public IntakeIONEO() {
SparkMaxConfig config = new SparkMaxConfig();
config.smartCurrentLimit(0, intakeCurrentLimit).idleMode(IdleMode.kCoast);
}

@Override
public void updateInputs(IntakeIOInputs inputs) {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
package org.curtinfrc.frc2025.subsystems.intake;

import static org.curtinfrc.frc2025.subsystems.intake.IntakeConstants.intakeBackSensorPort;
import static org.curtinfrc.frc2025.subsystems.intake.IntakeConstants.intakeFrontSensorPort;
import static org.curtinfrc.frc2025.subsystems.intake.IntakeConstants.*;

import edu.wpi.first.hal.SimBoolean;
import edu.wpi.first.hal.SimDevice;
Expand All @@ -21,7 +20,9 @@ public class IntakeIOSim implements IntakeIO {

public IntakeIOSim() {
intakeMotorSim =
new DCMotorSim(LinearSystemId.createDCMotorSystem(intakeMotor, 0.025, 4.0), intakeMotor);
new DCMotorSim(
LinearSystemId.createDCMotorSystem(intakeMotor, intakeMoi, motorReduction),
intakeMotor);

frontImpl = SimDevice.create("IntakeSensorFront", intakeFrontSensorPort);
frontSensor = frontImpl.createBoolean("IsTriggered", Direction.kInput, false);
Expand Down

0 comments on commit f93695f

Please sign in to comment.