Merge branch 'Shooter' of https://github.com/Team4388/2022NoWayHome into Shooter

This commit is contained in:
Abhishrek05
2022-02-19 10:57:33 -07:00
5 changed files with 48 additions and 24 deletions
@@ -88,7 +88,10 @@ public final class Constants {
public static final class ShooterConstants { public static final class ShooterConstants {
/* PID Constants Shooter */ /* PID Constants Shooter */
<<<<<<< Updated upstream
public static final int CLOSED_LOOP_TIME_MS = 1; public static final int CLOSED_LOOP_TIME_MS = 1;
=======
>>>>>>> Stashed changes
public static final int SHOOTER_TIMEOUT_MS = 32; public static final int SHOOTER_TIMEOUT_MS = 32;
public static final int SHOOTER_SLOT_IDX = 0; public static final int SHOOTER_SLOT_IDX = 0;
public static final int SHOOTER_PID_LOOP_IDX = 1; public static final int SHOOTER_PID_LOOP_IDX = 1;
+34 -19
View File
@@ -5,6 +5,8 @@
package frc4388.robot; package frc4388.robot;
import com.revrobotics.CANSparkMax; import com.revrobotics.CANSparkMax;
import com.ctre.phoenix.motorcontrol.TalonFXControlMode;
import com.ctre.phoenix.motorcontrol.can.TalonFX;
import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Command;
@@ -14,6 +16,7 @@ import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import frc4388.robot.Constants.*; import frc4388.robot.Constants.*;
import frc4388.robot.subsystems.BoomBoom; import frc4388.robot.subsystems.BoomBoom;
import frc4388.robot.subsystems.Hood; import frc4388.robot.subsystems.Hood;
//import frc4388.robot.subsystems.Intake;
import frc4388.robot.subsystems.LED; import frc4388.robot.subsystems.LED;
import frc4388.robot.subsystems.SwerveDrive; import frc4388.robot.subsystems.SwerveDrive;
import frc4388.robot.subsystems.Turret; import frc4388.robot.subsystems.Turret;
@@ -32,23 +35,24 @@ import frc4388.utility.controller.XboxController;
public class RobotContainer { public class RobotContainer {
/* RobotMap */ /* RobotMap */
private final RobotMap m_robotMap = new RobotMap(); private final RobotMap m_robotMap = new RobotMap();
private final TalonFX m_testMotor = new TalonFX(2);
/* Subsystems */ /* Subsystems
// private final SwerveDrive m_robotSwerveDrive = new SwerveDrive( private final SwerveDrive m_robotSwerveDrive = new SwerveDrive(
// m_robotMap.leftFrontSteerMotor, m_robotMap.leftFrontWheelMotor, m_robotMap.leftFrontSteerMotor, m_robotMap.leftFrontWheelMotor,
// m_robotMap.rightFrontSteerMotor, m_robotMap.rightFrontWheelMotor, m_robotMap.rightFrontSteerMotor, m_robotMap.rightFrontWheelMotor,
// m_robotMap.leftBackSteerMotor, m_robotMap.leftBackWheelMotor, m_robotMap.leftBackSteerMotor, m_robotMap.leftBackWheelMotor,
// m_robotMap.rightBackSteerMotor, m_robotMap.rightBackWheelMotor, m_robotMap.rightBackSteerMotor, m_robotMap.rightBackWheelMotor,
// m_robotMap.leftFrontEncoder, m_robotMap.leftFrontEncoder,
// m_robotMap.rightFrontEncoder, m_robotMap.rightFrontEncoder,
// m_robotMap.leftBackEncoder, m_robotMap.leftBackEncoder,
// m_robotMap.rightBackEncoder m_robotMap.rightBackEncoder
// ); );
*/
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();
private final Turret m_robotTurret = new Turret(); private final Turret m_robotTurret = new Turret(m_robotMap.shooterTurret);
private final Vision m_robotVison = new Vision(m_robotTurret, m_robotBoomBoom); private final Vision m_robotVison = new Vision(m_robotTurret, m_robotBoomBoom);
/* Controllers */ /* Controllers */
private final XboxController m_driverXbox = new XboxController(OIConstants.XBOX_DRIVER_ID); private final XboxController m_driverXbox = new XboxController(OIConstants.XBOX_DRIVER_ID);
@@ -62,15 +66,15 @@ public class RobotContainer {
/* Default Commands */ /* Default Commands */
// drives the swerve drive with a two-axis input from the driver controller // drives the swerve drive with a two-axis input from the driver controller
// m_robotSwerveDrive.setDefaultCommand( /*m_robotSwerveDrive.setDefaultCommand(
// new RunCommand(() -> m_robotSwerveDrive.driveWithInput(-getDriverController().getLeftXAxis(), new RunCommand(() -> m_robotSwerveDrive.driveWithInput(-getDriverController().getLeftXAxis(),
// getDriverController().getLeftYAxis(), -getDriverController().getRightXAxis(), false), m_robotSwerveDrive)); getDriverController().getLeftYAxis(), -getDriverController().getRightXAxis(), false), m_robotSwerveDrive));
// continually sends updates to the Blinkin LED controller to keep the lights on // continually sends updates to the Blinkin LED controller to keep the lights on
m_robotLED.setDefaultCommand(new RunCommand(m_robotLED::updateLED, m_robotLED)); m_robotLED.setDefaultCommand(new RunCommand(m_robotLED::updateLED, m_robotLED));
*/
//Turret default command //Turret default command
m_robotTurret.setDefaultCommand( m_robotTurret.setDefaultCommand(
@@ -90,6 +94,10 @@ public class RobotContainer {
/* Operator Buttons */ /* Operator Buttons */
// activates "Lit Mode" // activates "Lit Mode"
new JoystickButton(getDriverJoystick(), XboxController.A_BUTTON)
.whileHeld(() -> m_testMotor.set(TalonFXControlMode.PercentOutput, 0.5));
new JoystickButton(getOperatorJoystick(), XboxController.A_BUTTON) new JoystickButton(getOperatorJoystick(), XboxController.A_BUTTON)
.whenPressed(() -> m_robotLED.setPattern(LEDPatterns.LAVA_RAINBOW)) .whenPressed(() -> m_robotLED.setPattern(LEDPatterns.LAVA_RAINBOW))
.whenReleased(() -> m_robotLED.setPattern(LEDConstants.DEFAULT_PATTERN)); .whenReleased(() -> m_robotLED.setPattern(LEDConstants.DEFAULT_PATTERN));
@@ -97,9 +105,16 @@ public class RobotContainer {
new JoystickButton(getOperatorJoystick(), XboxController.B_BUTTON) new JoystickButton(getOperatorJoystick(), XboxController.B_BUTTON)
.whenPressed(() -> m_robotBoomBoom.runDrumShooterVelocityPID(0.1)) .whenPressed(() -> m_robotBoomBoom.runDrumShooterVelocityPID(0.1))
.whenReleased(() -> m_robotBoomBoom.runDrumShooterVelocityPID(0)); .whenReleased(() -> m_robotBoomBoom.runDrumShooterVelocityPID(0));
/* Driver Buttons */ /* Driver Buttons */
//activates intake
new JoystickButton(getOperatorJoystick(), XboxController.B_BUTTON);
// .whenPressed() -> m_robot
/*operator button*/
//activates hood
new JoystickButton(getOperatorJoystick(), XboxController.Y_BUTTON)
.whenPressed(() -> m_robotHood.runHood(0.5d))
.whenReleased(() -> m_robotHood.runHood(0.d));
// new JoystickButton(getOperatorJoystick());
} }
/** /**
* Use this to pass the autonomous command to the main {@link Robot} class. * Use this to pass the autonomous command to the main {@link Robot} class.
+7 -3
View File
@@ -5,11 +5,12 @@
package frc4388.robot; package frc4388.robot;
import com.ctre.phoenix.motorcontrol.NeutralMode; import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.StatorCurrentLimitConfiguration;
import com.ctre.phoenix.motorcontrol.SupplyCurrentLimitConfiguration;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX; import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX;
import com.ctre.phoenix.sensors.CANCoder; import com.ctre.phoenix.sensors.CANCoder;
import com.revrobotics.CANSparkMax; import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMaxLowLevel.MotorType; import com.revrobotics.CANSparkMaxLowLevel.MotorType;
import edu.wpi.first.wpilibj.motorcontrol.Spark; import edu.wpi.first.wpilibj.motorcontrol.Spark;
import frc4388.robot.Constants.LEDConstants; import frc4388.robot.Constants.LEDConstants;
import frc4388.robot.Constants.ShooterConstants; import frc4388.robot.Constants.ShooterConstants;
@@ -119,9 +120,9 @@ public class RobotMap {
//RIGHT FALCON //RIGHT FALCON
shooterFalconRight.configFactoryDefault();
shooterFalconRight.setNeutralMode(NeutralMode.Coast);
shooterFalconRight.setInverted(false); shooterFalconRight.setInverted(false);
shooterFalconRight.setNeutralMode(NeutralMode.Coast);
shooterFalconRight.configFactoryDefault();
shooterFalconRight.configOpenloopRamp(1, ShooterConstants.SHOOTER_TIMEOUT_MS); shooterFalconRight.configOpenloopRamp(1, ShooterConstants.SHOOTER_TIMEOUT_MS);
shooterFalconRight.configClosedloopRamp(0.75, ShooterConstants.SHOOTER_TIMEOUT_MS); shooterFalconRight.configClosedloopRamp(0.75, ShooterConstants.SHOOTER_TIMEOUT_MS);
//m_shooterFalconRight.configPeakOutputForward(0, ShooterConstants.SHOOTER_TIMEOUT_MS);(comment it in if necessary) //m_shooterFalconRight.configPeakOutputForward(0, ShooterConstants.SHOOTER_TIMEOUT_MS);(comment it in if necessary)
@@ -130,6 +131,9 @@ public class RobotMap {
shooterFalconRight.configSupplyCurrentLimit(ShooterConstants.SUPPLY_CURRENT_LIMIT_CONFIG, ShooterConstants.SHOOTER_TIMEOUT_MS); shooterFalconRight.configSupplyCurrentLimit(ShooterConstants.SUPPLY_CURRENT_LIMIT_CONFIG, ShooterConstants.SHOOTER_TIMEOUT_MS);
/*Turret Subsytem*/ /*Turret Subsytem*/
shooterFalconRight.configStatorCurrentLimit(new StatorCurrentLimitConfiguration(true, 6, 9, 4.2));
shooterFalconLeft.configSupplyCurrentLimit(new SupplyCurrentLimitConfiguration(true, 12, 13, 0.4));
} }
@@ -58,7 +58,7 @@ public BoomBoom(WPI_TalonFX shooterFalconLeft, WPI_TalonFX shooterFalconRight) {
@Override @Override
public void periodic() { public void periodic() {
// This method will be called once per scheduler run // This method will be called once per scheduler run
// Abhi was here
try { try {
// SmartDashboard.putNumber("Drum Velocity", m_shooterFalconLeft.getSelectedSensorVelocity()); // SmartDashboard.putNumber("Drum Velocity", m_shooterFalconLeft.getSelectedSensorVelocity());
@@ -4,6 +4,8 @@
package frc4388.robot.subsystems; package frc4388.robot.subsystems;
import javax.sql.rowset.WebRowSet;
import com.revrobotics.CANSparkMax; import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder; import com.revrobotics.RelativeEncoder;
import com.revrobotics.SparkMaxPIDController; import com.revrobotics.SparkMaxPIDController;
@@ -21,7 +23,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 = new CANSparkMax(ShooterConstants.SHOOTER_ANGLE_ADJUST_ID, MotorType.kBrushless);
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;