-
Notifications
You must be signed in to change notification settings - Fork 0
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
Showing
2 changed files
with
29 additions
and
9 deletions.
There are no files selected for viewing
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
31 changes: 22 additions & 9 deletions
31
src/main/java/frc/robot/subsystems/end effector/endEffector.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 |
---|---|---|
@@ -1,17 +1,30 @@ | ||
public class endEffector extends SubsystemBase{ | ||
private final CANSparkMax endEffectorMotor; | ||
private final int MOTOR_SPEED; | ||
import edu.wpi.first.wpilibj2.command.SubsystemBase; | ||
import frc.robot.Constants.EndEffectorConstants; | ||
|
||
public endEffector(int endEffectorMotorID) { | ||
endEffectorMotor = new CANSparkMaxSparkMax(endEffectorMotorID); | ||
MOTOR_SPEED = 2 | ||
import com.revrobotics.spark.SparkMax; | ||
import com.revrobotics.spark.SparkBase.PersistMode; | ||
import com.revrobotics.spark.SparkBase.ResetMode; | ||
import com.revrobotics.spark.SparkLowLevel.MotorType; | ||
import com.revrobotics.spark.config.SparkMaxConfig; | ||
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; | ||
|
||
public class EndEffector extends SubsystemBase { | ||
private final SparkMax endEffectorMotor; | ||
|
||
public EndEffector(int endEffectorMotorID) { | ||
endEffectorMotor = new SparkMax(endEffectorMotorID, MotorType.kBrushless); | ||
SparkMaxConfig config = new SparkMaxConfig(); | ||
config.smartCurrentLimit(40); | ||
config.idleMode(IdleMode.kBrake); | ||
config.inverted(false); | ||
endEffectorMotor.configure(config, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters); | ||
} | ||
|
||
public void stopMotor() { | ||
endEffectorMotor.stopMotor(); | ||
} | ||
} | ||
|
||
public void runMotor () { | ||
endEffectorMotor.set(MOTOR_SPEED); | ||
public void runMotor() { | ||
endEffectorMotor.set(EndEffectorConstants.MOTOR_SPEED); | ||
} | ||
} |