diff --git a/src/main/cpp/RobotContainer.cpp b/src/main/cpp/RobotContainer.cpp index 1c33a40..dc4ee23 100644 --- a/src/main/cpp/RobotContainer.cpp +++ b/src/main/cpp/RobotContainer.cpp @@ -69,10 +69,10 @@ void RobotContainer::ConfigureBindings() { // controller.POVUp().OnTrue(swerveSubsystem.TuneDrivePID([this] { return // controller.Start().Get(); })); - // controller.A().WhileTrue(shooterSubsystem.RunShooter( - // [] { return consts::shooter::PRESET_SPEEDS::AMP; })); - // controller.A().OnFalse(shooterSubsystem.RunShooter( - // [] { return consts::shooter::PRESET_SPEEDS::OFF; })); + controller.A().WhileTrue(shooterSubsystem.RunShooter( + [] { return consts::shooter::PRESET_SPEEDS::AMP; })); + controller.A().OnFalse(shooterSubsystem.RunShooter( + [] { return consts::shooter::PRESET_SPEEDS::OFF; })); controller.LeftTrigger().WhileTrue(intakeSubsystem.IntakeNote()); controller.RightTrigger().WhileTrue(intakeSubsystem.PoopNote()); @@ -123,17 +123,17 @@ SwerveSubsystem &RobotContainer::GetSwerveSubsystem() { return swerveSubsystem; } -// ShooterSubsystem &RobotContainer::GetShooterSubsystem() { -// return shooterSubsystem; -// } +ShooterSubsystem &RobotContainer::GetShooterSubsystem() { + return shooterSubsystem; +} IntakeSubsystem &RobotContainer::GetIntakeSubsystem() { return intakeSubsystem; } -// FeederSubsystem &RobotContainer::GetFeederSubsystem() { -// return feederSubsystem; -// } +FeederSubsystem &RobotContainer::GetFeederSubsystem() { + return feederSubsystem; +} // str::Vision &RobotContainer::GetVision() { return vision; } diff --git a/src/main/deploy/commit.txt b/src/main/deploy/commit.txt index 3aacab5..a3bc95f 100644 --- a/src/main/deploy/commit.txt +++ b/src/main/deploy/commit.txt @@ -1 +1 @@ -9255fe7 \ No newline at end of file +28d4f57 \ No newline at end of file diff --git a/src/main/include/RobotContainer.h b/src/main/include/RobotContainer.h index 91e9a8b..1fc5822 100644 --- a/src/main/include/RobotContainer.h +++ b/src/main/include/RobotContainer.h @@ -20,9 +20,9 @@ class RobotContainer { frc2::Command *GetAutonomousCommand(); SwerveSubsystem &GetSwerveSubsystem(); - // ShooterSubsystem &GetShooterSubsystem(); + ShooterSubsystem &GetShooterSubsystem(); IntakeSubsystem &GetIntakeSubsystem(); - // FeederSubsystem &GetFeederSubsystem(); + FeederSubsystem &GetFeederSubsystem(); //str::Vision &GetVision(); //str::NoteVisualizer &GetNoteVisualizer(); @@ -31,9 +31,9 @@ class RobotContainer { frc2::CommandXboxController controller{0}; SwerveSubsystem swerveSubsystem; - // ShooterSubsystem shooterSubsystem; + ShooterSubsystem shooterSubsystem; IntakeSubsystem intakeSubsystem; - // FeederSubsystem feederSubsystem; + FeederSubsystem feederSubsystem; // str::Vision vision; // str::NoteVisualizer noteVisualizer; diff --git a/src/main/include/constants/ShooterConstants.h b/src/main/include/constants/ShooterConstants.h index a29c4d1..8af5a9a 100644 --- a/src/main/include/constants/ShooterConstants.h +++ b/src/main/include/constants/ShooterConstants.h @@ -25,7 +25,7 @@ inline constexpr units::ampere_t STATOR_CURRENT_LIMIT = 180_A; namespace physical { -inline constexpr bool TOP_INVERT = false; +inline constexpr bool TOP_INVERT = true; inline constexpr bool BOTTOM_INVERT = true; inline constexpr units::scalar_t SHOOTER_RATIO = (1.0 / 1.0); diff --git a/src/main/include/subsystems/FeederSubsystem.h b/src/main/include/subsystems/FeederSubsystem.h index e2c6278..218a769 100644 --- a/src/main/include/subsystems/FeederSubsystem.h +++ b/src/main/include/subsystems/FeederSubsystem.h @@ -35,7 +35,7 @@ class FeederSubsystem : public frc2::SubsystemBase { void UpdateNTEntries(); ctre::phoenix6::hardware::TalonFX feederMotor{consts::feeder::can_ids::FEEDER, - "*"}; + "rio"}; frc::DigitalInput noteSensor{consts::feeder::ports::NOTE_SENSOR_PORT}; frc::Debouncer noteSensorDebouncer{ diff --git a/src/main/include/subsystems/IntakeSubsystem.h b/src/main/include/subsystems/IntakeSubsystem.h index 90ca30e..762dbb9 100644 --- a/src/main/include/subsystems/IntakeSubsystem.h +++ b/src/main/include/subsystems/IntakeSubsystem.h @@ -39,7 +39,7 @@ class IntakeSubsystem : public frc2::SubsystemBase { bool ConfigureMotorSignals(); ctre::phoenix6::hardware::TalonFX intakeMotor{consts::intake::can_ids::INTAKE, - "*"}; + "rio"}; ctre::phoenix6::StatusSignal intakeMotorVoltageSig = intakeMotor.GetMotorVoltage(); ctre::phoenix6::StatusSignal intakeMotorTorqueCurrentSig = diff --git a/src/main/include/subsystems/ShooterSubsystem.h b/src/main/include/subsystems/ShooterSubsystem.h index 0a662d9..1529f05 100644 --- a/src/main/include/subsystems/ShooterSubsystem.h +++ b/src/main/include/subsystems/ShooterSubsystem.h @@ -53,8 +53,8 @@ class ShooterSubsystem : public frc2::SubsystemBase { units::ampere_t statorCurrentLimit); bool ConfigureMotorSignals(); - ctre::phoenix6::hardware::TalonFX topWheelMotor{consts::shooter::can_ids::TOP_SHOOTER, "*"}; - ctre::phoenix6::hardware::TalonFX bottomWheelMotor{consts::shooter::can_ids::BOTTOM_SHOOTER, "*"}; + ctre::phoenix6::hardware::TalonFX topWheelMotor{consts::shooter::can_ids::TOP_SHOOTER, "rio"}; + ctre::phoenix6::hardware::TalonFX bottomWheelMotor{consts::shooter::can_ids::BOTTOM_SHOOTER, "rio"}; ctre::phoenix6::StatusSignal topMotorPosSig = topWheelMotor.GetPosition(); ctre::phoenix6::StatusSignal topMotorVelSig = topWheelMotor.GetVelocity();