led
This commit is contained in:
@@ -1,8 +1,12 @@
|
||||
/* Generated by Phoenix Tuner X */
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
|
||||
import edu.wpi.first.networktables.GenericEntry;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
@@ -15,6 +19,9 @@ import com.ctre.phoenix6.signals.RGBWColor;
|
||||
* Subsystem that controls an addressable LED strip using a CANdle.
|
||||
*/
|
||||
public class LEDSubsystem extends SubsystemBase {
|
||||
ShuffleboardTab teb = Shuffleboard.getTab("teb");
|
||||
private GenericEntry equipe =
|
||||
teb.add("equipe commence (bleu = ouvert, rouge = fermé)", true).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
||||
private final CANBus kCANBus = new CANBus("rio");
|
||||
private final CANdle m_candle = new CANdle(17, kCANBus);
|
||||
public void Bleu(){
|
||||
@@ -23,17 +30,108 @@ public class LEDSubsystem extends SubsystemBase {
|
||||
public void Rouge(){
|
||||
new SolidColor(0, 80).withColor(new RGBWColor(0, 0, 255, 0));
|
||||
}
|
||||
public void Vert(){
|
||||
new SolidColor(0, 80).withColor(new RGBWColor(0, 255, 0, 0));
|
||||
}
|
||||
public void Noir(){
|
||||
|
||||
new SolidColor(0, 80).withColor(new RGBWColor(0, 0, 0, 0));
|
||||
}
|
||||
public void Flach(boolean couleur){
|
||||
Timer timer = new Timer();
|
||||
timer.start();
|
||||
if(timer.get() <0.5){
|
||||
if(couleur){
|
||||
Bleu();
|
||||
}
|
||||
else{
|
||||
Rouge();
|
||||
}
|
||||
}
|
||||
else{
|
||||
Noir();
|
||||
timer.reset();
|
||||
}
|
||||
}
|
||||
public LEDSubsystem() {
|
||||
setDefaultCommand(updateLEDs());
|
||||
}
|
||||
|
||||
public boolean Equipe(){
|
||||
return equipe.getBoolean(false);
|
||||
}
|
||||
/**
|
||||
* Updates the animations and LEDs of the CANdle.
|
||||
*
|
||||
* @return Command to run
|
||||
*/
|
||||
public Command updateLEDs() {
|
||||
return run(() -> {});
|
||||
double temps = DriverStation.getMatchTime();
|
||||
return run(() -> {
|
||||
if(Equipe()){
|
||||
if(temps < 30){
|
||||
Vert();
|
||||
}
|
||||
else if(temps < 52){
|
||||
Bleu();
|
||||
}
|
||||
else if(temps < 55){
|
||||
Flach(true);
|
||||
}
|
||||
else if(temps < 77){
|
||||
Rouge();
|
||||
}
|
||||
else if(temps < 80){
|
||||
Flach(false);
|
||||
}
|
||||
else if(temps < 102){
|
||||
Bleu();
|
||||
}
|
||||
else if(temps < 105){
|
||||
Flach(true);
|
||||
}
|
||||
else if(temps <127){
|
||||
Rouge();
|
||||
}
|
||||
else if(temps < 130){
|
||||
Flach(false);
|
||||
}
|
||||
else if(temps < 140){
|
||||
Vert();
|
||||
}
|
||||
}
|
||||
else{
|
||||
if(temps < 30){
|
||||
Vert();
|
||||
}
|
||||
else if(temps < 52){
|
||||
Rouge();
|
||||
}
|
||||
else if(temps < 55){
|
||||
Flach(false);
|
||||
}
|
||||
else if(temps < 77){
|
||||
Bleu();
|
||||
}
|
||||
else if(temps < 80){
|
||||
Flach(true);
|
||||
}
|
||||
else if(temps < 102){
|
||||
Rouge();
|
||||
}
|
||||
else if(temps < 105){
|
||||
Flach(false);
|
||||
}
|
||||
else if(temps <127){
|
||||
Bleu();
|
||||
}
|
||||
else if(temps < 130){
|
||||
Flach(true);
|
||||
}
|
||||
else if(temps < 140){
|
||||
Vert();
|
||||
}
|
||||
}
|
||||
});
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user