Merge branch 'main' of https://git.demerso.net/pls5618/2024/robot
This commit is contained in:
@ -12,16 +12,27 @@ import frc.robot.Constants;
|
||||
|
||||
public class Accumulateur extends SubsystemBase {
|
||||
/** Creates a new Accumulateur. */
|
||||
public Accumulateur() {}
|
||||
|
||||
|
||||
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();}
|
||||
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() {}
|
||||
public void Accumuler(double vitesse){
|
||||
Moteuracc.set(vitesse);
|
||||
Moteuracc2.set(vitesse);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
|
@ -15,9 +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);
|
||||
public void Accumulation(double vitesse){roue.set(vitesse);}
|
||||
public void balayeuse(){etoile.follow(roue); etoile.setInverted(true);}
|
||||
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 balaye(double vitesse){
|
||||
roue.set(vitesse);
|
||||
etoile.set(vitesse);
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
|
@ -9,6 +9,9 @@ import com.revrobotics.CANSparkMax;
|
||||
import com.revrobotics.CANSparkLowLevel.MotorType;
|
||||
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.DoubleSolenoid;
|
||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||
import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.Constants;
|
||||
|
||||
@ -21,6 +24,8 @@ public class Grimpeur extends SubsystemBase {
|
||||
// limit switch
|
||||
final DigitalInput limitdroite = new DigitalInput(Constants.limithaut);
|
||||
final DigitalInput limitgauche = new DigitalInput(Constants.limitbas);
|
||||
final DoubleSolenoid pistondroite= new DoubleSolenoid(PneumaticsModuleType.CTREPCM, Constants.pistondroiteouvre, Constants.pistondroiteouvre);
|
||||
final DoubleSolenoid pistondgauche= new DoubleSolenoid(PneumaticsModuleType.CTREPCM, Constants.pistondgaucheouvre, Constants.pistondroiteouvre);
|
||||
//fonction
|
||||
public void droit(double vitesse){
|
||||
grimpeurd.set(vitesse);
|
||||
@ -40,10 +45,19 @@ public void resetencodeurd(){
|
||||
public void resetencodeurg(){
|
||||
grimpeurg.getEncoder().setPosition(0);
|
||||
}
|
||||
|
||||
public AHRS gyroscope = new AHRS();
|
||||
public double getpitch(){
|
||||
return gyroscope.getPitch();
|
||||
}
|
||||
public void pistonouvre(){
|
||||
pistondroite.set(Value.kForward);
|
||||
pistondgauche.set(Value.kForward);
|
||||
}
|
||||
public void pistonferme(){
|
||||
pistondroite.set(Value.kReverse);
|
||||
pistondgauche.set(Value.kReverse);
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
|
Reference in New Issue
Block a user