Skip to content

Commit

Permalink
Merge branch 'testing' of https://github.com/Creekside7688/FRC-2024 i…
Browse files Browse the repository at this point in the history
…nto testing

asdfsadf
  • Loading branch information
Zylve committed Feb 26, 2024
2 parents 749fe04 + b3c3d81 commit d3e4e39
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 1 deletion.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/constants/ShooterConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

public class ShooterConstants {
public static final int MOTOR_ID = 10;
public static final int CURRENT_LIMIT = 50;
public static final int CURRENT_LIMIT = 90;
public static final IdleMode IDLE_MODE = IdleMode.kCoast;

public static final double SHOOTER_SPINUP_DELAY = 10;
Expand Down
8 changes: 8 additions & 0 deletions src/main/java/frc/robot/shooter/Shooter.java
Original file line number Diff line number Diff line change
@@ -1,21 +1,29 @@
package frc.robot.shooter;

import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder;
import com.revrobotics.CANSparkLowLevel.MotorType;

import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.ShooterConstants;

public class Shooter extends SubsystemBase {
private final CANSparkMax motor = new CANSparkMax(ShooterConstants.MOTOR_ID, MotorType.kBrushless);
private final RelativeEncoder encoder;

public Shooter() {
motor.setSmartCurrentLimit(ShooterConstants.CURRENT_LIMIT);
motor.setIdleMode(ShooterConstants.IDLE_MODE);
motor.burnFlash();

encoder = motor.getEncoder();
encoder.setPositionConversionFactor(1);
}

@Override
public void periodic() {
SmartDashboard.putNumber(getName(), encoder.getVelocity());
}

public void run(double speed) {
Expand Down

0 comments on commit d3e4e39

Please sign in to comment.