Skip to content
This repository was archived by the owner on Jul 20, 2025. It is now read-only.
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions src/main/java/frc/robot/RobotMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,4 +31,9 @@ public static class mapIntake {
public static final int BOTTOM_MOTOR_CAN = 21;
}

public static class mapShooter {
public static final int PROPEL_MOTOR_CAN = 10;
public static final int SHOOT_MOTOR_CAN = 11;
}

}
42 changes: 42 additions & 0 deletions src/main/java/frc/robot/subsystems/Shooter.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.subsystems;

import com.ctre.phoenix6.hardware.TalonFX;

import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.RobotMap;

public class Shooter extends SubsystemBase {
/** Creates a new Shooter. */
TalonFX propelMotor;
TalonFX shootMotor;

public Shooter() {
propelMotor = new TalonFX(RobotMap.mapShooter.PROPEL_MOTOR_CAN);
shootMotor = new TalonFX(RobotMap.mapShooter.SHOOT_MOTOR_CAN);
}

public void setShooterVelocity(double velocity) {
shootMotor.set(velocity);
}

public double getShooterVelocity() {
return shootMotor.get();
}

public void setPropelVelocity(double velocity) {
propelMotor.set(velocity);
}

public double getPropelVelocity() {
return propelMotor.get();
}

@Override
public void periodic() {
// This method will be called once per scheduler run
}
}