This repository has been archived by the owner on Jan 6, 2024. It is now read-only.
-
-
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
1 parent
5f01aec
commit c177bf8
Showing
2 changed files
with
56 additions
and
0 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
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,55 @@ | ||
package frc.robot.shoulder; | ||
import com.revrobotics.CANSparkMax; | ||
import com.revrobotics.CANSparkMax.ControlType; | ||
import com.revrobotics.RelativeEncoder; | ||
import com.revrobotics.SparkMaxPIDController; | ||
import edu.wpi.first.wpilibj2.command.Command; | ||
import frc.robot.util.scheduling.LifecycleSubsystem; | ||
import frc.robot.util.scheduling.SubsystemPriority; | ||
|
||
public class ShoulderSubsystem extends LifecycleSubsystem { | ||
private final CANSparkMax motor; | ||
private RelativeEncoder encoder; | ||
private SparkMaxPIDController pid; | ||
private double goalAngle = 0.0; | ||
|
||
public ShoulderSubsystem(CANSparkMax motor) { | ||
super(SubsystemPriority.SHOULDER); | ||
|
||
this.motor = motor; | ||
encoder = motor.getEncoder(); | ||
pid = motor.getPIDController(); | ||
|
||
pid.setP(5); | ||
pid.setI(0); | ||
pid.setD(0); | ||
|
||
encoder.setPosition(0); | ||
encoder.setPositionConversionFactor(50); | ||
} | ||
|
||
@Override | ||
public void enabledPeriodic() { | ||
pid.setReference(goalAngle / 360.0, ControlType.kSmartMotion); | ||
} | ||
|
||
public void set(double angle) { | ||
goalAngle = angle; | ||
} | ||
|
||
public Command setPositionCommand(double angle) { | ||
return run(() -> { | ||
set(angle); | ||
}) | ||
.until(() -> atAngle(angle)); | ||
} | ||
|
||
private boolean atAngle(double angle) { | ||
return Math.abs(getWristAngle() - angle) < 1; | ||
} | ||
|
||
private double getWristAngle() { | ||
return encoder.getPosition() * 360.0; | ||
} | ||
} | ||
|
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