This commit is contained in:
EdwardFaucher 2023-03-13 18:47:31 -04:00
parent de5b5213cb
commit 6ba1dfbb2c
19 changed files with 256 additions and 156 deletions

View File

@ -2,6 +2,7 @@
"NTProvider": { "NTProvider": {
"types": { "types": {
"/FMSInfo": "FMSInfo", "/FMSInfo": "FMSInfo",
"/Shuffleboard/teb/DifferentialDrive[1]": "DifferentialDrive",
"/Shuffleboard/teb/auto/choix hauteur": "String Chooser" "/Shuffleboard/teb/auto/choix hauteur": "String Chooser"
} }
}, },

View File

@ -1,35 +1,33 @@
package frc.robot; package frc.robot;
public class Constants { public class Constants {
public static int avantdroit = 1; public static int avantdroit = 4;
public static int avantgauche = 2; public static int avantgauche = 6;
public static int arrieredroit = 3; public static int arrieredroit = 3;
public static int arrieregauche = 5; public static int arrieregauche = 5;
public static int BrasTelescopique = 2; public static int BrasTelescopique = 1;
public static int pivot = 6; public static int pivot = 2;
//moteur //moteur
public static int baiserGratte = 8; public static int GratteD = 7;
public static int leverGratte = 0; public static int GratteG = 8;
public static int baisserGratte = 2;
// pneumatique // pneumatique
public static int pistonpinceouvre = 0; public static int pistonpinceouvre = 0;
public static int pistonpinceferme = 1; public static int pistonpinceferme = 1;
public static int actuateur = 2; public static int brakeouvre = 5;
public static int brakedroit = 3; public static int brakeferme = 4;
public static int brakegauche = 4; public static int brakewinchf = 3;
public static int brakewinchf = 5; public static int brakewinchb = 2;
public static int brakewinchb = 6;
// DIO // DIO
public static int limitbd = 0; public static int limitbd = 2;
public static int limitbg = 2; public static int limitbg = 4;
public static int limithd = 3; public static int limithd = 1;
public static int limithg = 1; public static int limithg = 3;
public static int photocell = 4; public static int photocell = 0;
public static int limitpivot = 5; public static int limitpivot = 5;

View File

@ -30,11 +30,13 @@ import frc.robot.commands.GratteMonte;
import frc.robot.commands.Gyro; 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.FermePince; import frc.robot.commands.bras.FermePince;
import frc.robot.commands.bras.OuvrePince; import frc.robot.commands.bras.OuvrePince;
import frc.robot.commands.bras.PivotBrasRentre; import frc.robot.commands.bras.PivotBrasRentre;
import frc.robot.commands.bras.PivotChercheBas; import frc.robot.commands.bras.PivotChercheBas;
import frc.robot.commands.bras.PivotChercheHaut; import frc.robot.commands.bras.PivotChercheHaut;
import frc.robot.commands.bras.PivotManuel;
import frc.robot.commands.bras.PivoteBrasBas; import frc.robot.commands.bras.PivoteBrasBas;
import frc.robot.commands.bras.PivoteBrasHaut; import frc.robot.commands.bras.PivoteBrasHaut;
import frc.robot.commands.bras.PivoteBrasMilieux; import frc.robot.commands.bras.PivoteBrasMilieux;
@ -92,7 +94,8 @@ PivotChercheHaut pivotChercheHaut = new PivotChercheHaut(brasTelescopique, pivot
Cube cube = new Cube(limelight, basePilotable, null); Cube cube = new Cube(limelight, basePilotable, null);
Apriltag aprilTag = new Apriltag(limelight, basePilotable, null); Apriltag aprilTag = new Apriltag(limelight, basePilotable, null);
Tape tape = new Tape(limelight, basePilotable, null); Tape tape = new Tape(limelight, basePilotable, null);
PivotManuel pivotManuel = new PivotManuel(pivot);
BrasManuel brasManuel = new BrasManuel(brasTelescopique);
public RobotContainer() { public RobotContainer() {
@ -106,8 +109,8 @@ public RobotContainer() {
configureBindings(); configureBindings();
CameraServer.startAutomaticCapture(); CameraServer.startAutomaticCapture();
basePilotable.setDefaultCommand(new RunCommand(() -> { basePilotable.setDefaultCommand(new RunCommand(() -> {
basePilotable.drive(-manette1.getLeftY(), manette1.getLeftX()); basePilotable.drive(-manette1.getLeftY(), -manette1.getLeftX());
})); }, basePilotable));
} }
private void configureBindings() { private void configureBindings() {
// manette 1 // manette 1
@ -115,18 +118,21 @@ public RobotContainer() {
manette1.x().toggleOnTrue(Commands.startEnd(basePilotable::BrakeFerme,basePilotable::BrakeOuvre,basePilotable)); manette1.x().toggleOnTrue(Commands.startEnd(basePilotable::BrakeFerme,basePilotable::BrakeOuvre,basePilotable));
manette1.leftBumper().toggleOnTrue(aprilTag); manette1.leftBumper().toggleOnTrue(aprilTag);
manette1.rightBumper().toggleOnTrue(tape); manette1.rightBumper().toggleOnTrue(tape);
manette1.povUp().onTrue(pivoteBrasHaut); manette1.povUp().whileTrue(pivoteBrasHaut);
manette1.povDown().onTrue(pivoteBrasBas); manette1.povDown().whileTrue(pivoteBrasBas);
manette1.povRight().onTrue(pivoteBrasMilieux); manette1.povRight().whileTrue(pivoteBrasMilieux);
manette1.povLeft().onTrue(pivotBrasRentre); manette1.povLeft().whileTrue(pivotBrasRentre);
//manette 2 //manette 2
manette2.povRight().onTrue(pivotChercheBas); manette2.povDown().onTrue(pivotChercheBas);
manette2.povLeft().onTrue(pivotChercheHaut); manette2.povUp().onTrue(pivotChercheHaut);
manette2.rightBumper().toggleOnTrue(cube); manette2.rightBumper().toggleOnTrue(cube);
manette2.leftBumper().toggleOnTrue(cone); manette2.leftBumper().toggleOnTrue(cone);
manette2.y().whileTrue(gyro); manette2.y().whileTrue(gyro);
manette2.start().onTrue(new InstantCommand(basePilotable::resetGyro)); manette2.start().onTrue(new InstantCommand(basePilotable::resetGyro));
manette2.b().onTrue(Commands.either(gratteBaisser, gratteMonte, gratte::getenHaut)); manette2.a().whileTrue(gratteMonte);
manette2.b().whileTrue(gratteBaisser);
manette2.leftStick().whileTrue(brasManuel);
manette2.rightStick().whileTrue(pivotManuel);
} }
public Command getAutonomousCommand() { public Command getAutonomousCommand() {

View File

@ -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.commands; package frc.robot.commands;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj2.command.CommandBase; import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.subsystems.Gratte; import frc.robot.subsystems.Gratte;
@ -26,16 +27,16 @@ public class GratteBaisser extends CommandBase {
@Override @Override
public void execute() { public void execute() {
if(gratte.basd()){ if(gratte.basd()){
gratte.baiser(0); gratte.baiserd(0);
} }
else{ else{
gratte.baiser(0.5); gratte.baiserd(0.5);
} }
if(gratte.basg()){ if(gratte.basg()){
gratte.baiser(0); gratte.baiserg(0);
} }
else{ else{
gratte.baiser(0.5); gratte.baiserg(0.5);
} }
@ -43,7 +44,10 @@ public class GratteBaisser extends CommandBase {
// 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) {
gratte.baiserd(0);
gratte.baiserg(0);
}
// Returns true when the command should end. // Returns true when the command should end.
@Override @Override

View File

@ -5,6 +5,7 @@
package frc.robot.commands; package frc.robot.commands;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj2.command.CommandBase; import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.subsystems.Gratte; import frc.robot.subsystems.Gratte;
@ -27,22 +28,25 @@ public class GratteMonte extends CommandBase {
@Override @Override
public void execute() { public void execute() {
if(gratte.hautd()){ if(gratte.hautd()){
gratte.Lever(0.5); gratte.Leverd(0);
} }
else{ else{
gratte.Lever(0.5); gratte.Leverd(0.5);
} }
if(gratte.hautg()) { if(gratte.hautg()) {
gratte.Lever(0.5); gratte.Leverg(0);
} }
else{ else{
gratte.Lever(0.5); gratte.Leverg(0.5);
} }
} }
// 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) {
gratte.Leverd(0);
gratte.Leverg(0);
}
// Returns true when the command should end. // Returns true when the command should end.
@Override @Override

View File

@ -10,12 +10,9 @@ import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.subsystems.BasePilotable; import frc.robot.subsystems.BasePilotable;
public class Gyro extends CommandBase { public class Gyro extends CommandBase {
ShuffleboardTab teb = Shuffleboard.getTab("teb");
private BasePilotable basePilotable; private BasePilotable basePilotable;
/** Creates a new Gyro. */ /** Creates a new Gyro. */
public Gyro(BasePilotable basePilotable) { public Gyro(BasePilotable basePilotable) {
teb.add("angleGyro", 0.1);
teb.add("vitesseGyro", 0.1);
this.basePilotable = basePilotable; this.basePilotable = basePilotable;
// Use addRequirements() here to declare subsystem dependencies. // Use addRequirements() here to declare subsystem dependencies.
addRequirements(basePilotable); addRequirements(basePilotable);
@ -28,18 +25,13 @@ public class Gyro extends CommandBase {
// 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(basePilotable.getpitch()>10) if(basePilotable.getpitch()>6)
{ {
basePilotable.drive(0.3*basePilotable.getpitch()/12, 0); basePilotable.drive(0.3*basePilotable.getpitch()/12, 0);
} }
else if(basePilotable.getpitch()<-10) else if(basePilotable.getpitch()<-6)
{ {
basePilotable.drive(0.3*basePilotable.getpitch()/12, 0); basePilotable.drive(0.3*basePilotable.getpitch()/12, 0);
basePilotable.drive(0.3*basePilotable.getpitch()/15, 0);
}
else if(basePilotable.getpitch()<-4)
{
basePilotable.drive(0.3*basePilotable.getpitch()/15, 0);
} }
else else
{ {

View File

@ -0,0 +1,37 @@
// 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;
public class BrasManuel extends CommandBase {
private BrasTelescopique brasTelescopique;
/** Creates a new BrasManuel. */
public BrasManuel(BrasTelescopique brasTelescopique) {
this.brasTelescopique = brasTelescopique;
// 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() {
brasTelescopique.AvanceRecule(0.3);
}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {}
// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}

View File

@ -22,38 +22,37 @@ public class PivotBrasRentre extends CommandBase {
// 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.distance()>1){ if(brasTelescopique.photocell()){
brasTelescopique.AvanceRecule(0.5); brasTelescopique.ouvrir();
brasTelescopique.fermer();
}
if (pivot.distance()>1){
pivot.monteDescendre(0.5);
}
else if(brasTelescopique.photocell()){
brasTelescopique.Reset(); brasTelescopique.Reset();
brasTelescopique.AvanceRecule(0); brasTelescopique.AvanceRecule(0);
brasTelescopique.ouvrir();
} }
else{ else{
brasTelescopique.AvanceRecule(0.5); brasTelescopique.AvanceRecule(0.5);
} }
if(pivot.limitpivot()){ if(pivot.limitpivot()){
pivot.Reset(); pivot.Reset();
pivot.monteDescendre(0); pivot.monteDescendre(0);
} }
else{ else{
pivot.monteDescendre(0.5); pivot.monteDescendre(-0.3);
} }
} }
// 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);
brasTelescopique.ouvrir();
}
// Returns true when the command should end. // Returns true when the command should end.
@Override @Override

View File

@ -22,27 +22,29 @@ public class PivotChercheBas extends CommandBase {
// 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.distance()<10){ if(brasTelescopique.distance()>-17.5){
brasTelescopique.AvanceRecule(0.5); brasTelescopique.AvanceRecule(-0.2);
brasTelescopique.fermer(); brasTelescopique.fermer();
} }
else if(brasTelescopique.distance()>11) { else if(brasTelescopique.distance()<-19.5) {
brasTelescopique.AvanceRecule(-0.5); brasTelescopique.AvanceRecule(0.2);
} }
else { else {
brasTelescopique.AvanceRecule(0); brasTelescopique.AvanceRecule(0);
brasTelescopique.ouvrir(); brasTelescopique.ouvrir();
} }
if (pivot.distance()<10){ if (pivot.distance()<8.5){
pivot.monteDescendre(0.5); pivot.monteDescendre(0.3);
} }
else if(pivot.distance()>11) { else if(pivot.distance()>10.5) {
pivot.monteDescendre(-0.5); pivot.monteDescendre(-0.3);
} }
else{ else{
pivot.monteDescendre(0); pivot.monteDescendre(0);
@ -51,7 +53,11 @@ public class PivotChercheBas extends CommandBase {
// 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);
brasTelescopique.fermer();
}
// Returns true when the command should end. // Returns true when the command should end.
@Override @Override

View File

@ -22,27 +22,26 @@ public class PivotChercheHaut extends CommandBase {
// 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.distance()<10){ if(brasTelescopique.photocell()){
brasTelescopique.AvanceRecule(0.5);
brasTelescopique.fermer();
}
else if(brasTelescopique.distance()>11) {
brasTelescopique.AvanceRecule(-0.5);
}
else {
brasTelescopique.AvanceRecule(0);
brasTelescopique.ouvrir(); brasTelescopique.ouvrir();
brasTelescopique.Reset();
brasTelescopique.AvanceRecule(0);
}
else{
brasTelescopique.AvanceRecule(0.3);
} }
if (pivot.distance()<10){ if (pivot.distance()<43.5){
pivot.monteDescendre(0.5); pivot.monteDescendre(0.4);
} }
else if(pivot.distance()>11) { else if(pivot.distance()>44.5) {
pivot.monteDescendre(-0.5); pivot.monteDescendre(-0.4);
} }
else{ else{
pivot.monteDescendre(0); pivot.monteDescendre(0);
@ -51,7 +50,11 @@ public class PivotChercheHaut extends CommandBase {
// 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);
brasTelescopique.ouvrir();
}
// Returns true when the command should end. // Returns true when the command should end.
@Override @Override

View File

@ -0,0 +1,38 @@
// 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.Pivot;
public class PivotManuel extends CommandBase {
private Pivot pivot;
/** Creates a new PivotManuel. */
public PivotManuel(Pivot pivot) {
this.pivot = pivot;
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(pivot);
}
// 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() {
pivot.monteDescendre(0.3);
}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {}
// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}

View File

@ -24,27 +24,29 @@ public class PivoteBrasBas extends CommandBase {
// 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.distance()<10){ if(brasTelescopique.distance()>-13.5){
brasTelescopique.AvanceRecule(0.5); brasTelescopique.AvanceRecule(-0.2);
brasTelescopique.fermer(); brasTelescopique.fermer();
} }
else if(brasTelescopique.distance()>11) { else if(brasTelescopique.distance()<-15.5) {
brasTelescopique.AvanceRecule(-0.5); brasTelescopique.AvanceRecule(0.2);
} }
else { else {
brasTelescopique.AvanceRecule(0); brasTelescopique.AvanceRecule(0);
brasTelescopique.ouvrir(); brasTelescopique.ouvrir();
} }
if (pivot.distance()<10){ if (pivot.distance()<8.5){
pivot.monteDescendre(0.5); pivot.monteDescendre(0.3);
} }
else if(pivot.distance()>11) { else if(pivot.distance()>10.5) {
pivot.monteDescendre(-0.5); pivot.monteDescendre(-0.3);
} }
else{ else{
pivot.monteDescendre(0); pivot.monteDescendre(0);
@ -55,7 +57,11 @@ public class PivoteBrasBas extends CommandBase {
// 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);
brasTelescopique.ouvrir();
}
// Returns true when the command should end. // Returns true when the command should end.
@Override @Override
public boolean isFinished() { public boolean isFinished() {

View File

@ -22,27 +22,29 @@ public class PivoteBrasHaut extends CommandBase {
// 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.distance()<10){ if(brasTelescopique.distance()>-39.5){
brasTelescopique.AvanceRecule(0.5); brasTelescopique.AvanceRecule(-0.15);
brasTelescopique.fermer(); brasTelescopique.fermer();
} }
else if(brasTelescopique.distance()>11) { else if(brasTelescopique.distance()<41.5) {
brasTelescopique.AvanceRecule(-0.5); brasTelescopique.AvanceRecule(-0.15);
} }
else { else {
brasTelescopique.AvanceRecule(0); brasTelescopique.AvanceRecule(0);
brasTelescopique.ouvrir(); brasTelescopique.ouvrir();
} }
if (pivot.distance()<10){ if (pivot.distance()<50.5){
pivot.monteDescendre(0.5); pivot.monteDescendre(0.4);
} }
else if(pivot.distance()>11) { else if(pivot.distance()>52.5) {
pivot.monteDescendre(-0.5); pivot.monteDescendre(-0.4);
} }
else{ else{
pivot.monteDescendre(0); pivot.monteDescendre(0);
@ -51,7 +53,11 @@ public class PivoteBrasHaut extends CommandBase {
// 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);
brasTelescopique.ouvrir();
}
// Returns true when the command should end. // Returns true when the command should end.
@Override @Override

View File

@ -22,27 +22,29 @@ public class PivoteBrasMilieux extends CommandBase {
// 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.distance()<10){ if(brasTelescopique.distance()>-16.5){
brasTelescopique.AvanceRecule(0.5); brasTelescopique.AvanceRecule(-0.2);
brasTelescopique.fermer(); brasTelescopique.fermer();
} }
else if(brasTelescopique.distance()>11) { else if(brasTelescopique.distance()<-17.5) {
brasTelescopique.AvanceRecule(-0.5); brasTelescopique.AvanceRecule(0.2);
} }
else { else {
brasTelescopique.AvanceRecule(0); brasTelescopique.AvanceRecule(0);
brasTelescopique.ouvrir(); brasTelescopique.ouvrir();
} }
if (pivot.distance()<10){ if (pivot.distance()<43.5){
pivot.monteDescendre(0.5); pivot.monteDescendre(0.4);
} }
else if(pivot.distance()>11) { else if(pivot.distance()>44.5) {
pivot.monteDescendre(-0.5); pivot.monteDescendre(-0.4);
} }
else{ else{
pivot.monteDescendre(0); pivot.monteDescendre(0);
@ -52,7 +54,11 @@ public class PivoteBrasMilieux extends CommandBase {
// 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);
brasTelescopique.ouvrir();
}
// Returns true when the command should end. // Returns true when the command should end.
@Override @Override

View File

@ -13,9 +13,7 @@ import edu.wpi.first.wpilibj.PneumaticsModuleType;
import edu.wpi.first.wpilibj.DoubleSolenoid.Value; import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup; import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants; import frc.robot.Constants;
@ -30,23 +28,21 @@ public class BasePilotable extends SubsystemBase {
final DifferentialDrive drive = new DifferentialDrive(gauche, droit); final DifferentialDrive drive = new DifferentialDrive(gauche, droit);
//piston //piston
private DoubleSolenoid brakedroit = new DoubleSolenoid(PneumaticsModuleType.CTREPCM,Constants.brakedroit, Constants.brakedroit); private DoubleSolenoid brake = new DoubleSolenoid(PneumaticsModuleType.CTREPCM,Constants.brakeouvre, Constants.brakeferme);
private DoubleSolenoid brakegauche = new DoubleSolenoid(PneumaticsModuleType.CTREPCM,Constants.brakegauche, Constants.brakegauche);
//gyro //gyro
ShuffleboardTab teb = Shuffleboard.getTab("teb"); ShuffleboardTab teb = Shuffleboard.getTab("teb");
ShuffleboardLayout layout = Shuffleboard.getTab("teb")
.getLayout ("encodeurs base pilotable", BuiltInLayouts.kList) double pitchoffset = 0;
.withSize(2, 2);
private AHRS gyroscope = new AHRS();public double getangle() {return gyroscope.getAngle();} private AHRS gyroscope = new AHRS();
public double getpitch() { public double getpitch() {
return gyroscope.getPitch(); return -gyroscope.getPitch() + pitchoffset;
} }
public void drive(double xSpeed, double zRotation){ public void drive(double xSpeed, double zRotation){
drive.arcadeDrive(xSpeed, zRotation); drive.arcadeDrive(xSpeed, zRotation);
} }
public double distance(){ public double distance(){
teb .add ("distance",0.1);
return (-avantdroit.getEncoder().getPosition() return (-avantdroit.getEncoder().getPosition()
+avantgauche.getEncoder().getPosition() +avantgauche.getEncoder().getPosition()
-arrieredroit.getEncoder().getPosition() -arrieredroit.getEncoder().getPosition()
@ -59,21 +55,21 @@ public class BasePilotable extends SubsystemBase {
arrieregauche.getEncoder().setPosition(0); arrieregauche.getEncoder().setPosition(0);
} }
public void resetGyro(){ public void resetGyro(){
{gyroscope.reset(); pitchoffset = gyroscope.getPitch();
}
} }
public void BrakeOuvre(){ public void BrakeOuvre(){
brakedroit.set(Value.kForward); brake.set(Value.kForward);
brakegauche.set(Value.kForward);
} }
public void BrakeFerme(){ public void BrakeFerme(){
brakedroit.set(Value.kReverse); brake.set(Value.kReverse);
brakegauche.set(Value.kReverse);
} }
/** Creates a new BasePilotable. */ /** Creates a new BasePilotable. */
public BasePilotable() { public BasePilotable() {
droit.setInverted(true); droit.setInverted(true);
teb.add(drive);
teb.addDouble("distancerobot",this::distance);
teb.addDouble("angle gyro", this::getpitch);
} }
@Override @Override

View File

@ -18,8 +18,8 @@ ShuffleboardTab teb = Shuffleboard.getTab("teb");
ShuffleboardLayout limitswitchgratte = Shuffleboard.getTab("teb") ShuffleboardLayout limitswitchgratte = Shuffleboard.getTab("teb")
.getLayout("limitswitchsgratte", BuiltInLayouts.kList) .getLayout("limitswitchsgratte", BuiltInLayouts.kList)
.withSize(2, 2); .withSize(2, 2);
private WPI_TalonSRX Gratted = new WPI_TalonSRX(Constants.leverGratte); private WPI_TalonSRX Gratted = new WPI_TalonSRX(Constants.GratteD);
private WPI_TalonSRX Gratteg = new WPI_TalonSRX(Constants.baiserGratte); private WPI_TalonSRX Gratteg = new WPI_TalonSRX(Constants.GratteG);
private DigitalInput limithd = new DigitalInput(Constants.limithd); private DigitalInput limithd = new DigitalInput(Constants.limithd);
private DigitalInput limithg = new DigitalInput(Constants.limithg); private DigitalInput limithg = new DigitalInput(Constants.limithg);
private DigitalInput limitbd = new DigitalInput(Constants.limitbd); private DigitalInput limitbd = new DigitalInput(Constants.limitbd);
@ -50,19 +50,25 @@ ShuffleboardLayout limitswitchgratte = Shuffleboard.getTab("teb")
} }
public Gratte() { public Gratte() {
limitswitchgratte.add ("limitbd", 0.1); limitswitchgratte.addBoolean ("limitbd", this::basd);
limitswitchgratte.add ("limithg", 0.1); limitswitchgratte.addBoolean ("limithg", this::hautg);
limitswitchgratte.add ("limithd", 0.1); limitswitchgratte.addBoolean ("limithd", this::hautd);
limitswitchgratte.add ("limitbg", 0.1); limitswitchgratte.addBoolean ("limitbg", this::basg);
} }
public void Lever(double vitesse){ public void Leverd(double vitesse){
Gratted.set(vitesse);
Gratteg.set(vitesse);
}
public void baiser(double vitesse){
Gratted.set(-vitesse); Gratted.set(-vitesse);
}
public void Leverg(double vitesse){
Gratteg.set(-vitesse); Gratteg.set(-vitesse);
} }
public void baiserd(double vitesse){
Gratted.set(vitesse);
}
public void baiserg(double vitesse){
Gratteg.set(vitesse);
}
@Override @Override
public void periodic(){ public void periodic(){
} }

View File

@ -5,8 +5,7 @@
package frc.robot.subsystems; package frc.robot.subsystems;
import edu.wpi.first.cameraserver.CameraServer; import edu.wpi.first.cameraserver.CameraServer;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import org.photonvision.PhotonCamera; import org.photonvision.PhotonCamera;
import org.photonvision.common.hardware.VisionLEDMode; import org.photonvision.common.hardware.VisionLEDMode;
@ -17,12 +16,11 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase;
public class Limelight extends SubsystemBase { public class Limelight extends SubsystemBase {
ShuffleboardTab teb = Shuffleboard.getTab("teb");
PhotonCamera limelight = new PhotonCamera("limelight"); PhotonCamera limelight = new PhotonCamera("limelight");
/** Creates a new Limelight. */ /** Creates a new Limelight. */
public Limelight() { public Limelight() {
CameraServer.startAutomaticCapture(); CameraServer.startAutomaticCapture();
teb .add("limelight", 0.1);
PortForwarder.add(5800, "photonvision.local", 5800); PortForwarder.add(5800, "photonvision.local", 5800);
} }

View File

@ -15,24 +15,18 @@ import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts; import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout; import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants; import frc.robot.Constants;
public class BrasTelescopique extends SubsystemBase { public class BrasTelescopique extends SubsystemBase {
ShuffleboardLayout layout = Shuffleboard.getTab("teb") ShuffleboardLayout layout = Shuffleboard.getTab("teb")
.getLayout("layout", BuiltInLayouts.kList) .getLayout("bras", BuiltInLayouts.kList)
.withSize(2, 2); .withSize(2, 2);
ShuffleboardLayout bras = Shuffleboard.getTab("teb")
.getLayout("bras", BuiltInLayouts.kList)
.withSize(2, 2);
ShuffleboardTab teb = Shuffleboard.getTab("teb");
/** Creates a new BrasTelescopique. */ /** Creates a new BrasTelescopique. */
public BrasTelescopique() { public BrasTelescopique() {
teb .add("photocell",0.1); layout .addBoolean("photocell",this::photocell);
teb .add("winch",0.1); layout .addDouble("encodeur",this::distance);
teb .add("encodeur",0.1);
} }
final CANSparkMax Winch = new CANSparkMax(Constants.BrasTelescopique,MotorType.kBrushless); final CANSparkMax Winch = new CANSparkMax(Constants.BrasTelescopique,MotorType.kBrushless);
private DigitalInput photocell = new DigitalInput(Constants.photocell); private DigitalInput photocell = new DigitalInput(Constants.photocell);

View File

@ -38,7 +38,7 @@ public class Pivot extends SubsystemBase {
} }
public boolean limitpivot(){ public boolean limitpivot(){
return limitpivot.get(); return !limitpivot.get();
} }
@Override @Override
public void periodic() { public void periodic() {