Merge branch 'main' of https://git.demerso.net/pls5618/2024/robot
This commit is contained in:
commit
500c1a0c81
@ -3,7 +3,7 @@
|
|||||||
"front": -12.375,
|
"front": -12.375,
|
||||||
"left": 12.375
|
"left": 12.375
|
||||||
},
|
},
|
||||||
"absoluteEncoderOffset": 0.416259765625,
|
"absoluteEncoderOffset":209.443,
|
||||||
"drive": {
|
"drive": {
|
||||||
"type": "sparkmax",
|
"type": "sparkmax",
|
||||||
"id": 8,
|
"id": 8,
|
||||||
|
@ -3,7 +3,7 @@
|
|||||||
"front": -12.375,
|
"front": -12.375,
|
||||||
"left": -12.375
|
"left": -12.375
|
||||||
},
|
},
|
||||||
"absoluteEncoderOffset": -0.023193359375,
|
"absoluteEncoderOffset": 5.537,
|
||||||
"drive": {
|
"drive": {
|
||||||
"type": "sparkmax",
|
"type": "sparkmax",
|
||||||
"id": 11,
|
"id": 11,
|
||||||
|
@ -3,7 +3,7 @@
|
|||||||
"front": 12.375,
|
"front": 12.375,
|
||||||
"left": 12.375
|
"left": 12.375
|
||||||
},
|
},
|
||||||
"absoluteEncoderOffset": 0.2744140625,
|
"absoluteEncoderOffset":258.223 ,
|
||||||
"drive": {
|
"drive": {
|
||||||
"type": "sparkmax",
|
"type": "sparkmax",
|
||||||
"id": 2,
|
"id": 2,
|
||||||
|
@ -3,7 +3,7 @@
|
|||||||
"front": 12.375,
|
"front": 12.375,
|
||||||
"left": -12.375
|
"left": -12.375
|
||||||
},
|
},
|
||||||
"absoluteEncoderOffset": -0.297119140625,
|
"absoluteEncoderOffset": 110.215,
|
||||||
"drive": {
|
"drive": {
|
||||||
"type": "sparkmax",
|
"type": "sparkmax",
|
||||||
"id": 18,
|
"id": 18,
|
||||||
|
@ -30,9 +30,8 @@ import frc.robot.command.LancerNote;
|
|||||||
import frc.robot.command.LancerTrape;
|
import frc.robot.command.LancerTrape;
|
||||||
import frc.robot.command.Lancerampli;
|
import frc.robot.command.Lancerampli;
|
||||||
import frc.robot.command.Limelight_tracker;
|
import frc.robot.command.Limelight_tracker;
|
||||||
import frc.robot.command.PistonFerme;
|
|
||||||
import frc.robot.command.PistonOuvre;
|
|
||||||
import frc.robot.command.RestGyro;
|
import frc.robot.command.RestGyro;
|
||||||
|
import frc.robot.command.Debalayer;
|
||||||
// Subsystems
|
// Subsystems
|
||||||
import frc.robot.subsystem.Accumulateur;
|
import frc.robot.subsystem.Accumulateur;
|
||||||
import frc.robot.subsystem.Balayeuse;
|
import frc.robot.subsystem.Balayeuse;
|
||||||
@ -59,7 +58,6 @@ public class RobotContainer {
|
|||||||
CommandXboxController manette = new CommandXboxController(1);
|
CommandXboxController manette = new CommandXboxController(1);
|
||||||
|
|
||||||
//command
|
//command
|
||||||
PistonFerme pistonFerme = new PistonFerme(grimpeur);
|
|
||||||
Balayer balayer = new Balayer(balayeuse, accumulateur);
|
Balayer balayer = new Balayer(balayeuse, accumulateur);
|
||||||
GuiderHaut guiderHaut = new GuiderHaut(guideur);
|
GuiderHaut guiderHaut = new GuiderHaut(guideur);
|
||||||
GuiderBas guiderBas = new GuiderBas(guideur);
|
GuiderBas guiderBas = new GuiderBas(guideur);
|
||||||
@ -68,6 +66,8 @@ public class RobotContainer {
|
|||||||
Lancerampli lancerampli = new Lancerampli(lanceur,limelight);
|
Lancerampli lancerampli = new Lancerampli(lanceur,limelight);
|
||||||
GrimpeurDroit grimpeurDroit = new GrimpeurDroit(grimpeur, manette::getLeftY);
|
GrimpeurDroit grimpeurDroit = new GrimpeurDroit(grimpeur, manette::getLeftY);
|
||||||
GrimpeurGauche grimpeurGauche = new GrimpeurGauche(grimpeur, manette::getRightY);
|
GrimpeurGauche grimpeurGauche = new GrimpeurGauche(grimpeur, manette::getRightY);
|
||||||
|
Debalayer debalayer = new Debalayer(balayeuse, accumulateur);
|
||||||
|
|
||||||
public RobotContainer() {
|
public RobotContainer() {
|
||||||
|
|
||||||
dashboard.addCamera("limelight", "limelight","limelight.local:5800")
|
dashboard.addCamera("limelight", "limelight","limelight.local:5800")
|
||||||
@ -82,13 +82,14 @@ public class RobotContainer {
|
|||||||
|
|
||||||
NamedCommands.registerCommand("balayer",new Balayer(balayeuse, accumulateur));
|
NamedCommands.registerCommand("balayer",new Balayer(balayeuse, accumulateur));
|
||||||
NamedCommands.registerCommand("lancer", new LancerNote(lanceur, accumulateur));
|
NamedCommands.registerCommand("lancer", new LancerNote(lanceur, accumulateur));
|
||||||
NamedCommands.registerCommand("piston", new PistonFerme(grimpeur));
|
|
||||||
autoChooser = AutoBuilder.buildAutoChooser();
|
autoChooser = AutoBuilder.buildAutoChooser();
|
||||||
|
|
||||||
|
//manette
|
||||||
|
manette.start().whileTrue(new RestGyro(drive));
|
||||||
manette.a().whileTrue(new GuiderBas(guideur));
|
manette.a().whileTrue(new GuiderBas(guideur));
|
||||||
manette.b().whileTrue(new GuiderHaut(guideur));
|
manette.b().whileTrue(new GuiderHaut(guideur));
|
||||||
manette.x().whileTrue(new PistonFerme(grimpeur));
|
|
||||||
manette.y().whileTrue(new PistonOuvre(grimpeur));
|
//joystick
|
||||||
joystick.button(3).whileTrue(new Balayer(balayeuse, accumulateur));
|
joystick.button(3).whileTrue(new Balayer(balayeuse, accumulateur));
|
||||||
joystick.button(1).whileTrue(new LancerNote(lanceur, accumulateur));
|
joystick.button(1).whileTrue(new LancerNote(lanceur, accumulateur));
|
||||||
joystick.button(5).whileTrue(new LancerAmp(lanceur, accumulateur));
|
joystick.button(5).whileTrue(new LancerAmp(lanceur, accumulateur));
|
||||||
@ -96,11 +97,12 @@ public class RobotContainer {
|
|||||||
joystick.button(2).whileTrue(new ParallelCommandGroup(new Lancerampli(lanceur,limelight),new Limelight_tracker(limelight,drive)));
|
joystick.button(2).whileTrue(new ParallelCommandGroup(new Lancerampli(lanceur,limelight),new Limelight_tracker(limelight,drive)));
|
||||||
joystick.button(6).whileTrue(new LancerTrape(lanceur, accumulateur));
|
joystick.button(6).whileTrue(new LancerTrape(lanceur, accumulateur));
|
||||||
joystick.button(7).whileTrue(new Limelight_tracker(limelight, drive));
|
joystick.button(7).whileTrue(new Limelight_tracker(limelight, drive));
|
||||||
manette.start().whileTrue(new RestGyro(drive));
|
joystick.button(8).whileTrue(new Debalayer(balayeuse, accumulateur));
|
||||||
|
|
||||||
// deplacement
|
// deplacement
|
||||||
configureBindings();
|
configureBindings();
|
||||||
drive.setDefaultCommand(new RunCommand(()->{
|
drive.setDefaultCommand(new RunCommand(()->{
|
||||||
drive.drive(MathUtil.applyDeadband(joystick.getY(),0.2), MathUtil.applyDeadband(joystick.getX(),0.2), MathUtil.applyDeadband(joystick.getZ(), 0.2));
|
drive.drive(MathUtil.applyDeadband(joystick.getY(),0.2), MathUtil.applyDeadband(joystick.getX(),0.2), MathUtil.applyDeadband(joystick.getZ(), 0.35));
|
||||||
},drive));
|
},drive));
|
||||||
|
|
||||||
// grimpeur manuel
|
// grimpeur manuel
|
||||||
|
@ -29,7 +29,7 @@ public class Balayer extends Command {
|
|||||||
accumulateur.Accumuler(0);
|
accumulateur.Accumuler(0);
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
balayeuse.balaye(0.3);
|
balayeuse.balaye(0.55);
|
||||||
accumulateur.Accumuler();
|
accumulateur.Accumuler();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -36,7 +36,6 @@ public class GrimpeurDroit extends Command {
|
|||||||
@Override
|
@Override
|
||||||
public void end(boolean interrupted) {
|
public void end(boolean interrupted) {
|
||||||
grimpeur.droit(0);
|
grimpeur.droit(0);
|
||||||
grimpeur.pistonouvre();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
||||||
|
@ -27,7 +27,7 @@ public class GuiderBas extends Command {
|
|||||||
guideur.guider(0);
|
guideur.guider(0);
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
guideur.guider(0.5);
|
guideur.guider(0.6);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -27,7 +27,7 @@ public class GuiderHaut extends Command {
|
|||||||
guideur.guider(0);
|
guideur.guider(0);
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
guideur.guider(-0.4);
|
guideur.guider(-0.6);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -27,7 +27,7 @@ public class LancerAmp extends Command {
|
|||||||
// 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() {
|
||||||
double vitesse = 0.15;
|
double vitesse = 0.3;
|
||||||
lancer.lanceramp();
|
lancer.lanceramp();
|
||||||
if(lancer.vitesse(vitesse)>vitesse){
|
if(lancer.vitesse(vitesse)>vitesse){
|
||||||
accumulateur.Accumuler();
|
accumulateur.Accumuler();
|
||||||
|
@ -1,40 +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.command;
|
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
|
||||||
import frc.robot.subsystem.Grimpeur;
|
|
||||||
|
|
||||||
public class PistonFerme extends Command {
|
|
||||||
private Grimpeur grimpeur;
|
|
||||||
/** Creates a new PistonFerme. */
|
|
||||||
public PistonFerme(Grimpeur grimpeur) {
|
|
||||||
this.grimpeur = grimpeur;
|
|
||||||
addRequirements(grimpeur);
|
|
||||||
// Use addRequirements() here to declare subsystem dependencies.
|
|
||||||
}
|
|
||||||
|
|
||||||
// Called when the command is initially scheduled.
|
|
||||||
@Override
|
|
||||||
public void initialize() {
|
|
||||||
grimpeur.pistonouvre();
|
|
||||||
}
|
|
||||||
|
|
||||||
// Called every time the scheduler runs while the command is scheduled.
|
|
||||||
@Override
|
|
||||||
public void execute() {}
|
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
|
||||||
@Override
|
|
||||||
public void end(boolean interrupted) {
|
|
||||||
grimpeur.pistonferme();
|
|
||||||
}
|
|
||||||
|
|
||||||
// Returns true when the command should end.
|
|
||||||
@Override
|
|
||||||
public boolean isFinished() {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
@ -1,40 +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.command;
|
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
|
||||||
import frc.robot.subsystem.Grimpeur;
|
|
||||||
|
|
||||||
public class PistonOuvre extends Command {
|
|
||||||
private Grimpeur grimpeur;
|
|
||||||
/** Creates a new PistonFerme. */
|
|
||||||
public PistonOuvre(Grimpeur grimpeur) {
|
|
||||||
this.grimpeur = grimpeur;
|
|
||||||
addRequirements(grimpeur);
|
|
||||||
// Use addRequirements() here to declare subsystem dependencies.
|
|
||||||
}
|
|
||||||
|
|
||||||
// Called when the command is initially scheduled.
|
|
||||||
@Override
|
|
||||||
public void initialize() {
|
|
||||||
grimpeur.pistonferme();
|
|
||||||
}
|
|
||||||
|
|
||||||
// Called every time the scheduler runs while the command is scheduled.
|
|
||||||
@Override
|
|
||||||
public void execute() {}
|
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
|
||||||
@Override
|
|
||||||
public void end(boolean interrupted) {
|
|
||||||
grimpeur.pistonouvre();
|
|
||||||
}
|
|
||||||
|
|
||||||
// Returns true when the command should end.
|
|
||||||
@Override
|
|
||||||
public boolean isFinished() {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
@ -18,13 +18,13 @@ public class RestGyro extends Command {
|
|||||||
|
|
||||||
// Called when the command is initially scheduled.
|
// Called when the command is initially scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void initialize() {}
|
public void initialize() {
|
||||||
|
drive.restgyroscope();
|
||||||
|
}
|
||||||
|
|
||||||
// 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() {}
|
||||||
drive.restgyroscope();
|
|
||||||
}
|
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
// Called once the command ends or is interrupted.
|
||||||
@Override
|
@Override
|
||||||
|
@ -18,7 +18,7 @@ public class Accumulateur extends SubsystemBase {
|
|||||||
|
|
||||||
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
|
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
|
||||||
private GenericEntry vitesse =
|
private GenericEntry vitesse =
|
||||||
dashboard.add("vitesseacc", 0.5)
|
dashboard.add("vitesseacc", 0.7)
|
||||||
.withSize(1, 1)
|
.withSize(1, 1)
|
||||||
.withPosition(0, 0)
|
.withPosition(0, 0)
|
||||||
.getEntry();
|
.getEntry();
|
||||||
@ -41,7 +41,7 @@ public class Accumulateur extends SubsystemBase {
|
|||||||
Moteuracc2.set(-vitesse);
|
Moteuracc2.set(-vitesse);
|
||||||
}
|
}
|
||||||
public void Accumuler(){
|
public void Accumuler(){
|
||||||
Accumuler(vitesse.getDouble(0.5));
|
Accumuler(vitesse.getDouble(0.7));
|
||||||
}
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
|
@ -4,7 +4,6 @@
|
|||||||
|
|
||||||
package frc.robot.subsystem;
|
package frc.robot.subsystem;
|
||||||
|
|
||||||
import com.kauailabs.navx.frc.AHRS;
|
|
||||||
import com.revrobotics.CANSparkMax;
|
import com.revrobotics.CANSparkMax;
|
||||||
import com.revrobotics.CANSparkLowLevel.MotorType;
|
import com.revrobotics.CANSparkLowLevel.MotorType;
|
||||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||||
@ -31,10 +30,8 @@ public class Grimpeur extends SubsystemBase {
|
|||||||
final Solenoid pistondroite= new Solenoid(PneumaticsModuleType.REVPH, Constants.pistondroite);
|
final Solenoid pistondroite= new Solenoid(PneumaticsModuleType.REVPH, Constants.pistondroite);
|
||||||
//fonction
|
//fonction
|
||||||
public Grimpeur() {
|
public Grimpeur() {
|
||||||
pistonouvre();
|
|
||||||
layout.addDouble("grimpeurencodeurd", this::encoderd);
|
layout.addDouble("grimpeurencodeurd", this::encoderd);
|
||||||
layout.addDouble("grimpeurencodeurg", this::encoderg);
|
layout.addDouble("grimpeurencodeurg", this::encoderg);
|
||||||
layout.addDouble("pitchgyrogrimpeur", this::getpitch);
|
|
||||||
}
|
}
|
||||||
public void droit(double vitesse){
|
public void droit(double vitesse){
|
||||||
grimpeurd.set(vitesse);
|
grimpeurd.set(vitesse);
|
||||||
@ -54,19 +51,6 @@ public double encoderd(){
|
|||||||
public double encoderg(){
|
public double encoderg(){
|
||||||
return grimpeurg.getEncoder().getPosition();
|
return grimpeurg.getEncoder().getPosition();
|
||||||
}
|
}
|
||||||
public AHRS gyroscope = new AHRS();
|
|
||||||
public double getpitch(){
|
|
||||||
return gyroscope.getPitch();
|
|
||||||
}
|
|
||||||
public void pistonferme(){
|
|
||||||
pistondroite.set(true);
|
|
||||||
}
|
|
||||||
public void pistonouvre(){
|
|
||||||
pistondroite.set(false);
|
|
||||||
}
|
|
||||||
public boolean piston(){
|
|
||||||
return pistondroite.get();
|
|
||||||
}
|
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void periodic() {
|
public void periodic() {
|
||||||
|
@ -31,7 +31,7 @@ public class Lanceur extends SubsystemBase {
|
|||||||
.withPosition(2,0)
|
.withPosition(2,0)
|
||||||
.getEntry();
|
.getEntry();
|
||||||
private GenericEntry vitesseamp =
|
private GenericEntry vitesseamp =
|
||||||
dashboard.add("vitesseamp", 0.15)
|
dashboard.add("vitesseamp", 0.3)
|
||||||
.withSize(1, 1)
|
.withSize(1, 1)
|
||||||
.withPosition(1,0)
|
.withPosition(1,0)
|
||||||
.getEntry();
|
.getEntry();
|
||||||
@ -90,7 +90,7 @@ public class Lanceur extends SubsystemBase {
|
|||||||
lancer(vitesse.getDouble(0.8));
|
lancer(vitesse.getDouble(0.8));
|
||||||
}
|
}
|
||||||
public void lanceramp(){
|
public void lanceramp(){
|
||||||
lancer(vitesseamp.getDouble(0.1));
|
lancer(vitesseamp.getDouble(0.3));
|
||||||
}
|
}
|
||||||
public double vitesse(double vitesse){
|
public double vitesse(double vitesse){
|
||||||
return lanceur3.getEncoder().getVelocity();
|
return lanceur3.getEncoder().getVelocity();
|
||||||
|
Loading…
x
Reference in New Issue
Block a user