Skip to content

Commit

Permalink
we shot a note
Browse files Browse the repository at this point in the history
  • Loading branch information
r4stered committed Oct 5, 2024
1 parent 28d4f57 commit 6a45868
Show file tree
Hide file tree
Showing 7 changed files with 20 additions and 20 deletions.
20 changes: 10 additions & 10 deletions src/main/cpp/RobotContainer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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());
Expand Down Expand Up @@ -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; }

Expand Down
2 changes: 1 addition & 1 deletion src/main/deploy/commit.txt
Original file line number Diff line number Diff line change
@@ -1 +1 @@
9255fe7
28d4f57
8 changes: 4 additions & 4 deletions src/main/include/RobotContainer.h
Original file line number Diff line number Diff line change
Expand Up @@ -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();

Expand All @@ -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;

Expand Down
2 changes: 1 addition & 1 deletion src/main/include/constants/ShooterConstants.h
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
2 changes: 1 addition & 1 deletion src/main/include/subsystems/FeederSubsystem.h
Original file line number Diff line number Diff line change
Expand Up @@ -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{
Expand Down
2 changes: 1 addition & 1 deletion src/main/include/subsystems/IntakeSubsystem.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<units::volt_t> intakeMotorVoltageSig =
intakeMotor.GetMotorVoltage();
ctre::phoenix6::StatusSignal<units::ampere_t> intakeMotorTorqueCurrentSig =
Expand Down
4 changes: 2 additions & 2 deletions src/main/include/subsystems/ShooterSubsystem.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<units::turn_t> topMotorPosSig = topWheelMotor.GetPosition();
ctre::phoenix6::StatusSignal<units::turns_per_second_t> topMotorVelSig = topWheelMotor.GetVelocity();
Expand Down

0 comments on commit 6a45868

Please sign in to comment.