Merge branch 'requin' of https://git.demerso.net/PLS5618/Reefscape-2025
This commit is contained in:
@ -43,8 +43,12 @@ public class Bougie extends SubsystemBase {
|
||||
candle.setLEDs(255, 215, 0,0,48,8);
|
||||
candle.setLEDs(255, 215, 0,0,64,8);
|
||||
}
|
||||
public void RainBow(){candle.animate(rainbowAnim);}
|
||||
public void RainBowStop(){candle.animate(null);}
|
||||
public void RainBow(){
|
||||
candle.animate(rainbowAnim);
|
||||
}
|
||||
public void RainBowStop(){
|
||||
candle.animate(null);
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
|
48
src/main/java/frc/robot/subsystems/Requin.java
Normal file
48
src/main/java/frc/robot/subsystems/Requin.java
Normal file
@ -0,0 +1,48 @@
|
||||
// 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 com.revrobotics.spark.SparkFlex;
|
||||
import com.revrobotics.spark.SparkMax;
|
||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Requin extends SubsystemBase {
|
||||
/** Creates a new Requin. */
|
||||
ShuffleboardTab teb = Shuffleboard.getTab("teb");
|
||||
public Requin() {
|
||||
teb.addBoolean("limit requin", this::enHaut);
|
||||
}
|
||||
|
||||
final SparkFlex balaye = new SparkFlex(15, MotorType.kBrushless);
|
||||
final SparkMax rotatione = new SparkMax(17, MotorType.kBrushless);
|
||||
final DigitalInput limit3 = new DigitalInput(1);
|
||||
|
||||
public void balaye(double vitesse){
|
||||
balaye.set(vitesse);
|
||||
}
|
||||
public void rotationer(double vitesse){
|
||||
rotatione.set(vitesse);
|
||||
}
|
||||
public boolean enHaut(){
|
||||
return limit3.get();
|
||||
}
|
||||
public double encodeur(){
|
||||
return rotatione.getEncoder().getPosition();
|
||||
}
|
||||
public void reset(){
|
||||
rotatione.getEncoder().setPosition(0);
|
||||
}
|
||||
public double amp(){
|
||||
return balaye.getOutputCurrent();
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
}
|
||||
}
|
Reference in New Issue
Block a user