blob: 41620bb45ef9f02c2c7704a00b59e9ba933ae547 (
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
37
38
39
40
41
42
43
44
45
46
47
48
|
package frc.robot.subsystems;
import org.littletonrobotics.junction.Logger;
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
public class Intake extends SubsystemBase
{
public static final CANSparkMax m_intakeT = new CANSparkMax(Constants.intakeT_ID, MotorType.kBrushless);
public static final CANSparkMax m_intakeD = new CANSparkMax(Constants.intakeD_ID, MotorType.kBrushless);
private final RelativeEncoder m_intakeD_encoder = m_intakeD.getEncoder();
public Intake()
{
m_intakeT.setInverted(true);
m_intakeD.setInverted(true);
}
public void atPercentage(double perc)
{
atPercentage(perc, perc);
}
public void atPercentage(double upPerc, double downPerc)
{
m_intakeT.set(upPerc);
m_intakeD.set(downPerc);
}
public void shoot()
{
if (m_intakeD_encoder.getVelocity() > 2000) {
m_intakeT.set(1);
}
m_intakeD.set(1);
}
@Override
public void periodic()
{
Logger.recordOutput(getName() + "/speedT", m_intakeT.getEncoder().getVelocity());
Logger.recordOutput(getName() + "/speedD", m_intakeD.getEncoder().getVelocity());
}
}
|