mirror of
https://github.com/Team4388/2026KPopRobotHunters.git
synced 2026-06-08 16:28:05 -06:00
Switch Motor type
This commit is contained in:
@@ -101,7 +101,7 @@ public class RobotMap {
|
|||||||
|
|
||||||
//Configure Intake 20,21
|
//Configure Intake 20,21
|
||||||
SparkMax arm = new SparkMax(IntakeConstants.ARM_ID.id, com.revrobotics.spark.SparkLowLevel.MotorType.kBrushless);
|
SparkMax arm = new SparkMax(IntakeConstants.ARM_ID.id, com.revrobotics.spark.SparkLowLevel.MotorType.kBrushless);
|
||||||
SparkMax roller = new SparkMax(IntakeConstants.ROLLER_ID.id, com.revrobotics.spark.SparkLowLevel.MotorType.kBrushless);
|
TalonFX roller = new TalonFX(IntakeConstants.ROLLER_ID.id, Constants.CANIVORE_CANBUS);
|
||||||
// DigitalInput armLimitSwitch = new DigitalInput(IntakeConstants.ARM_LIMIT_SWITCH_CHANNEL);
|
// DigitalInput armLimitSwitch = new DigitalInput(IntakeConstants.ARM_LIMIT_SWITCH_CHANNEL);
|
||||||
// DigitalInput basinLimitSwitch = new DigitalInput(ElevatorConstants.BASIN_LIMIT_SWITCH);
|
// DigitalInput basinLimitSwitch = new DigitalInput(ElevatorConstants.BASIN_LIMIT_SWITCH);
|
||||||
// DigitalInput endeffectorLimitSwitch = new DigitalInput(ElevatorConstants.ENDEFFECTOR_LIMIT_SWITCH);
|
// DigitalInput endeffectorLimitSwitch = new DigitalInput(ElevatorConstants.ENDEFFECTOR_LIMIT_SWITCH);
|
||||||
@@ -120,7 +120,7 @@ public class RobotMap {
|
|||||||
FaultTalonFX.addDevice(shooter2, "Shooter2");
|
FaultTalonFX.addDevice(shooter2, "Shooter2");
|
||||||
FaultTalonFX.addDevice(indexer, "Indexer");
|
FaultTalonFX.addDevice(indexer, "Indexer");
|
||||||
FaultSparkMax.addDevice(arm, "Arm");
|
FaultSparkMax.addDevice(arm, "Arm");
|
||||||
FaultSparkMax.addDevice(roller, "Roller");
|
FaultTalonFX.addDevice(roller, "Roller");
|
||||||
|
|
||||||
FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getDriveMotor(), "Module 0 Drive");
|
FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getDriveMotor(), "Module 0 Drive");
|
||||||
FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getSteerMotor(), "Module 0 Steer");
|
FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getSteerMotor(), "Module 0 Steer");
|
||||||
|
|||||||
@@ -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 = 197;
|
public static final int GIT_REVISION = 198;
|
||||||
public static final String GIT_SHA = "2407a900c901efca8c60d0a6143e39db7cf90201";
|
public static final String GIT_SHA = "958bdc46fd90b8388750f8bf1a95b62ff91b2092";
|
||||||
public static final String GIT_DATE = "2026-03-31 19:47:27 MDT";
|
public static final String GIT_DATE = "2026-03-31 20:51:47 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 20:33:43 MDT";
|
public static final String BUILD_DATE = "2026-04-01 17:29:06 MDT";
|
||||||
public static final long BUILD_UNIX_TIME = 1775010823079L;
|
public static final long BUILD_UNIX_TIME = 1775086146983L;
|
||||||
public static final int DIRTY = 1;
|
public static final int DIRTY = 1;
|
||||||
|
|
||||||
private BuildConstants(){}
|
private BuildConstants(){}
|
||||||
|
|||||||
@@ -1,5 +1,9 @@
|
|||||||
package frc4388.robot.subsystems.intake;
|
package frc4388.robot.subsystems.intake;
|
||||||
|
|
||||||
|
import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
|
||||||
|
import com.ctre.phoenix6.configs.MotorOutputConfigs;
|
||||||
|
import com.ctre.phoenix6.configs.TalonFXConfiguration;
|
||||||
|
import com.ctre.phoenix6.signals.NeutralModeValue;
|
||||||
import com.revrobotics.spark.FeedbackSensor;
|
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;
|
||||||
@@ -85,7 +89,7 @@ public class IntakeConstants {
|
|||||||
// Motor configs
|
// Motor configs
|
||||||
|
|
||||||
public static final SparkMaxConfig ARM_MOTOR_CONFIG = new SparkMaxConfig();
|
public static final SparkMaxConfig ARM_MOTOR_CONFIG = new SparkMaxConfig();
|
||||||
public static final SparkMaxConfig ROLELR_MOTOR_CONFIG = new SparkMaxConfig();
|
public static final CanDevice ROLLER_MOTOR_ID = new CanDevice("INTAKE_ROLLER", 21);
|
||||||
|
|
||||||
static {
|
static {
|
||||||
ARM_MOTOR_CONFIG.limitSwitch
|
ARM_MOTOR_CONFIG.limitSwitch
|
||||||
@@ -101,7 +105,7 @@ public class IntakeConstants {
|
|||||||
ARM_MOTOR_CONFIG.idleMode(IdleMode.kBrake);
|
ARM_MOTOR_CONFIG.idleMode(IdleMode.kBrake);
|
||||||
|
|
||||||
|
|
||||||
ROLELR_MOTOR_CONFIG.idleMode(IdleMode.kCoast);
|
// ROLLER_MOTOR_CONFIG.idleMode(IdleMode.kCoast);
|
||||||
}
|
}
|
||||||
|
|
||||||
// public static final TalonFXConfiguration ARM_MOTOR_CONFIG = new TalonFXConfiguration()
|
// public static final TalonFXConfiguration ARM_MOTOR_CONFIG = new TalonFXConfiguration()
|
||||||
@@ -115,14 +119,14 @@ public class IntakeConstants {
|
|||||||
// .withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means
|
// .withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means
|
||||||
// );
|
// );
|
||||||
|
|
||||||
// public static final TalonFXConfiguration ROLLER_MOTOR_CONFIG = new TalonFXConfiguration()
|
public static final TalonFXConfiguration ROLLER_MOTOR_CONFIG = new TalonFXConfiguration()
|
||||||
// .withCurrentLimits(
|
.withCurrentLimits(
|
||||||
// new CurrentLimitsConfigs()
|
new CurrentLimitsConfigs()
|
||||||
// .withStatorCurrentLimit(40) // TODO: tune???
|
.withStatorCurrentLimit(40) // TODO: tune???
|
||||||
// .withStatorCurrentLimitEnable(true)
|
.withStatorCurrentLimitEnable(true)
|
||||||
// ).withMotorOutput(
|
).withMotorOutput(
|
||||||
// new MotorOutputConfigs()
|
new MotorOutputConfigs()
|
||||||
// .withNeutralMode(NeutralModeValue.Coast) // Must be coast because this is spinny spinny
|
.withNeutralMode(NeutralModeValue.Coast) // Must be coast because this is spinny spinny
|
||||||
// .withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means
|
.withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means
|
||||||
// );
|
);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -21,17 +21,18 @@ import edu.wpi.first.units.measure.Angle;
|
|||||||
import edu.wpi.first.units.measure.Velocity;
|
import edu.wpi.first.units.measure.Velocity;
|
||||||
import edu.wpi.first.wpilibj.DigitalInput;
|
import edu.wpi.first.wpilibj.DigitalInput;
|
||||||
import edu.wpi.first.wpilibj.DutyCycleEncoder;
|
import edu.wpi.first.wpilibj.DutyCycleEncoder;
|
||||||
|
import frc4388.robot.subsystems.shooter.ShooterConstants;
|
||||||
import frc4388.utility.compute.JankCoder;
|
import frc4388.utility.compute.JankCoder;
|
||||||
|
|
||||||
public class IntakeReal implements IntakeIO {
|
public class IntakeReal implements IntakeIO {
|
||||||
|
|
||||||
SparkMax m_armMotor;
|
SparkMax m_armMotor;
|
||||||
SparkMax m_rollerMotor;
|
TalonFX m_rollerMotor;
|
||||||
JankCoder m_encoder;
|
JankCoder m_encoder;
|
||||||
|
|
||||||
public IntakeReal(
|
public IntakeReal(
|
||||||
SparkMax armMotor,
|
SparkMax armMotor,
|
||||||
SparkMax rollerMotor,
|
TalonFX rollerMotor,
|
||||||
JankCoder jankCoder
|
JankCoder jankCoder
|
||||||
) {
|
) {
|
||||||
// m_angleMotor = angleMotor;
|
// m_angleMotor = angleMotor;
|
||||||
@@ -41,7 +42,7 @@ public class IntakeReal implements IntakeIO {
|
|||||||
m_encoder = jankCoder;
|
m_encoder = jankCoder;
|
||||||
|
|
||||||
m_armMotor.configure(IntakeConstants.ARM_MOTOR_CONFIG, ResetMode.kNoResetSafeParameters, PersistMode.kPersistParameters);
|
m_armMotor.configure(IntakeConstants.ARM_MOTOR_CONFIG, ResetMode.kNoResetSafeParameters, PersistMode.kPersistParameters);
|
||||||
m_rollerMotor.configure(IntakeConstants.ROLELR_MOTOR_CONFIG, ResetMode.kNoResetSafeParameters, PersistMode.kPersistParameters);
|
m_rollerMotor.getConfigurator().apply(IntakeConstants.ROLLER_MOTOR_CONFIG);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@@ -113,7 +114,7 @@ public class IntakeReal implements IntakeIO {
|
|||||||
state.armMotorCurrent = Amps.of(m_armMotor.getOutputCurrent());
|
state.armMotorCurrent = Amps.of(m_armMotor.getOutputCurrent());
|
||||||
|
|
||||||
state.rollerOutput = m_rollerMotor.get();
|
state.rollerOutput = m_rollerMotor.get();
|
||||||
state.rollerMotorCurrent = Amps.of(m_rollerMotor.getOutputCurrent());
|
// state.rollerMotorCurrent = Amps.of(m_rollerMotor.getOutputCurrent());
|
||||||
|
|
||||||
state.retractedSoftLimit = retractedLimit();
|
state.retractedSoftLimit = retractedLimit();
|
||||||
state.extendedSoftLimit = extendedLimit();
|
state.extendedSoftLimit = extendedLimit();
|
||||||
|
|||||||
Reference in New Issue
Block a user