Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

blinkin subsystem #52

Merged
merged 1 commit into from
Apr 6, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,11 @@
* constants are needed, to reduce verbosity.
*/
public final class Constants {
public class BlinkinConstants {

Check warning on line 25 in src/main/java/frc/robot/Constants.java

View workflow job for this annotation

GitHub Actions / Qodana Community for JVM

Inner class may be 'static'

Inner class `BlinkinConstants` may be 'static'

public static final int kBlinkinPort = 0;

}

public static final class DriveConstants {

Expand Down
67 changes: 67 additions & 0 deletions src/main/java/frc/robot/subsystems/BlinkinSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.subsystems;

import java.util.function.BooleanSupplier;

import edu.wpi.first.wpilibj.motorcontrol.Spark;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants.BlinkinConstants;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;


public class BlinkinSubsystem extends SubsystemBase {

private final ShuffleboardTab m_tab = Shuffleboard.getTab("Blinkin");

private final Spark blinkin;

public BlinkinSubsystem() {
blinkin = new Spark(BlinkinConstants.kBlinkinPort);
m_tab.add(blinkin.toString(), blinkin);
}

public BooleanSupplier supplier = () -> {return false;};

@Override
public void periodic() {
if (supplier.getAsBoolean())
setGreen();
// This method will be called once per scheduler run
}

public void set(double pattern) {
blinkin.set(pattern);
}

public void setOcean(){
blinkin.set(-0.95);
}

public void setRainbow(){
blinkin.set(-0.99);
}

public void setBlue(){
blinkin.set(0.87);
}

public void setGreen(){
blinkin.set(0.77);
}

public void setRed(){
blinkin.set(0.61);
}

public void setWhite(){
blinkin.set(0.93);
}
@Override
public void simulationPeriodic() {
// This method will be called once per scheduler run during simulation
}
}