Merge branch 'main' of https://demerso.net/pls5618/2023/robot
This commit is contained in:
commit
2feccacf6c
@ -1 +1,26 @@
|
||||
|
||||
[
|
||||
{
|
||||
"name": "/Shuffleboard/teb/auto/reculerdistancesortir",
|
||||
"type": "double",
|
||||
"value": -66.0,
|
||||
"properties": {
|
||||
"persistent": true
|
||||
}
|
||||
},
|
||||
{
|
||||
"name": "/Shuffleboard/teb/auto/reculerdistancebalance",
|
||||
"type": "double",
|
||||
"value": -31.0,
|
||||
"properties": {
|
||||
"persistent": true
|
||||
}
|
||||
},
|
||||
{
|
||||
"name": "/Shuffleboard/teb/auto/avancer",
|
||||
"type": "double",
|
||||
"value": -35.0,
|
||||
"properties": {
|
||||
"persistent": true
|
||||
}
|
||||
}
|
||||
]
|
||||
|
1
networktables.json.bck
Normal file
1
networktables.json.bck
Normal file
@ -0,0 +1 @@
|
||||
|
@ -65,9 +65,9 @@ ShuffleboardLayout layoutauto = Shuffleboard.getTab("teb").getLayout("auto",Buil
|
||||
.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();
|
||||
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();
|
||||
@ -93,9 +93,9 @@ 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, null);
|
||||
Apriltag aprilTag = new Apriltag(limelight, basePilotable, null);
|
||||
Tape tape = new Tape(limelight, basePilotable, null);
|
||||
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);
|
||||
|
||||
@ -126,9 +126,10 @@ public RobotContainer() {
|
||||
private void configureBindings() {
|
||||
// manette 1
|
||||
manette1.a().toggleOnTrue(Commands.startEnd(pince::ouvrir, pince::fermer,pince));
|
||||
manette1.x().toggleOnTrue(Commands.startEnd(basePilotable::BrakeFerme,basePilotable::BrakeOuvre,basePilotable));
|
||||
manette1.leftBumper().toggleOnTrue(aprilTag);
|
||||
manette1.rightBumper().toggleOnTrue(tape);
|
||||
manette1.x().onTrue(brakeOuvre);
|
||||
manette1.b().onTrue(brakeFerme);
|
||||
manette1.leftBumper().whileTrue(aprilTag);
|
||||
manette1.rightBumper().whileTrue(tape);
|
||||
manette1.povUp().whileTrue(pivoteBrasHaut);
|
||||
manette1.povDown().whileTrue(pivoteBrasBas);
|
||||
manette1.povRight().whileTrue(pivoteBrasMilieux);
|
||||
@ -136,19 +137,18 @@ public RobotContainer() {
|
||||
//manette 2
|
||||
manette2.povDown().onTrue(pivotChercheBas);
|
||||
manette2.povUp().onTrue(pivotChercheHaut);
|
||||
manette2.rightBumper().toggleOnTrue(cube);
|
||||
manette2.leftBumper().toggleOnTrue(cone);
|
||||
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));
|
||||
|
||||
}
|
||||
|
||||
public Command getAutonomousCommand() {
|
||||
chooser.getSelected();
|
||||
autobalance.getBoolean(true);
|
||||
return new SequentialCommandGroup(
|
||||
return Commands.waitSeconds(14).deadlineWith( new SequentialCommandGroup(
|
||||
Commands.select(Map.ofEntries(
|
||||
Map.entry(enhaut,pivoteBrasHaut),
|
||||
Map.entry(aumilieux,pivoteBrasMilieux),
|
||||
@ -156,10 +156,14 @@ public RobotContainer() {
|
||||
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)),
|
||||
avancer.unless(()->!autosortir.getBoolean(true)|| autobalance.getBoolean(false)),
|
||||
Commands.either(gyro, Commands.none(),()-> autobalance.getBoolean(true))
|
||||
).deadlineWith(Commands.waitSeconds(14.6)).andThen(brakeOuvre);
|
||||
)).andThen(new InstantCommand(basePilotable::BrakeOuvre,basePilotable));
|
||||
|
||||
|
||||
}
|
||||
|
@ -37,6 +37,6 @@ public class BrakeFerme extends CommandBase {
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
@ -37,6 +37,6 @@ public class BrakeOuvre extends CommandBase {
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
@ -5,7 +5,6 @@
|
||||
package frc.robot.commands;
|
||||
|
||||
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import frc.robot.subsystems.Gratte;
|
||||
|
||||
|
@ -30,7 +30,7 @@ public class Reculer 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.
|
||||
|
@ -29,7 +29,10 @@ public class BrasManuel extends CommandBase {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
brasTelescopique.AvanceRecule(doubleSupplier.getAsDouble());
|
||||
if(doubleSupplier.getAsDouble()>0.2 || doubleSupplier.getAsDouble()<-0.2){
|
||||
brasTelescopique.AvanceRecule(doubleSupplier.getAsDouble());
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
|
@ -33,6 +33,6 @@ public class FermePince extends CommandBase {
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
@ -33,6 +33,6 @@ public class OuvrePince extends CommandBase {
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
@ -42,7 +42,7 @@ public class PivotBrasRentre extends CommandBase {
|
||||
pivot.monteDescendre(0);
|
||||
}
|
||||
else{
|
||||
pivot.monteDescendre(-0.3);
|
||||
pivot.monteDescendre(-0.5);
|
||||
}
|
||||
}
|
||||
|
||||
@ -57,6 +57,6 @@ public class PivotBrasRentre extends CommandBase {
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
return brasTelescopique.photocell() && pivot.limitpivot();
|
||||
}
|
||||
}
|
||||
|
@ -38,10 +38,10 @@ public class PivotChercheHaut extends CommandBase {
|
||||
brasTelescopique.AvanceRecule(0.3);
|
||||
}
|
||||
if (pivot.distance()<43.5){
|
||||
pivot.monteDescendre(0.4);
|
||||
pivot.monteDescendre(0.5);
|
||||
}
|
||||
else if(pivot.distance()>44.5) {
|
||||
pivot.monteDescendre(-0.4);
|
||||
pivot.monteDescendre(-0.5);
|
||||
}
|
||||
else{
|
||||
pivot.monteDescendre(0);
|
||||
|
@ -27,7 +27,8 @@ public class PivotManuel extends CommandBase {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
pivot.monteDescendre(doubleSupplier.getAsDouble());
|
||||
if(doubleSupplier.getAsDouble()>0.2 || doubleSupplier.getAsDouble()<-0.2){
|
||||
pivot.monteDescendre(doubleSupplier.getAsDouble());}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
|
@ -43,10 +43,10 @@ public class PivoteBrasBas extends CommandBase {
|
||||
brasTelescopique.ouvrir();
|
||||
}
|
||||
if (pivot.distance()<8.5){
|
||||
pivot.monteDescendre(0.3);
|
||||
pivot.monteDescendre(0.4);
|
||||
}
|
||||
else if(pivot.distance()>10.5) {
|
||||
pivot.monteDescendre(-0.3);
|
||||
pivot.monteDescendre(-0.4);
|
||||
}
|
||||
else{
|
||||
pivot.monteDescendre(0);
|
||||
@ -65,6 +65,7 @@ public class PivoteBrasBas extends CommandBase {
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
return brasTelescopique.distance()>-13.5 && brasTelescopique.distance() <-14.5 && pivot.distance()<8.5 && pivot.distance()>9.5;
|
||||
|
||||
}
|
||||
}
|
||||
|
@ -33,7 +33,7 @@ public class PivoteBrasHaut extends CommandBase {
|
||||
brasTelescopique.AvanceRecule(-0.15);
|
||||
brasTelescopique.fermer();
|
||||
}
|
||||
else if(brasTelescopique.distance()<41.5) {
|
||||
else if(brasTelescopique.distance()<-41.5) {
|
||||
brasTelescopique.AvanceRecule(-0.15);
|
||||
}
|
||||
else {
|
||||
@ -41,10 +41,10 @@ public class PivoteBrasHaut extends CommandBase {
|
||||
brasTelescopique.ouvrir();
|
||||
}
|
||||
if (pivot.distance()<50.5){
|
||||
pivot.monteDescendre(0.4);
|
||||
pivot.monteDescendre(0.5);
|
||||
}
|
||||
else if(pivot.distance()>52.5) {
|
||||
pivot.monteDescendre(-0.4);
|
||||
pivot.monteDescendre(-0.5);
|
||||
}
|
||||
else{
|
||||
pivot.monteDescendre(0);
|
||||
@ -62,6 +62,6 @@ public class PivoteBrasHaut extends CommandBase {
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
return brasTelescopique.distance()>-39.5 && brasTelescopique.distance() <-41.5 && pivot.distance()<50.5 && pivot.distance()>52.5;
|
||||
}
|
||||
}
|
||||
|
@ -30,21 +30,21 @@ public class PivoteBrasMilieux extends CommandBase {
|
||||
@Override
|
||||
public void execute() {
|
||||
if(brasTelescopique.distance()>-16.5){
|
||||
brasTelescopique.AvanceRecule(-0.2);
|
||||
brasTelescopique.AvanceRecule(-0.15);
|
||||
brasTelescopique.fermer();
|
||||
}
|
||||
else if(brasTelescopique.distance()<-17.5) {
|
||||
brasTelescopique.AvanceRecule(0.2);
|
||||
brasTelescopique.AvanceRecule(0.15);
|
||||
}
|
||||
else {
|
||||
brasTelescopique.AvanceRecule(0);
|
||||
brasTelescopique.ouvrir();
|
||||
}
|
||||
if (pivot.distance()<43.5){
|
||||
pivot.monteDescendre(0.4);
|
||||
pivot.monteDescendre(0.6);
|
||||
}
|
||||
else if(pivot.distance()>44.5) {
|
||||
pivot.monteDescendre(-0.4);
|
||||
pivot.monteDescendre(-0.6);
|
||||
}
|
||||
else{
|
||||
pivot.monteDescendre(0);
|
||||
@ -63,6 +63,7 @@ public class PivoteBrasMilieux extends CommandBase {
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
return brasTelescopique.distance()>-16.5 && brasTelescopique.distance() <-15.5 && pivot.distance()<44.5 && pivot.distance()>43.5;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -47,7 +47,7 @@ public class Limelight extends SubsystemBase {
|
||||
public double getYaw() {
|
||||
var result = limelight.getLatestResult();
|
||||
if(result.hasTargets()){
|
||||
return result.getBestTarget().getYaw();
|
||||
return -result.getBestTarget().getYaw()/60;
|
||||
}
|
||||
return 0;
|
||||
|
||||
|
Loading…
x
Reference in New Issue
Block a user