Merge branch 'main' of https://demerso.net/pls5618/2023/robot
This commit is contained in:
commit
ea716afab9
@ -11,8 +11,8 @@ public class Constants {
|
||||
//moteur
|
||||
|
||||
|
||||
public static int GratteD = 7;
|
||||
public static int GratteG = 8;
|
||||
public static int GratteD = 8;
|
||||
public static int GratteG = 7;
|
||||
|
||||
|
||||
// pneumatique
|
||||
|
@ -3,6 +3,7 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot;
|
||||
|
||||
import java.util.Map;
|
||||
|
||||
|
||||
@ -40,72 +41,64 @@ import frc.robot.commands.Gyro;
|
||||
import frc.robot.commands.Reculer;
|
||||
import frc.robot.commands.Tape;
|
||||
import frc.robot.commands.bras.BrasManuel;
|
||||
import frc.robot.commands.bras.DescendrePivotBras;
|
||||
import frc.robot.commands.bras.FermePince;
|
||||
import frc.robot.commands.bras.MonterPivotBras;
|
||||
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.PivoteBrasBas;
|
||||
import frc.robot.commands.bras.PivoteBrasHaut;
|
||||
import frc.robot.commands.bras.PivoteBrasMilieux;
|
||||
|
||||
|
||||
import frc.robot.commands.ActiverLimeLight;
|
||||
public class RobotContainer {
|
||||
|
||||
CommandXboxController manette1 = new CommandXboxController(0);
|
||||
CommandXboxController manette2 = new CommandXboxController(1);
|
||||
|
||||
SendableChooser<String> chooser = new SendableChooser<>();
|
||||
String enhaut = "en haut";
|
||||
String aumilieux = "au milieux";
|
||||
String enbas = "en bas";
|
||||
String nulpart = "nul part";
|
||||
ShuffleboardLayout layoutauto = Shuffleboard.getTab("teb").getLayout("auto",BuiltInLayouts.kList)
|
||||
.withSize(2, 2).withProperties(Map.of("Label position","LEFT"));
|
||||
GenericEntry autobalance = layoutauto.add("choix balance",true).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
||||
GenericEntry autosortir = layoutauto.add("choix sortir",false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
||||
GenericEntry reculerdistances = layoutauto.addPersistent("reculerdistancesortir",-66).getEntry();
|
||||
GenericEntry reculerdistanceb = layoutauto.addPersistent("reculerdistancebalance", -31).getEntry();
|
||||
GenericEntry avancerdistance = layoutauto.addPersistent("avancer",-35).getEntry();
|
||||
// subsystems
|
||||
BasePilotable basePilotable = new BasePilotable();
|
||||
Gratte gratte = new Gratte();
|
||||
BrasTelescopique brasTelescopique = new BrasTelescopique();
|
||||
Pince pince = new Pince();
|
||||
Pivot pivot = new Pivot();
|
||||
Limelight limelight = new Limelight();
|
||||
//commands
|
||||
BrakeFerme brakeFerme = new BrakeFerme(basePilotable);
|
||||
BrakeOuvre brakeOuvre = new BrakeOuvre(basePilotable);
|
||||
GratteBaisser gratteBaisser = new GratteBaisser(gratte);
|
||||
GratteMonte gratteMonte = new GratteMonte(gratte);
|
||||
Gyro gyro = new Gyro(basePilotable);
|
||||
FermePince fermePince = new FermePince(pince);
|
||||
OuvrePince ouvrePince = new OuvrePince(pince);
|
||||
PivotBrasRentre pivotBrasRentre = new PivotBrasRentre(brasTelescopique, pivot);
|
||||
PivoteBrasBas pivoteBrasBas = new PivoteBrasBas(brasTelescopique, pivot);
|
||||
PivoteBrasMilieux pivoteBrasMilieux = new PivoteBrasMilieux(brasTelescopique, pivot);
|
||||
PivoteBrasHaut pivoteBrasHaut = new PivoteBrasHaut(brasTelescopique, pivot);
|
||||
Cone cone = new Cone(limelight, basePilotable, ()->-manette1.getLeftY());
|
||||
Reculer reculers = new Reculer(basePilotable, ()->reculerdistances.getDouble(0));
|
||||
Reculer reculerb = new Reculer(basePilotable, ()->reculerdistanceb.getDouble(0));
|
||||
Avancer avancer = new Avancer(basePilotable, ()->avancerdistance.getDouble(0));
|
||||
PivotChercheBas pivotChercheBas = new PivotChercheBas(brasTelescopique, pivot);
|
||||
PivotChercheHaut pivotChercheHaut = new PivotChercheHaut(brasTelescopique, pivot);
|
||||
Cube cube = new Cube(limelight, basePilotable, ()-> manette1.getLeftY());
|
||||
Apriltag aprilTag = new Apriltag(limelight, basePilotable,()-> manette1.getLeftY());
|
||||
Tape tape = new Tape(limelight, basePilotable, ()-> manette1.getLeftY());
|
||||
PivotManuel pivotManuel = new PivotManuel(pivot,manette2::getLeftX);
|
||||
BrasManuel brasManuel = new BrasManuel(brasTelescopique,manette2::getLeftY);
|
||||
CommandXboxController manette1 = new CommandXboxController(0);
|
||||
CommandXboxController manette2 = new CommandXboxController(1);
|
||||
|
||||
// dashboard
|
||||
SendableChooser<String> chooser = new SendableChooser<>();
|
||||
String enhaut = "en haut";
|
||||
String aumilieux = "au milieux";
|
||||
String enbas = "en bas";
|
||||
String nulpart = "nul part";
|
||||
ShuffleboardLayout layoutauto = Shuffleboard.getTab("teb").getLayout("auto", BuiltInLayouts.kList)
|
||||
.withSize(2, 2).withProperties(Map.of("Label position", "LEFT"));
|
||||
GenericEntry autobalance = layoutauto.add("choix balance", true).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
||||
GenericEntry autosortir = layoutauto.add("choix sortir", false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
||||
GenericEntry reculerdistances = layoutauto.addPersistent("reculerdistancesortir", 0).getEntry();
|
||||
GenericEntry reculerdistanceb = layoutauto.addPersistent("reculerdistancebalance", 0).getEntry();
|
||||
GenericEntry avancerdistance = layoutauto.addPersistent("avancer", 0).getEntry();
|
||||
|
||||
public RobotContainer() {
|
||||
chooser.setDefaultOption(enhaut, enhaut);
|
||||
// subsystems
|
||||
BasePilotable basePilotable = new BasePilotable();
|
||||
Gratte gratte = new Gratte();
|
||||
BrasTelescopique brasTelescopique = new BrasTelescopique();
|
||||
Pince pince = new Pince();
|
||||
Pivot pivot = new Pivot();
|
||||
Limelight limelight = new Limelight();
|
||||
|
||||
// commands
|
||||
BrakeFerme brakeFerme = new BrakeFerme(basePilotable);
|
||||
BrakeOuvre brakeOuvre = new BrakeOuvre(basePilotable);
|
||||
GratteBaisser gratteBaisser = new GratteBaisser(gratte);
|
||||
GratteMonte gratteMonte = new GratteMonte(gratte);
|
||||
Gyro gyro = new Gyro(basePilotable);
|
||||
FermePince fermePince = new FermePince(pince);
|
||||
OuvrePince ouvrePince = new OuvrePince(pince);
|
||||
Cone cone = new Cone(limelight, basePilotable, () -> -manette1.getLeftY());
|
||||
Reculer reculers = new Reculer(basePilotable, () -> reculerdistances.getDouble(0));
|
||||
Reculer reculerb = new Reculer(basePilotable, () -> reculerdistanceb.getDouble(0));
|
||||
Avancer avancer = new Avancer(basePilotable, () -> avancerdistance.getDouble(0));
|
||||
Cube cube = new Cube(limelight, basePilotable, () -> manette1.getLeftY());
|
||||
Apriltag aprilTag = new Apriltag(limelight, basePilotable, () -> manette1.getLeftY());
|
||||
Tape tape = new Tape(limelight, basePilotable, () -> manette1.getLeftY());
|
||||
PivotManuel pivotManuel = new PivotManuel(pivot, manette1::getRightY);
|
||||
BrasManuel brasManuel = new BrasManuel(brasTelescopique, manette1::getRightX);
|
||||
ActiverLimeLight activerLimeLight = new ActiverLimeLight(limelight);
|
||||
|
||||
public RobotContainer() {
|
||||
chooser.addOption(enhaut, enhaut);
|
||||
chooser.addOption(enbas, enbas);
|
||||
chooser.addOption(aumilieux, aumilieux);
|
||||
chooser.addOption(nulpart, nulpart);
|
||||
layoutauto.add("choix hauteur",chooser);
|
||||
layoutauto.add("choix hauteur", chooser);
|
||||
configureBindings();
|
||||
CameraServer.startAutomaticCapture();
|
||||
basePilotable.setDefaultCommand(new RunCommand(() -> {
|
||||
@ -114,50 +107,58 @@ public RobotContainer() {
|
||||
brasTelescopique.setDefaultCommand(brasManuel);
|
||||
pivot.setDefaultCommand(pivotManuel);
|
||||
}
|
||||
|
||||
private void configureBindings() {
|
||||
// manette 1
|
||||
manette1.a().toggleOnTrue(Commands.startEnd(pince::ouvrir, pince::fermer,pince));
|
||||
manette1.x().onTrue(brakeOuvre);
|
||||
manette1.b().onTrue(brakeFerme);
|
||||
manette2.a().onTrue(brakeOuvre);
|
||||
manette2.b().onTrue(brakeFerme);
|
||||
manette1.leftBumper().whileTrue(aprilTag);
|
||||
manette1.rightBumper().whileTrue(tape);
|
||||
manette1.povUp().whileTrue(pivoteBrasHaut);
|
||||
manette1.povDown().whileTrue(pivoteBrasBas);
|
||||
manette1.povRight().whileTrue(pivoteBrasMilieux);
|
||||
manette1.povLeft().whileTrue(pivotBrasRentre);
|
||||
manette1.povUp().whileTrue(creerCommandBras(51, -40));
|
||||
manette1.povDown().whileTrue(creerCommandBras(9, -14));
|
||||
manette1.povRight().whileTrue(creerCommandBras(44, -17));
|
||||
manette1.povLeft().whileTrue(creerCommandBras(0, 0));
|
||||
manette1.y().whileTrue(activerLimeLight);
|
||||
//manette 2
|
||||
manette2.povDown().onTrue(pivotChercheBas);
|
||||
manette2.povUp().onTrue(pivotChercheHaut);
|
||||
manette2.povDown().whileTrue(creerCommandBras(9, -18));
|
||||
manette2.povUp().whileTrue(creerCommandBras(44, 0));
|
||||
manette2.rightBumper().whileTrue(cube);
|
||||
manette2.leftBumper().whileTrue(cone);
|
||||
manette2.y().whileTrue(gyro);
|
||||
manette2.start().onTrue(new InstantCommand(basePilotable::resetGyro));
|
||||
manette2.a().whileTrue(gratteMonte);
|
||||
manette2.b().whileTrue(gratteBaisser);
|
||||
manette2.back().onTrue(new InstantCommand(basePilotable::Reset));
|
||||
manette1.b().whileTrue(gratteMonte);
|
||||
manette1.x().whileTrue(gratteBaisser);
|
||||
|
||||
}
|
||||
|
||||
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() {
|
||||
chooser.getSelected();
|
||||
autobalance.getBoolean(true);
|
||||
return Commands.waitSeconds(14).deadlineWith( new SequentialCommandGroup(
|
||||
Commands.select(Map.ofEntries(
|
||||
Map.entry(enhaut,pivoteBrasHaut),
|
||||
Map.entry(aumilieux,pivoteBrasMilieux),
|
||||
Map.entry(enbas,pivoteBrasBas),
|
||||
Map.entry(nulpart,pivotBrasRentre)
|
||||
), chooser::getSelected),
|
||||
ouvrePince.unless(()->chooser.getSelected().equals(nulpart)),
|
||||
Commands.waitSeconds(1),
|
||||
fermePince.unless(()->chooser.getSelected().equals(nulpart)),
|
||||
new PivotBrasRentre(brasTelescopique , pivot).unless(()->chooser.getSelected().equals(nulpart)),
|
||||
Commands.waitSeconds(1),
|
||||
Commands.either(reculers, reculerb,()-> autosortir.getBoolean(true)),
|
||||
avancer.unless(()->!autosortir.getBoolean(true)|| autobalance.getBoolean(false)),
|
||||
Commands.either(gyro, Commands.none(),()-> autobalance.getBoolean(true))
|
||||
)).andThen(new InstantCommand(basePilotable::BrakeOuvre,basePilotable));
|
||||
|
||||
return Commands.deadline(
|
||||
Commands.waitSeconds(14.6),
|
||||
new SequentialCommandGroup(
|
||||
Commands.select(Map.ofEntries(
|
||||
Map.entry(enhaut, creerCommandBras(51, -40)),
|
||||
Map.entry(aumilieux, creerCommandBras(9, -14)),
|
||||
Map.entry(enbas, creerCommandBras(44, -17)),
|
||||
Map.entry(nulpart, creerCommandBras(0, 0))), chooser::getSelected),
|
||||
new OuvrePince(pince).unless(() -> chooser.getSelected().equals(nulpart)),
|
||||
Commands.waitSeconds(1),
|
||||
new FermePince(pince).unless(() -> chooser.getSelected().equals(nulpart)),
|
||||
creerCommandBras(0, 0).unless(() -> chooser.getSelected().equals(nulpart)),
|
||||
Commands.waitSeconds(1),
|
||||
Commands.either(reculers, reculerb, () -> autosortir.getBoolean(true)),
|
||||
new Avancer(basePilotable, () -> avancerdistance.getDouble(0)).unless(() -> !autosortir.getBoolean(true) || !autobalance.getBoolean(false)),
|
||||
Commands.either(gyro, Commands.none(), () -> autobalance.getBoolean(true))))
|
||||
.andThen(brakeOuvre);
|
||||
|
||||
}
|
||||
}
|
||||
|
40
src/main/java/frc/robot/commands/ActiverLimeLight.java
Normal file
40
src/main/java/frc/robot/commands/ActiverLimeLight.java
Normal file
@ -0,0 +1,40 @@
|
||||
// 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;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import frc.robot.subsystems.Limelight;
|
||||
|
||||
public class ActiverLimeLight extends CommandBase {
|
||||
private Limelight limelight;
|
||||
/** Creates a new ActiverLimeLight. */
|
||||
public ActiverLimeLight(Limelight limelight) {
|
||||
this.limelight = limelight;
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
addRequirements(limelight);
|
||||
}
|
||||
|
||||
// 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() {
|
||||
limelight.joueurhumain();
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
limelight.joueurhumain1();
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
@ -32,7 +32,7 @@ public class Apriltag extends CommandBase {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
basePilotable.drive(doubleSupplier.getAsDouble(), limelight.getYaw());
|
||||
basePilotable.drive(doubleSupplier.getAsDouble(), limelight.getYaw(),false);
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
|
@ -7,9 +7,6 @@ package frc.robot.commands;
|
||||
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import frc.robot.subsystems.BasePilotable;
|
||||
|
||||
@ -33,12 +30,14 @@ public class Avancer extends CommandBase {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
basePilotable.drive(0.3,0);
|
||||
basePilotable.drive(0.4,0);
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {}
|
||||
public void end(boolean interrupted) {
|
||||
basePilotable.drive(0,0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
|
@ -3,6 +3,7 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import frc.robot.subsystems.Gratte;
|
||||
|
||||
@ -19,23 +20,23 @@ public class GratteBaisser extends CommandBase {
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
gratte.setenHaut(false);
|
||||
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(gratte.basd()){
|
||||
gratte.baiserd(0);
|
||||
gratte.bougerd(0);
|
||||
}
|
||||
else{
|
||||
gratte.baiserd(0.5);
|
||||
gratte.bougerd(0.3);
|
||||
}
|
||||
if(gratte.basg()){
|
||||
gratte.baiserg(0);
|
||||
gratte.bougerg(0);
|
||||
}
|
||||
else{
|
||||
gratte.baiserg(0.5);
|
||||
gratte.bougerg(0.3);
|
||||
}
|
||||
|
||||
|
||||
@ -44,8 +45,8 @@ public class GratteBaisser extends CommandBase {
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
gratte.baiserd(0);
|
||||
gratte.baiserg(0);
|
||||
gratte.bougerd(0);
|
||||
gratte.bougerg(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
|
@ -21,31 +21,30 @@ public class GratteMonte extends CommandBase {
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
gratte.setenHaut(true);
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(gratte.hautd()){
|
||||
gratte.Leverd(0);
|
||||
gratte.bougerd(0);
|
||||
}
|
||||
else{
|
||||
gratte.Leverd(0.5);
|
||||
gratte.bougerd(-0.3);
|
||||
}
|
||||
if(gratte.hautg()) {
|
||||
gratte.Leverg(0);
|
||||
gratte.bougerg(0);
|
||||
}
|
||||
else{
|
||||
gratte.Leverg(0.5);
|
||||
gratte.bougerg(-0.3);
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
gratte.Leverd(0);
|
||||
gratte.Leverg(0);
|
||||
gratte.bougerd(0);
|
||||
gratte.bougerg(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
|
@ -26,11 +26,11 @@ public class Gyro extends CommandBase {
|
||||
public void execute() {
|
||||
if(basePilotable.getpitch()>6)
|
||||
{
|
||||
basePilotable.drive(0.3*basePilotable.getpitch()/12, 0);
|
||||
basePilotable.drive(0.4*basePilotable.getpitch()/12, 0);
|
||||
}
|
||||
else if(basePilotable.getpitch()<-6)
|
||||
{
|
||||
basePilotable.drive(0.3*basePilotable.getpitch()/12, 0);
|
||||
basePilotable.drive(0.4*basePilotable.getpitch()/12, 0);
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -35,7 +35,9 @@ public class Reculer extends CommandBase {
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {}
|
||||
public void end(boolean interrupted) {
|
||||
basePilotable.drive(0,0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
|
@ -32,7 +32,7 @@ public class Tape extends CommandBase {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
basePilotable.drive(doubleSupplier.getAsDouble(), limelight.getYaw());
|
||||
basePilotable.drive(doubleSupplier.getAsDouble(), limelight.getYaw(),false);
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
|
@ -6,45 +6,36 @@ 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 PivotChercheHaut extends CommandBase {
|
||||
private BrasTelescopique brasTelescopique;
|
||||
private Pivot pivot;
|
||||
/** Creates a new PivotChercheHaut. */
|
||||
public PivotChercheHaut(BrasTelescopique brasTelescopique, Pivot pivot) {
|
||||
public class Bougerbras extends CommandBase {
|
||||
/** Creates a new bougerbras. */
|
||||
double distance;
|
||||
BrasTelescopique brasTelescopique;
|
||||
public Bougerbras(BrasTelescopique brasTelescopique,double distance) {
|
||||
this.brasTelescopique = brasTelescopique;
|
||||
this.pivot = pivot;
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
this.distance = distance;
|
||||
addRequirements(brasTelescopique);
|
||||
addRequirements(pivot);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// 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.photocell()){
|
||||
brasTelescopique.ouvrir();
|
||||
brasTelescopique.Reset();
|
||||
brasTelescopique.AvanceRecule(0);
|
||||
}
|
||||
else{
|
||||
if(brasTelescopique.distance()>distance+0.5 ) {
|
||||
brasTelescopique.AvanceRecule(-0.3);
|
||||
|
||||
}
|
||||
else if(brasTelescopique.distance()<distance-0.5) {
|
||||
brasTelescopique.AvanceRecule(0.3);
|
||||
}
|
||||
if (pivot.distance()<43.5){
|
||||
pivot.monteDescendre(0.5);
|
||||
}
|
||||
else if(pivot.distance()>44.5) {
|
||||
pivot.monteDescendre(-0.5);
|
||||
}
|
||||
else{
|
||||
pivot.monteDescendre(0);
|
||||
else {
|
||||
brasTelescopique.AvanceRecule(0);
|
||||
}
|
||||
}
|
||||
|
||||
@ -52,13 +43,13 @@ public class PivotChercheHaut extends CommandBase {
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
brasTelescopique.AvanceRecule(0);
|
||||
pivot.monteDescendre(0);
|
||||
brasTelescopique.ouvrir();
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
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;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import frc.robot.subsystems.bras.BrasTelescopique;
|
||||
import frc.robot.subsystems.bras.Pivot;
|
||||
|
||||
public class PivotBrasRentre extends CommandBase {
|
||||
private BrasTelescopique brasTelescopique;
|
||||
private Pivot pivot;
|
||||
/** Creates a new PivotBrasRentre. */
|
||||
public PivotBrasRentre(BrasTelescopique brasTelescopique, Pivot pivot) {
|
||||
this.brasTelescopique = brasTelescopique;
|
||||
public class Bougerpivot extends CommandBase {
|
||||
/** Creates a new Bougerpivot. */
|
||||
Pivot pivot;
|
||||
double distance;
|
||||
public Bougerpivot(Pivot pivot,double distance) {
|
||||
this.pivot = pivot;
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
addRequirements(brasTelescopique);
|
||||
this.distance = distance;
|
||||
addRequirements(pivot);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
brasTelescopique.fermer();
|
||||
}
|
||||
public void initialize() {}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(brasTelescopique.photocell()){
|
||||
brasTelescopique.ouvrir();
|
||||
brasTelescopique.Reset();
|
||||
brasTelescopique.AvanceRecule(0);
|
||||
}
|
||||
else{
|
||||
brasTelescopique.AvanceRecule(0.5);
|
||||
}
|
||||
if(pivot.limitpivot()){
|
||||
pivot.Reset();
|
||||
pivot.monteDescendre(0);
|
||||
}
|
||||
else{
|
||||
if(pivot.distance()>distance+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.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
brasTelescopique.AvanceRecule(0);
|
||||
pivot.monteDescendre(0);
|
||||
brasTelescopique.ouvrir();
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return brasTelescopique.photocell() && pivot.limitpivot();
|
||||
}
|
||||
return pivot.distance()>distance-0.5 && pivot.distance()<distance+0.5;
|
||||
|
||||
}
|
||||
}
|
@ -29,10 +29,12 @@ public class BrasManuel extends CommandBase {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(doubleSupplier.getAsDouble()>0.2 && doubleSupplier.getAsDouble()<-0.2){
|
||||
brasTelescopique.AvanceRecule(doubleSupplier.getAsDouble());
|
||||
if(doubleSupplier.getAsDouble()>0.2 || doubleSupplier.getAsDouble()<-0.2){
|
||||
brasTelescopique.AvanceRecule(doubleSupplier.getAsDouble()*0.5);
|
||||
}
|
||||
|
||||
else{
|
||||
brasTelescopique.AvanceRecule(0);
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
|
@ -0,0 +1,27 @@
|
||||
// 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)
|
||||
|
||||
);
|
||||
}
|
||||
}
|
30
src/main/java/frc/robot/commands/bras/MonterPivotBras.java
Normal file
30
src/main/java/frc/robot/commands/bras/MonterPivotBras.java
Normal file
@ -0,0 +1,30 @@
|
||||
// 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.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 SequentialCommandGroup {
|
||||
/** 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 Bougerpivot(pivot, 10).unless(()->pivot.distance()>10),
|
||||
new ParallelCommandGroup(new Bougerpivot(pivot, distancePivot)),
|
||||
new ParallelCommandGroup(new Bougerbras(brasTelescopique, distanceBras))
|
||||
|
||||
|
||||
);
|
||||
}
|
||||
}
|
@ -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;
|
||||
}
|
||||
}
|
@ -27,10 +27,14 @@ public class PivotManuel extends CommandBase {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(doubleSupplier.getAsDouble()>0.2 && doubleSupplier.getAsDouble()<-0.2){
|
||||
pivot.monteDescendre(doubleSupplier.getAsDouble());}
|
||||
if(doubleSupplier.getAsDouble()>0.2 || doubleSupplier.getAsDouble()<-0.2){
|
||||
pivot.monteDescendre(-doubleSupplier.getAsDouble()*0.5)
|
||||
;}
|
||||
else{
|
||||
pivot.monteDescendre(0);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {}
|
||||
|
@ -31,21 +31,21 @@ public class PivoteBrasBas extends CommandBase {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(brasTelescopique.distance()>-13.5){
|
||||
if(brasTelescopique.distance()>-8.5){
|
||||
brasTelescopique.AvanceRecule(-0.2);
|
||||
brasTelescopique.fermer();
|
||||
}
|
||||
else if(brasTelescopique.distance()<-15.5) {
|
||||
else if(brasTelescopique.distance()<-9.5) {
|
||||
brasTelescopique.AvanceRecule(0.2);
|
||||
}
|
||||
else {
|
||||
brasTelescopique.AvanceRecule(0);
|
||||
brasTelescopique.ouvrir();
|
||||
}
|
||||
if (pivot.distance()<8.5){
|
||||
if (pivot.distance()<12.5){
|
||||
pivot.monteDescendre(0.4);
|
||||
}
|
||||
else if(pivot.distance()>10.5) {
|
||||
else if(pivot.distance()>13.5) {
|
||||
pivot.monteDescendre(-0.4);
|
||||
}
|
||||
else{
|
||||
|
@ -29,21 +29,21 @@ public class PivoteBrasHaut extends CommandBase {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(brasTelescopique.distance()>-39.5){
|
||||
if(brasTelescopique.distance()>-36.5){
|
||||
brasTelescopique.AvanceRecule(-0.15);
|
||||
brasTelescopique.fermer();
|
||||
}
|
||||
else if(brasTelescopique.distance()<-41.5) {
|
||||
else if(brasTelescopique.distance()<-37.5) {
|
||||
brasTelescopique.AvanceRecule(-0.15);
|
||||
}
|
||||
else {
|
||||
brasTelescopique.AvanceRecule(0);
|
||||
brasTelescopique.ouvrir();
|
||||
}
|
||||
if (pivot.distance()<50.5){
|
||||
if (pivot.distance()<52.5){
|
||||
pivot.monteDescendre(0.5);
|
||||
}
|
||||
else if(pivot.distance()>52.5) {
|
||||
else if(pivot.distance()>53.5) {
|
||||
pivot.monteDescendre(-0.5);
|
||||
}
|
||||
else{
|
||||
|
@ -29,11 +29,11 @@ public class PivoteBrasMilieux extends CommandBase {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(brasTelescopique.distance()>-16.5){
|
||||
if(brasTelescopique.distance()>-11){
|
||||
brasTelescopique.AvanceRecule(-0.15);
|
||||
brasTelescopique.fermer();
|
||||
}
|
||||
else if(brasTelescopique.distance()<-17.5) {
|
||||
else if(brasTelescopique.distance()<-13) {
|
||||
brasTelescopique.AvanceRecule(0.15);
|
||||
}
|
||||
else {
|
||||
|
@ -17,6 +17,7 @@ import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.Constants;
|
||||
import frc.robot.commands.bras.Bougerbras;
|
||||
|
||||
public class BasePilotable extends SubsystemBase {
|
||||
final CANSparkMax avantdroit = new CANSparkMax(Constants.avantdroit, MotorType.kBrushless);
|
||||
@ -42,6 +43,9 @@ public class BasePilotable extends SubsystemBase {
|
||||
public void drive(double xSpeed, double zRotation){
|
||||
drive.arcadeDrive(xSpeed, zRotation);
|
||||
}
|
||||
public void drive(double xSpeed, double zRotation, boolean square){
|
||||
drive.arcadeDrive(xSpeed, zRotation, square);
|
||||
}
|
||||
public double distance(){
|
||||
return (-avantdroit.getEncoder().getPosition()
|
||||
+avantgauche.getEncoder().getPosition()
|
||||
|
@ -24,15 +24,6 @@ ShuffleboardLayout limitswitchgratte = Shuffleboard.getTab("teb")
|
||||
private DigitalInput limithg = new DigitalInput(Constants.limithg);
|
||||
private DigitalInput limitbd = new DigitalInput(Constants.limitbd);
|
||||
private DigitalInput limitbg = new DigitalInput(Constants.limitbg);
|
||||
public boolean baiser;
|
||||
boolean enHaut = true;
|
||||
public void setenHaut(boolean enHaut){
|
||||
this.enHaut = enHaut;
|
||||
}
|
||||
public boolean getenHaut(){
|
||||
return enHaut;
|
||||
|
||||
}
|
||||
|
||||
public boolean hautd(){
|
||||
return limithd.get();
|
||||
@ -55,17 +46,11 @@ ShuffleboardLayout limitswitchgratte = Shuffleboard.getTab("teb")
|
||||
limitswitchgratte.addBoolean ("limithd", this::hautd);
|
||||
limitswitchgratte.addBoolean ("limitbg", this::basg);
|
||||
}
|
||||
public void Leverd(double vitesse){
|
||||
Gratted.set(-vitesse);
|
||||
public void bougerd(double vitesse){
|
||||
Gratted.set(vitesse);
|
||||
|
||||
}
|
||||
public void Leverg(double vitesse){
|
||||
Gratteg.set(-vitesse);
|
||||
}
|
||||
public void baiserd(double vitesse){
|
||||
Gratted.set(vitesse);
|
||||
}
|
||||
public void baiserg(double vitesse){
|
||||
public void bougerg(double vitesse){
|
||||
Gratteg.set(vitesse);
|
||||
}
|
||||
|
||||
|
@ -4,7 +4,6 @@
|
||||
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import edu.wpi.first.cameraserver.CameraServer;
|
||||
|
||||
|
||||
import org.photonvision.PhotonCamera;
|
||||
@ -20,7 +19,7 @@ public class Limelight extends SubsystemBase {
|
||||
PhotonCamera limelight = new PhotonCamera("limelight");
|
||||
/** Creates a new Limelight. */
|
||||
public Limelight() {
|
||||
CameraServer.startAutomaticCapture();
|
||||
|
||||
PortForwarder.add(5800, "photonvision.local", 5800);
|
||||
}
|
||||
|
||||
@ -42,12 +41,13 @@ public class Limelight extends SubsystemBase {
|
||||
public void tape() {
|
||||
limelight.setLED(VisionLEDMode.kOn);
|
||||
limelight.setPipelineIndex(1);
|
||||
|
||||
}
|
||||
|
||||
public double getYaw() {
|
||||
var result = limelight.getLatestResult();
|
||||
if(result.hasTargets()){
|
||||
return -result.getBestTarget().getYaw()/60;
|
||||
return -result.getBestTarget().getYaw()/45;
|
||||
}
|
||||
return 0;
|
||||
|
||||
@ -56,6 +56,12 @@ public class Limelight extends SubsystemBase {
|
||||
limelight.setLED(VisionLEDMode.kOff);
|
||||
limelight.setDriverMode(true);
|
||||
}
|
||||
public void joueurhumain(){
|
||||
limelight.setLED(VisionLEDMode.kOn);
|
||||
}
|
||||
public void joueurhumain1(){
|
||||
limelight.setLED(VisionLEDMode.kOff);
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
}
|
||||
|
@ -51,6 +51,6 @@ public class BrasTelescopique extends SubsystemBase {
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
|
||||
if(photocell())Reset();
|
||||
}
|
||||
}
|
@ -42,6 +42,7 @@ public class Pivot extends SubsystemBase {
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
if(limitpivot())Reset();
|
||||
}
|
||||
|
||||
|
||||
|
Loading…
x
Reference in New Issue
Block a user