Merge branch 'main' of https://git.demerso.net/pls5618/2024/robot
This commit is contained in:
@ -9,22 +9,35 @@ import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.Constants;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
|
||||
|
||||
public class Accumulateur extends SubsystemBase {
|
||||
/** Creates a new Accumulateur. */
|
||||
|
||||
|
||||
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
|
||||
final WPI_TalonSRX Moteuracc2 = new WPI_TalonSRX(Constants.Moteuracc2);
|
||||
final WPI_TalonSRX Moteuracc = new WPI_TalonSRX(Constants.Moteuracc);
|
||||
final DigitalInput limitacc = new DigitalInput(Constants.limitacc);
|
||||
final DigitalInput limitacc2 = new DigitalInput(Constants.limitacc2);
|
||||
public void Deaccumuler(double vitesse){Moteuracc2.set(vitesse);}
|
||||
public void moteuraccfollow(){Moteuracc.follow(Moteuracc2); Moteuracc.setInverted(true);}
|
||||
public boolean limitswitch1(){return limitacc.get();}
|
||||
public boolean limitswitch2(){return limitacc2.get();}
|
||||
public Accumulateur() {}
|
||||
public void Accumuler(double vitesse){Moteuracc.set(vitesse);}
|
||||
public void Accumuler2(double vitesse){Moteuracc2.set(vitesse);}
|
||||
final DigitalInput limitacc = new DigitalInput(Constants.limitacc);
|
||||
|
||||
public void Deaccumuler(double vitesse){
|
||||
Moteuracc2.set(vitesse);
|
||||
}
|
||||
public void moteuraccfollow(){
|
||||
Moteuracc.follow(Moteuracc2);
|
||||
Moteuracc.setInverted(true);
|
||||
}
|
||||
public boolean limitswitch(){
|
||||
return limitacc.get();
|
||||
}
|
||||
public Accumulateur() {
|
||||
dashboard.addBoolean("limitacc", this::limitswitch);
|
||||
}
|
||||
public void Accumuler(double vitesse){
|
||||
Moteuracc.set(vitesse);
|
||||
Moteuracc2.set(vitesse);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
|
@ -15,10 +15,19 @@ public class Balayeuse extends SubsystemBase {
|
||||
|
||||
public Balayeuse() {}
|
||||
final WPI_TalonSRX roue = new WPI_TalonSRX(Constants.roue);
|
||||
final TalonSRX etoile = new TalonSRX(Constants.etoile);
|
||||
final WPI_TalonSRX etoile = new WPI_TalonSRX(Constants.etoile);
|
||||
|
||||
public void Accumulation(double vitesse){roue.set(vitesse);}
|
||||
public void balayeuse(){etoile.follow(roue); etoile.setInverted(true);}
|
||||
public void Accumulation(double vitesse){
|
||||
roue.set(vitesse);
|
||||
}
|
||||
public void balayeuse(){
|
||||
etoile.follow(roue);
|
||||
etoile.setInverted(true);
|
||||
}
|
||||
public void balaye(double vitesse){
|
||||
roue.set(vitesse);
|
||||
etoile.set(vitesse);
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
|
@ -18,13 +18,13 @@ public class Lanceur extends SubsystemBase {
|
||||
public Lanceur() {}
|
||||
final CANSparkMax lancer = new CANSparkMax(Constants.lanceur, MotorType.kBrushless);
|
||||
final CANSparkMax lancer2 = new CANSparkMax(Constants.lancer2, MotorType.kBrushless);
|
||||
final CANSparkMax lancer3 = new CANSparkMax(Constants.lanceur, MotorType.kBrushless);
|
||||
final CANSparkMax lancer4 = new CANSparkMax(Constants.lancer2, MotorType.kBrushless);
|
||||
final CANSparkMax lancer3 = new CANSparkMax(Constants.lancer3, MotorType.kBrushless);
|
||||
final CANSparkMax lancer4 = new CANSparkMax(Constants.lancer4, MotorType.kBrushless);
|
||||
|
||||
public void lancer(double vitesse){
|
||||
lancer.set(vitesse);
|
||||
public void lancer(double vitesse){
|
||||
lancer.set(vitesse);
|
||||
}
|
||||
public void lanceur(){
|
||||
public void lanceur(){
|
||||
lancer2.follow(lancer);
|
||||
lancer3.follow(lancer);
|
||||
lancer4.follow(lancer);
|
||||
|
@ -4,13 +4,21 @@
|
||||
|
||||
package frc.robot.subsystem;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.LimelightHelpers;
|
||||
|
||||
|
||||
public class Limelight extends SubsystemBase {
|
||||
/** Creates a new Limelight. */
|
||||
public Limelight() {
|
||||
|
||||
}
|
||||
|
||||
boolean tv = LimelightHelpers.getTV("No_name");
|
||||
|
||||
double tx = LimelightHelpers.getTX("No_name");
|
||||
double ty = LimelightHelpers.getTY("No_name");
|
||||
double ta = LimelightHelpers.getTA("No_name");
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
|
Reference in New Issue
Block a user