Balayer et debalayer + menage
This commit is contained in:
parent
ad1fd9d2d2
commit
82caa36322
@ -13,11 +13,9 @@ public class Balayer extends Command {
|
||||
private Accumulateur accumulateur;
|
||||
/** Creates a new Balayer. */
|
||||
public Balayer(Balayeuse balayeuse, Accumulateur accumulateur) {
|
||||
this.balayeuse = balayeuse;
|
||||
addRequirements(balayeuse, accumulateur);
|
||||
this.balayeuse = balayeuse;
|
||||
addRequirements(balayeuse, accumulateur);}
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {}
|
||||
@ -25,16 +23,26 @@ public class Balayer extends Command {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
|
||||
if(accumulateur.limitswitch()){
|
||||
balayeuse.balaye(0);
|
||||
accumulateur.Accumuler(0);
|
||||
}
|
||||
else{
|
||||
balayeuse.balaye(0.6);
|
||||
accumulateur.Accumuler(0.6);
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {}
|
||||
public void end(boolean interrupted) {
|
||||
balayeuse.balaye(0);
|
||||
accumulateur.Accumuler(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
return accumulateur.limitswitch()==true;
|
||||
}
|
||||
}
|
||||
|
42
src/main/java/frc/robot/command/Debalayer.java
Normal file
42
src/main/java/frc/robot/command/Debalayer.java
Normal file
@ -0,0 +1,42 @@
|
||||
// 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.command;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.subsystem.Accumulateur;
|
||||
import frc.robot.subsystem.Balayeuse;
|
||||
|
||||
public class Debalayer extends Command {
|
||||
private Balayeuse balayeuse;
|
||||
private Accumulateur accumulateur;
|
||||
/** Creates a new Balayer. */
|
||||
public Debalayer(Balayeuse balayeuse, Accumulateur accumulateur) {
|
||||
this.balayeuse = balayeuse;
|
||||
addRequirements(balayeuse, accumulateur);}
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
balayeuse.balaye(-0.6);
|
||||
accumulateur.Accumuler(-0.6);
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
balayeuse.balaye(0);
|
||||
accumulateur.Accumuler(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
@ -16,15 +16,22 @@ public class Accumulateur extends SubsystemBase {
|
||||
|
||||
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);}
|
||||
public void Accumuler2(double vitesse){Moteuracc2.set(vitesse);}
|
||||
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
|
||||
|
Loading…
x
Reference in New Issue
Block a user