mirror of
https://github.com/Team4388/2022NoWayHome.git
synced 2026-06-09 08:48:07 -06:00
hood change
This commit is contained in:
@@ -95,7 +95,7 @@ public class RobotContainer {
|
|||||||
private final Storage m_robotStorage = new Storage(m_robotMap.storageMotor, m_robotMap.beamIntake, m_robotMap.beamShooter);
|
private final Storage m_robotStorage = new Storage(m_robotMap.storageMotor, m_robotMap.beamIntake, m_robotMap.beamShooter);
|
||||||
private final LED m_robotLED = new LED(m_robotMap.LEDController);
|
private final LED m_robotLED = new LED(m_robotMap.LEDController);
|
||||||
private final BoomBoom m_robotBoomBoom = new BoomBoom(m_robotMap.shooterFalconLeft, m_robotMap.shooterFalconRight);
|
private final BoomBoom m_robotBoomBoom = new BoomBoom(m_robotMap.shooterFalconLeft, m_robotMap.shooterFalconRight);
|
||||||
private final Hood m_robotHood = new Hood();
|
private final Hood m_robotHood = new Hood(m_robotMap.angleAdjusterMotor);
|
||||||
private final Turret m_robotTurret = new Turret(m_robotMap.shooterTurret);
|
private final Turret m_robotTurret = new Turret(m_robotMap.shooterTurret);
|
||||||
private final VisionOdometry m_robotVisionOdometry = new VisionOdometry(m_robotSwerveDrive, m_robotTurret);
|
private final VisionOdometry m_robotVisionOdometry = new VisionOdometry(m_robotSwerveDrive, m_robotTurret);
|
||||||
private final Vision m_robotVision = new Vision(m_robotTurret, m_robotBoomBoom);
|
private final Vision m_robotVision = new Vision(m_robotTurret, m_robotBoomBoom);
|
||||||
|
|||||||
@@ -13,6 +13,7 @@ import com.ctre.phoenix.sensors.CANCoder;
|
|||||||
import com.ctre.phoenix.sensors.WPI_PigeonIMU;
|
import com.ctre.phoenix.sensors.WPI_PigeonIMU;
|
||||||
|
|
||||||
import com.revrobotics.CANSparkMax;
|
import com.revrobotics.CANSparkMax;
|
||||||
|
import com.revrobotics.CANSparkMax.IdleMode;
|
||||||
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
|
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj.DigitalInput;
|
import edu.wpi.first.wpilibj.DigitalInput;
|
||||||
@@ -32,17 +33,15 @@ import frc4388.robot.subsystems.SwerveModule;
|
|||||||
public class RobotMap {
|
public class RobotMap {
|
||||||
|
|
||||||
public RobotMap() {
|
public RobotMap() {
|
||||||
// configureLEDMotorControllers();
|
configureLEDMotorControllers();
|
||||||
configureSwerveMotorControllers();
|
configureSwerveMotorControllers();
|
||||||
// configureShooterMotorControllers();
|
configureShooterMotorControllers();
|
||||||
}
|
}
|
||||||
|
|
||||||
/* LED Subsystem */
|
/* LED Subsystem */
|
||||||
public final Spark LEDController = new Spark(LEDConstants.LED_SPARK_ID);
|
public final Spark LEDController = new Spark(LEDConstants.LED_SPARK_ID);
|
||||||
|
|
||||||
void configureLEDMotorControllers() {
|
void configureLEDMotorControllers() {}
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
/* Swerve Subsystem */
|
/* Swerve Subsystem */
|
||||||
|
|
||||||
@@ -167,8 +166,12 @@ public class RobotMap {
|
|||||||
public final WPI_TalonFX shooterFalconLeft = new WPI_TalonFX(ShooterConstants.SHOOTER_FALCON_LEFT_CAN_ID);
|
public final WPI_TalonFX shooterFalconLeft = new WPI_TalonFX(ShooterConstants.SHOOTER_FALCON_LEFT_CAN_ID);
|
||||||
public final WPI_TalonFX shooterFalconRight = new WPI_TalonFX(ShooterConstants.SHOOTER_FALCON_RIGHT_CAN_ID);
|
public final WPI_TalonFX shooterFalconRight = new WPI_TalonFX(ShooterConstants.SHOOTER_FALCON_RIGHT_CAN_ID);
|
||||||
|
|
||||||
|
// turret subsystem
|
||||||
public final CANSparkMax shooterTurret = new CANSparkMax(ShooterConstants.TURRET_MOTOR_CAN_ID, MotorType.kBrushless);
|
public final CANSparkMax shooterTurret = new CANSparkMax(ShooterConstants.TURRET_MOTOR_CAN_ID, MotorType.kBrushless);
|
||||||
|
|
||||||
|
// hood subsystem
|
||||||
|
public CANSparkMax angleAdjusterMotor = new CANSparkMax(ShooterConstants.SHOOTER_ANGLE_ADJUST_ID, MotorType.kBrushless);
|
||||||
|
|
||||||
// Create motor CANSparkMax
|
// Create motor CANSparkMax
|
||||||
void configureShooterMotorControllers() {
|
void configureShooterMotorControllers() {
|
||||||
|
|
||||||
@@ -209,6 +212,9 @@ public class RobotMap {
|
|||||||
// SupplyCurrentLimitConfiguration(true, 12, 13, 0.4)); // TODO: dont pull
|
// SupplyCurrentLimitConfiguration(true, 12, 13, 0.4)); // TODO: dont pull
|
||||||
// numbers out of our ass anymore
|
// numbers out of our ass anymore
|
||||||
|
|
||||||
|
// hood subsystem
|
||||||
|
angleAdjusterMotor.restoreFactoryDefaults();
|
||||||
|
angleAdjusterMotor.setIdleMode(IdleMode.kBrake);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -24,7 +24,7 @@ import frc4388.utility.Gains;
|
|||||||
public class Hood extends SubsystemBase {
|
public class Hood extends SubsystemBase {
|
||||||
public BoomBoom m_shooterSubsystem;
|
public BoomBoom m_shooterSubsystem;
|
||||||
|
|
||||||
public CANSparkMax m_angleAdjusterMotor = new CANSparkMax(ShooterConstants.SHOOTER_ANGLE_ADJUST_ID, MotorType.kBrushless);
|
public CANSparkMax m_angleAdjusterMotor;
|
||||||
public SparkMaxLimitSwitch m_hoodUpLimitSwitch;
|
public SparkMaxLimitSwitch m_hoodUpLimitSwitch;
|
||||||
public SparkMaxLimitSwitch m_hoodDownLimitSwitch;
|
public SparkMaxLimitSwitch m_hoodDownLimitSwitch;
|
||||||
public static Gains m_angleAdjusterGains = ShooterConstants.SHOOTER_ANGLE_GAINS;
|
public static Gains m_angleAdjusterGains = ShooterConstants.SHOOTER_ANGLE_GAINS;
|
||||||
@@ -39,8 +39,9 @@ public double m_fireAngle;
|
|||||||
|
|
||||||
|
|
||||||
/** Creates a new Hood. */
|
/** Creates a new Hood. */
|
||||||
public Hood() {
|
public Hood(CANSparkMax angleAdjusterMotor) {
|
||||||
m_angleAdjusterMotor.setIdleMode(IdleMode.kBrake);
|
|
||||||
|
m_angleAdjusterMotor = angleAdjusterMotor;
|
||||||
|
|
||||||
m_hoodUpLimitSwitch = m_angleAdjusterMotor.getForwardLimitSwitch(SparkMaxLimitSwitch.Type.kNormallyOpen);
|
m_hoodUpLimitSwitch = m_angleAdjusterMotor.getForwardLimitSwitch(SparkMaxLimitSwitch.Type.kNormallyOpen);
|
||||||
m_hoodDownLimitSwitch = m_angleAdjusterMotor.getReverseLimitSwitch(SparkMaxLimitSwitch.Type.kNormallyOpen);
|
m_hoodDownLimitSwitch = m_angleAdjusterMotor.getReverseLimitSwitch(SparkMaxLimitSwitch.Type.kNormallyOpen);
|
||||||
|
|||||||
Reference in New Issue
Block a user