summaryrefslogtreecommitdiff
path: root/src/main/java/frc/robot/subsystems/Shooter.java
blob: 273e5bdb40d74238c5d867f56c8b7f1c02a4428f (plain)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
package frc.robot.subsystems;

import org.littletonrobotics.junction.Logger;

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

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

public class Shooter extends SubsystemBase 
{   
    public static final CANSparkMax m_shooterT = new CANSparkMax(Constants.shooterT_ID, MotorType.kBrushless);
    public static final CANSparkMax m_shooterD = new CANSparkMax(Constants.shooterD_ID, MotorType.kBrushless);

    public Shooter() {}

    // perc is betwen 0.0 and 1.0
    public void atPercentage(double perc)
    {
        atPercentage(perc, perc);
    }

    public void atPercentage(double upPerc, double downPerc)
    {
        m_shooterT.set(upPerc);
        m_shooterD.set(downPerc);
    }

    @Override
    public void periodic() 
    {     
        Logger.recordOutput(getName() + "/speedT", m_shooterT.getEncoder().getVelocity());
        Logger.recordOutput(getName() + "/speedD", m_shooterD.getEncoder().getVelocity());
    }
}