Merge branch 'brasTelescopiquev2' into 'main'
bras See merge request pls5618/2023/robot!1
This commit is contained in:
commit
d4a0188c04
@ -3,6 +3,7 @@
|
|||||||
// the WPILib BSD license file in the root directory of this project.
|
// the WPILib BSD license file in the root directory of this project.
|
||||||
|
|
||||||
package frc.robot;
|
package frc.robot;
|
||||||
|
|
||||||
import java.util.Map;
|
import java.util.Map;
|
||||||
|
|
||||||
import edu.wpi.first.cameraserver.CameraServer;
|
import edu.wpi.first.cameraserver.CameraServer;
|
||||||
@ -39,75 +40,63 @@ import frc.robot.commands.Gyro;
|
|||||||
import frc.robot.commands.Reculer;
|
import frc.robot.commands.Reculer;
|
||||||
import frc.robot.commands.Tape;
|
import frc.robot.commands.Tape;
|
||||||
import frc.robot.commands.bras.BrasManuel;
|
import frc.robot.commands.bras.BrasManuel;
|
||||||
|
import frc.robot.commands.bras.DescendrePivotBras;
|
||||||
import frc.robot.commands.bras.FermePince;
|
import frc.robot.commands.bras.FermePince;
|
||||||
|
import frc.robot.commands.bras.MonterPivotBras;
|
||||||
import frc.robot.commands.bras.OuvrePince;
|
import frc.robot.commands.bras.OuvrePince;
|
||||||
import frc.robot.commands.bras.PivotBrasRentre;
|
|
||||||
import frc.robot.commands.bras.PivotChercheBas;
|
|
||||||
import frc.robot.commands.bras.PivotChercheHaut;
|
|
||||||
import frc.robot.commands.bras.PivotManuel;
|
import frc.robot.commands.bras.PivotManuel;
|
||||||
import frc.robot.commands.bras.PivoteBrasBas;
|
|
||||||
import frc.robot.commands.bras.PivoteBrasHaut;
|
|
||||||
import frc.robot.commands.bras.PivoteBrasMilieux;
|
|
||||||
|
|
||||||
|
|
||||||
public class RobotContainer {
|
public class RobotContainer {
|
||||||
|
|
||||||
CommandXboxController manette1 = new CommandXboxController(0);
|
CommandXboxController manette1 = new CommandXboxController(0);
|
||||||
CommandXboxController manette2 = new CommandXboxController(1);
|
CommandXboxController manette2 = new CommandXboxController(1);
|
||||||
|
|
||||||
// dashboard
|
// dashboard
|
||||||
SendableChooser<String> chooser = new SendableChooser<>();
|
SendableChooser<String> chooser = new SendableChooser<>();
|
||||||
String enhaut = "en haut";
|
String enhaut = "en haut";
|
||||||
String aumilieux = "au milieux";
|
String aumilieux = "au milieux";
|
||||||
String enbas = "en bas";
|
String enbas = "en bas";
|
||||||
String nulpart = "nul part";
|
String nulpart = "nul part";
|
||||||
ShuffleboardLayout layoutauto = Shuffleboard.getTab("teb").getLayout("auto",BuiltInLayouts.kList)
|
ShuffleboardLayout layoutauto = Shuffleboard.getTab("teb").getLayout("auto", BuiltInLayouts.kList)
|
||||||
.withSize(2, 2).withProperties(Map.of("Label position","LEFT"));
|
.withSize(2, 2).withProperties(Map.of("Label position", "LEFT"));
|
||||||
GenericEntry autobalance = layoutauto.add("choix balance",true).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
GenericEntry autobalance = layoutauto.add("choix balance", true).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
||||||
GenericEntry autosortir = layoutauto.add("choix sortir",false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
GenericEntry autosortir = layoutauto.add("choix sortir", false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
||||||
GenericEntry reculerdistances = layoutauto.addPersistent("reculerdistancesortir",0).getEntry();
|
GenericEntry reculerdistances = layoutauto.addPersistent("reculerdistancesortir", 0).getEntry();
|
||||||
GenericEntry reculerdistanceb = layoutauto.addPersistent("reculerdistancebalance", 0).getEntry();
|
GenericEntry reculerdistanceb = layoutauto.addPersistent("reculerdistancebalance", 0).getEntry();
|
||||||
GenericEntry avancerdistance = layoutauto.addPersistent("avancer",0).getEntry();
|
GenericEntry avancerdistance = layoutauto.addPersistent("avancer", 0).getEntry();
|
||||||
|
|
||||||
// subsystems
|
// subsystems
|
||||||
BasePilotable basePilotable = new BasePilotable();
|
BasePilotable basePilotable = new BasePilotable();
|
||||||
Gratte gratte = new Gratte();
|
Gratte gratte = new Gratte();
|
||||||
BrasTelescopique brasTelescopique = new BrasTelescopique();
|
BrasTelescopique brasTelescopique = new BrasTelescopique();
|
||||||
Pince pince = new Pince();
|
Pince pince = new Pince();
|
||||||
Pivot pivot = new Pivot();
|
Pivot pivot = new Pivot();
|
||||||
Limelight limelight = new Limelight();
|
Limelight limelight = new Limelight();
|
||||||
|
|
||||||
//commands
|
// commands
|
||||||
BrakeFerme brakeFerme = new BrakeFerme(basePilotable);
|
BrakeFerme brakeFerme = new BrakeFerme(basePilotable);
|
||||||
BrakeOuvre brakeOuvre = new BrakeOuvre(basePilotable);
|
BrakeOuvre brakeOuvre = new BrakeOuvre(basePilotable);
|
||||||
GratteBaisser gratteBaisser = new GratteBaisser(gratte);
|
GratteBaisser gratteBaisser = new GratteBaisser(gratte);
|
||||||
GratteMonte gratteMonte = new GratteMonte(gratte);
|
GratteMonte gratteMonte = new GratteMonte(gratte);
|
||||||
Gyro gyro = new Gyro(basePilotable);
|
Gyro gyro = new Gyro(basePilotable);
|
||||||
FermePince fermePince = new FermePince(pince);
|
FermePince fermePince = new FermePince(pince);
|
||||||
OuvrePince ouvrePince = new OuvrePince(pince);
|
OuvrePince ouvrePince = new OuvrePince(pince);
|
||||||
PivotBrasRentre pivotBrasRentre = new PivotBrasRentre(brasTelescopique, pivot);
|
Cone cone = new Cone(limelight, basePilotable, () -> -manette1.getLeftY());
|
||||||
PivoteBrasBas pivoteBrasBas = new PivoteBrasBas(brasTelescopique, pivot);
|
Reculer reculers = new Reculer(basePilotable, () -> reculerdistances.getDouble(0));
|
||||||
PivoteBrasMilieux pivoteBrasMilieux = new PivoteBrasMilieux(brasTelescopique, pivot);
|
Reculer reculerb = new Reculer(basePilotable, () -> reculerdistanceb.getDouble(0));
|
||||||
PivoteBrasHaut pivoteBrasHaut = new PivoteBrasHaut(brasTelescopique, pivot);
|
Avancer avancer = new Avancer(basePilotable, () -> avancerdistance.getDouble(0));
|
||||||
Cone cone = new Cone(limelight, basePilotable, ()->-manette1.getLeftY());
|
Cube cube = new Cube(limelight, basePilotable, () -> manette1.getLeftY());
|
||||||
Reculer reculers = new Reculer(basePilotable, ()->reculerdistances.getDouble(0));
|
Apriltag aprilTag = new Apriltag(limelight, basePilotable, () -> manette1.getLeftY());
|
||||||
Reculer reculerb = new Reculer(basePilotable, ()->reculerdistanceb.getDouble(0));
|
Tape tape = new Tape(limelight, basePilotable, () -> manette1.getLeftY());
|
||||||
Avancer avancer = new Avancer(basePilotable, ()->avancerdistance.getDouble(0));
|
PivotManuel pivotManuel = new PivotManuel(pivot, manette2::getLeftX);
|
||||||
PivotChercheBas pivotChercheBas = new PivotChercheBas(brasTelescopique, pivot);
|
BrasManuel brasManuel = new BrasManuel(brasTelescopique, manette2::getLeftY);
|
||||||
PivotChercheHaut pivotChercheHaut = new PivotChercheHaut(brasTelescopique, pivot);
|
|
||||||
Cube cube = new Cube(limelight, basePilotable, null);
|
|
||||||
Apriltag aprilTag = new Apriltag(limelight, basePilotable, null);
|
|
||||||
Tape tape = new Tape(limelight, basePilotable, null);
|
|
||||||
PivotManuel pivotManuel = new PivotManuel(pivot,manette2::getLeftX);
|
|
||||||
BrasManuel brasManuel = new BrasManuel(brasTelescopique,manette2::getLeftY);
|
|
||||||
|
|
||||||
|
public RobotContainer() {
|
||||||
public RobotContainer() {
|
|
||||||
chooser.addOption(enhaut, enhaut);
|
chooser.addOption(enhaut, enhaut);
|
||||||
chooser.addOption(enbas, enbas);
|
chooser.addOption(enbas, enbas);
|
||||||
chooser.addOption(aumilieux, aumilieux);
|
chooser.addOption(aumilieux, aumilieux);
|
||||||
chooser.addOption(nulpart, nulpart);
|
chooser.addOption(nulpart, nulpart);
|
||||||
layoutauto.add("choix hauteur",chooser);
|
layoutauto.add("choix hauteur", chooser);
|
||||||
configureBindings();
|
configureBindings();
|
||||||
CameraServer.startAutomaticCapture();
|
CameraServer.startAutomaticCapture();
|
||||||
basePilotable.setDefaultCommand(new RunCommand(() -> {
|
basePilotable.setDefaultCommand(new RunCommand(() -> {
|
||||||
@ -116,48 +105,58 @@ public RobotContainer() {
|
|||||||
brasTelescopique.setDefaultCommand(brasManuel);
|
brasTelescopique.setDefaultCommand(brasManuel);
|
||||||
pivot.setDefaultCommand(pivotManuel);
|
pivot.setDefaultCommand(pivotManuel);
|
||||||
}
|
}
|
||||||
|
|
||||||
private void configureBindings() {
|
private void configureBindings() {
|
||||||
// manette 1
|
// manette 1
|
||||||
manette1.a().toggleOnTrue(Commands.startEnd(pince::ouvrir, pince::fermer,pince));
|
manette1.a().toggleOnTrue(Commands.startEnd(pince::ouvrir, pince::fermer, pince));
|
||||||
manette1.x().toggleOnTrue(Commands.startEnd(basePilotable::BrakeFerme,basePilotable::BrakeOuvre,basePilotable));
|
manette1.x().onTrue(brakeOuvre);
|
||||||
manette1.leftBumper().toggleOnTrue(aprilTag);
|
manette1.b().onTrue(brakeFerme);
|
||||||
manette1.rightBumper().toggleOnTrue(tape);
|
manette1.leftBumper().whileTrue(aprilTag);
|
||||||
manette1.povUp().whileTrue(pivoteBrasHaut);
|
manette1.rightBumper().whileTrue(tape);
|
||||||
manette1.povDown().whileTrue(pivoteBrasBas);
|
manette1.povUp().whileTrue(creerCommandBras(51, -40));
|
||||||
manette1.povRight().whileTrue(pivoteBrasMilieux);
|
manette1.povDown().whileTrue(creerCommandBras(9, -14));
|
||||||
manette1.povLeft().whileTrue(pivotBrasRentre);
|
manette1.povRight().whileTrue(creerCommandBras(44, -17));
|
||||||
//manette 2
|
manette1.povLeft().whileTrue(creerCommandBras(0, 0));
|
||||||
manette2.povDown().onTrue(pivotChercheBas);
|
// manette 2
|
||||||
manette2.povUp().onTrue(pivotChercheHaut);
|
manette2.povDown().onTrue(creerCommandBras(9, -18));
|
||||||
manette2.rightBumper().toggleOnTrue(cube);
|
manette2.povUp().onTrue(creerCommandBras(44, 0));
|
||||||
manette2.leftBumper().toggleOnTrue(cone);
|
manette2.rightBumper().whileTrue(cube);
|
||||||
|
manette2.leftBumper().whileTrue(cone);
|
||||||
manette2.y().whileTrue(gyro);
|
manette2.y().whileTrue(gyro);
|
||||||
manette2.start().onTrue(new InstantCommand(basePilotable::resetGyro));
|
manette2.start().onTrue(new InstantCommand(basePilotable::resetGyro));
|
||||||
manette2.a().whileTrue(gratteMonte);
|
manette2.a().whileTrue(gratteMonte);
|
||||||
manette2.b().whileTrue(gratteBaisser);
|
manette2.b().whileTrue(gratteBaisser);
|
||||||
|
|
||||||
}
|
}
|
||||||
//mode auto
|
|
||||||
|
private Command creerCommandBras(double distancePivot, double distanceBras) {
|
||||||
|
return Commands.either(
|
||||||
|
new MonterPivotBras(brasTelescopique, pivot, distanceBras, distancePivot),
|
||||||
|
new DescendrePivotBras(brasTelescopique, pivot, distanceBras, distancePivot),
|
||||||
|
() -> pivot.distance() < distancePivot);
|
||||||
|
}
|
||||||
|
|
||||||
public Command getAutonomousCommand() {
|
public Command getAutonomousCommand() {
|
||||||
chooser.getSelected();
|
chooser.getSelected();
|
||||||
autobalance.getBoolean(true);
|
autobalance.getBoolean(true);
|
||||||
return new SequentialCommandGroup(
|
return Commands.deadline(
|
||||||
|
Commands.waitSeconds(14.6),
|
||||||
|
new SequentialCommandGroup(
|
||||||
Commands.select(Map.ofEntries(
|
Commands.select(Map.ofEntries(
|
||||||
Map.entry(enhaut,pivoteBrasHaut),
|
Map.entry(enhaut, creerCommandBras(51, -40)),
|
||||||
Map.entry(aumilieux,pivoteBrasMilieux),
|
Map.entry(aumilieux, creerCommandBras(9, -14)),
|
||||||
Map.entry(enbas,pivoteBrasBas),
|
Map.entry(enbas, creerCommandBras(44, -17)),
|
||||||
Map.entry(nulpart,pivotBrasRentre)
|
Map.entry(nulpart, creerCommandBras(0, 0))), chooser::getSelected),
|
||||||
), chooser::getSelected),
|
new OuvrePince(pince).unless(() -> chooser.getSelected().equals(nulpart)),
|
||||||
new OuvrePince(pince).unless(()->chooser.getSelected().equals(nulpart)),
|
|
||||||
Commands.waitSeconds(1),
|
Commands.waitSeconds(1),
|
||||||
new FermePince(pince).unless(()->chooser.getSelected().equals(nulpart)),
|
fermePince.unless(() -> chooser.getSelected().equals(nulpart)),
|
||||||
new PivotBrasRentre(brasTelescopique , pivot).unless(()->chooser.getSelected().equals(nulpart)),
|
creerCommandBras(0, 0).unless(() -> chooser.getSelected().equals(nulpart)),
|
||||||
Commands.waitSeconds(1),
|
Commands.waitSeconds(1),
|
||||||
Commands.either(reculers, reculerb,()-> autosortir.getBoolean(true)),
|
Commands.either(reculers, reculerb, () -> autosortir.getBoolean(true)),
|
||||||
new Avancer(basePilotable,()-> avancerdistance.getDouble(0)).unless(()->!autosortir.getBoolean(true)|| autobalance.getBoolean(false)),
|
new Avancer(basePilotable, () -> avancerdistance.getDouble(0))
|
||||||
Commands.either(gyro, Commands.none(),()-> autobalance.getBoolean(true))
|
.unless(() -> !autosortir.getBoolean(true) || !autobalance.getBoolean(false)),
|
||||||
).deadlineWith(Commands.waitSeconds(14.6)).andThen(brakeOuvre);
|
Commands.either(gyro, Commands.none(), () -> autobalance.getBoolean(true))))
|
||||||
|
.andThen(brakeOuvre);
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -6,45 +6,36 @@ package frc.robot.commands.bras;
|
|||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||||
import frc.robot.subsystems.bras.BrasTelescopique;
|
import frc.robot.subsystems.bras.BrasTelescopique;
|
||||||
import frc.robot.subsystems.bras.Pivot;
|
|
||||||
|
|
||||||
public class PivotChercheHaut extends CommandBase {
|
public class Bougerbras extends CommandBase {
|
||||||
private BrasTelescopique brasTelescopique;
|
/** Creates a new bougerbras. */
|
||||||
private Pivot pivot;
|
double distance;
|
||||||
/** Creates a new PivotChercheHaut. */
|
BrasTelescopique brasTelescopique;
|
||||||
public PivotChercheHaut(BrasTelescopique brasTelescopique, Pivot pivot) {
|
public Bougerbras(BrasTelescopique brasTelescopique,double distance) {
|
||||||
this.brasTelescopique = brasTelescopique;
|
this.brasTelescopique = brasTelescopique;
|
||||||
this.pivot = pivot;
|
this.distance = distance;
|
||||||
// Use addRequirements() here to declare subsystem dependencies.
|
|
||||||
addRequirements(brasTelescopique);
|
addRequirements(brasTelescopique);
|
||||||
addRequirements(pivot);
|
// Use addRequirements() here to declare subsystem dependencies.
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called when the command is initially scheduled.
|
// Called when the command is initially scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void initialize() {
|
public void initialize() {
|
||||||
brasTelescopique.fermer();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void execute() {
|
public void execute() {
|
||||||
if(brasTelescopique.photocell()){
|
if(brasTelescopique.distance()>distance+0.5 ) {
|
||||||
brasTelescopique.ouvrir();
|
brasTelescopique.AvanceRecule(-0.3);
|
||||||
brasTelescopique.Reset();
|
|
||||||
brasTelescopique.AvanceRecule(0);
|
|
||||||
}
|
}
|
||||||
else{
|
else if(brasTelescopique.distance()<distance-0.5) {
|
||||||
brasTelescopique.AvanceRecule(0.3);
|
brasTelescopique.AvanceRecule(0.3);
|
||||||
}
|
}
|
||||||
if (pivot.distance()<43.5){
|
else {
|
||||||
pivot.monteDescendre(0.5);
|
brasTelescopique.AvanceRecule(0);
|
||||||
}
|
|
||||||
else if(pivot.distance()>44.5) {
|
|
||||||
pivot.monteDescendre(-0.5);
|
|
||||||
}
|
|
||||||
else{
|
|
||||||
pivot.monteDescendre(0);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -52,13 +43,13 @@ public class PivotChercheHaut extends CommandBase {
|
|||||||
@Override
|
@Override
|
||||||
public void end(boolean interrupted) {
|
public void end(boolean interrupted) {
|
||||||
brasTelescopique.AvanceRecule(0);
|
brasTelescopique.AvanceRecule(0);
|
||||||
pivot.monteDescendre(0);
|
|
||||||
brasTelescopique.ouvrir();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
||||||
@Override
|
@Override
|
||||||
public boolean isFinished() {
|
public boolean isFinished() {
|
||||||
return false;
|
return brasTelescopique.distance()>distance-0.5 && brasTelescopique.distance()<distance+0.5;
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
@ -5,58 +5,47 @@
|
|||||||
package frc.robot.commands.bras;
|
package frc.robot.commands.bras;
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||||
import frc.robot.subsystems.bras.BrasTelescopique;
|
|
||||||
import frc.robot.subsystems.bras.Pivot;
|
import frc.robot.subsystems.bras.Pivot;
|
||||||
|
|
||||||
public class PivotBrasRentre extends CommandBase {
|
public class Bougerpivot extends CommandBase {
|
||||||
private BrasTelescopique brasTelescopique;
|
/** Creates a new Bougerpivot. */
|
||||||
private Pivot pivot;
|
Pivot pivot;
|
||||||
/** Creates a new PivotBrasRentre. */
|
double distance;
|
||||||
public PivotBrasRentre(BrasTelescopique brasTelescopique, Pivot pivot) {
|
public Bougerpivot(Pivot pivot,double distance) {
|
||||||
this.brasTelescopique = brasTelescopique;
|
|
||||||
this.pivot = pivot;
|
this.pivot = pivot;
|
||||||
// Use addRequirements() here to declare subsystem dependencies.
|
this.distance = distance;
|
||||||
addRequirements(brasTelescopique);
|
|
||||||
addRequirements(pivot);
|
addRequirements(pivot);
|
||||||
|
// Use addRequirements() here to declare subsystem dependencies.
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called when the command is initially scheduled.
|
// Called when the command is initially scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void initialize() {
|
public void initialize() {}
|
||||||
brasTelescopique.fermer();
|
|
||||||
}
|
|
||||||
|
|
||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void execute() {
|
public void execute() {
|
||||||
if(brasTelescopique.photocell()){
|
if(pivot.distance()>distance+0.5 ) {
|
||||||
brasTelescopique.ouvrir();
|
|
||||||
brasTelescopique.Reset();
|
|
||||||
brasTelescopique.AvanceRecule(0);
|
|
||||||
}
|
|
||||||
else{
|
|
||||||
brasTelescopique.AvanceRecule(0.5);
|
|
||||||
}
|
|
||||||
if(pivot.limitpivot()){
|
|
||||||
pivot.Reset();
|
|
||||||
pivot.monteDescendre(0);
|
|
||||||
}
|
|
||||||
else{
|
|
||||||
pivot.monteDescendre(-0.5);
|
pivot.monteDescendre(-0.5);
|
||||||
}
|
}
|
||||||
|
else if(pivot.distance()<distance-0.5) {
|
||||||
|
pivot.monteDescendre(0.5);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
pivot.monteDescendre(0);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
// Called once the command ends or is interrupted.
|
||||||
@Override
|
@Override
|
||||||
public void end(boolean interrupted) {
|
public void end(boolean interrupted) {
|
||||||
brasTelescopique.AvanceRecule(0);
|
|
||||||
pivot.monteDescendre(0);
|
pivot.monteDescendre(0);
|
||||||
brasTelescopique.ouvrir();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
||||||
@Override
|
@Override
|
||||||
public boolean isFinished() {
|
public boolean isFinished() {
|
||||||
return brasTelescopique.photocell() && pivot.limitpivot();
|
return pivot.distance()>distance-0.5 && pivot.distance()<distance+0.5;
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
@ -0,0 +1,25 @@
|
|||||||
|
// 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.commands.bras;
|
||||||
|
|
||||||
|
|
||||||
|
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||||
|
import frc.robot.subsystems.bras.BrasTelescopique;
|
||||||
|
import frc.robot.subsystems.bras.Pivot;
|
||||||
|
|
||||||
|
// NOTE: Consider using this command inline, rather than writing a subclass. For more
|
||||||
|
// information, see:
|
||||||
|
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
|
||||||
|
public class DescendrePivotBras extends SequentialCommandGroup {
|
||||||
|
/** Creates a new DescendrePivotBras. */
|
||||||
|
public DescendrePivotBras(BrasTelescopique brasTelescopique, Pivot pivot, double distanceBras, double distancePivot) {
|
||||||
|
// Add your commands in the addCommands() call, e.g.
|
||||||
|
// addCommands(new FooCommand(), new BarCommand());
|
||||||
|
addCommands(
|
||||||
|
new Bougerbras(brasTelescopique, distanceBras),
|
||||||
|
new Bougerpivot(pivot, distancePivot)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
28
src/main/java/frc/robot/commands/bras/MonterPivotBras.java
Normal file
28
src/main/java/frc/robot/commands/bras/MonterPivotBras.java
Normal file
@ -0,0 +1,28 @@
|
|||||||
|
// 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.commands.bras;
|
||||||
|
|
||||||
|
import edu.wpi.first.wpilibj2.command.Commands;
|
||||||
|
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
|
||||||
|
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||||
|
import frc.robot.subsystems.bras.BrasTelescopique;
|
||||||
|
import frc.robot.subsystems.bras.Pivot;
|
||||||
|
|
||||||
|
// NOTE: Consider using this command inline, rather than writing a subclass. For more
|
||||||
|
// information, see:
|
||||||
|
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
|
||||||
|
public class MonterPivotBras extends ParallelCommandGroup {
|
||||||
|
/** Creates a new Sequancepivotbras. */
|
||||||
|
public MonterPivotBras(BrasTelescopique brasTelescopique, Pivot pivot, double distanceBras, double distancePivot) {
|
||||||
|
|
||||||
|
// Add your commands in the addCommands() call, e.g.
|
||||||
|
// addCommands(new FooCommand(), new BarCommand());
|
||||||
|
addCommands(
|
||||||
|
new SequentialCommandGroup(Commands.waitUntil(()->pivot.distance()>8),new Bougerbras(brasTelescopique, distanceBras)),
|
||||||
|
new Bougerpivot(pivot, distancePivot)
|
||||||
|
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
@ -1,67 +0,0 @@
|
|||||||
// 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.commands.bras;
|
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
|
||||||
import frc.robot.subsystems.bras.BrasTelescopique;
|
|
||||||
import frc.robot.subsystems.bras.Pivot;
|
|
||||||
|
|
||||||
public class PivotChercheBas extends CommandBase {
|
|
||||||
private BrasTelescopique brasTelescopique;
|
|
||||||
private Pivot pivot;
|
|
||||||
/** Creates a new PivotChercheBas. */
|
|
||||||
public PivotChercheBas(BrasTelescopique brasTelescopique, Pivot pivot) {
|
|
||||||
this.brasTelescopique = brasTelescopique;
|
|
||||||
this.pivot = pivot;
|
|
||||||
// Use addRequirements() here to declare subsystem dependencies.
|
|
||||||
addRequirements(brasTelescopique);
|
|
||||||
addRequirements(pivot);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Called when the command is initially scheduled.
|
|
||||||
@Override
|
|
||||||
public void initialize() {
|
|
||||||
brasTelescopique.fermer();
|
|
||||||
}
|
|
||||||
|
|
||||||
// Called every time the scheduler runs while the command is scheduled.
|
|
||||||
@Override
|
|
||||||
public void execute() {
|
|
||||||
if(brasTelescopique.distance()>-17.5){
|
|
||||||
brasTelescopique.AvanceRecule(-0.2);
|
|
||||||
brasTelescopique.fermer();
|
|
||||||
}
|
|
||||||
else if(brasTelescopique.distance()<-19.5) {
|
|
||||||
brasTelescopique.AvanceRecule(0.2);
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
brasTelescopique.AvanceRecule(0);
|
|
||||||
brasTelescopique.ouvrir();
|
|
||||||
}
|
|
||||||
if (pivot.distance()<8.5){
|
|
||||||
pivot.monteDescendre(0.3);
|
|
||||||
}
|
|
||||||
else if(pivot.distance()>10.5) {
|
|
||||||
pivot.monteDescendre(-0.3);
|
|
||||||
}
|
|
||||||
else{
|
|
||||||
pivot.monteDescendre(0);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
|
||||||
@Override
|
|
||||||
public void end(boolean interrupted) {
|
|
||||||
brasTelescopique.AvanceRecule(0);
|
|
||||||
pivot.monteDescendre(0);
|
|
||||||
brasTelescopique.fermer();
|
|
||||||
}
|
|
||||||
|
|
||||||
// Returns true when the command should end.
|
|
||||||
@Override
|
|
||||||
public boolean isFinished() {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
}
|
|
@ -51,6 +51,6 @@ public class BrasTelescopique extends SubsystemBase {
|
|||||||
}
|
}
|
||||||
@Override
|
@Override
|
||||||
public void periodic() {
|
public void periodic() {
|
||||||
|
if(photocell())Reset();
|
||||||
}
|
}
|
||||||
}
|
}
|
@ -42,6 +42,7 @@ public class Pivot extends SubsystemBase {
|
|||||||
}
|
}
|
||||||
@Override
|
@Override
|
||||||
public void periodic() {
|
public void periodic() {
|
||||||
|
if(limitpivot())Reset();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
x
Reference in New Issue
Block a user