-
Notifications
You must be signed in to change notification settings - Fork 1
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
1 parent
bb4cc32
commit e91716d
Showing
1 changed file
with
37 additions
and
0 deletions.
There are no files selected for viewing
37 changes: 37 additions & 0 deletions
37
src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,37 @@ | ||
package frc.robot.subsystems.intake; | ||
|
||
import com.revrobotics.CANSparkLowLevel.MotorType; | ||
import com.revrobotics.CANSparkMax; | ||
import com.revrobotics.RelativeEncoder; | ||
import edu.wpi.first.math.util.Units; | ||
|
||
public class IntakeIOSparkMax implements IntakeIO { | ||
private static final double GEAR_RATIO = 10.0; | ||
|
||
// define the 2 SparkMax Controllers. A leader, and a follower | ||
private final CANSparkMax leader = new CANSparkMax(0, MotorType.kBrushless); | ||
|
||
// Gets the NEO encoder | ||
private final RelativeEncoder encoder = leader.getEncoder(); | ||
|
||
public IntakeIOSparkMax() { | ||
// leader motor is not inverted, and set follower motor to follow the leader | ||
leader.setInverted(false); | ||
} | ||
|
||
@Override | ||
public void updateInputs(IntakeIOInputs inputs) { | ||
// Set velocityRadPerSec to the encoder velocity(rotationsPerMinute) divided by the gear ratio | ||
// and converted into Radians Per Second | ||
inputs.velocityRadPerSec = | ||
Units.rotationsPerMinuteToRadiansPerSecond(encoder.getVelocity() / GEAR_RATIO); | ||
// Get applied voltage from the leader motor | ||
inputs.appliedVolts = leader.getAppliedOutput() * leader.getBusVoltage(); | ||
} | ||
|
||
@Override | ||
public void setVoltage(double volts) { | ||
// Set the voltage output for the leader motor | ||
leader.setVoltage(volts); | ||
} | ||
} |