Merge branch 'main' of https://git.demerso.net/pls5618/2024/robot
This commit is contained in:
commit
b4ef632169
@ -42,7 +42,7 @@ public class Constants {
|
|||||||
public static int ArriereDroit = 6;
|
public static int ArriereDroit = 6;
|
||||||
public static int ArriereGauche = 7;
|
public static int ArriereGauche = 7;
|
||||||
|
|
||||||
// Limit switsh
|
// Limit switch
|
||||||
public static int guideurhaut = 23;
|
public static int guideurhaut = 23;
|
||||||
public static int guideurbas = 24;
|
public static int guideurbas = 24;
|
||||||
public static int limitacc = 25;
|
public static int limitacc = 25;
|
||||||
@ -50,4 +50,9 @@ public class Constants {
|
|||||||
public static int limithaut = 28;
|
public static int limithaut = 28;
|
||||||
public static int limitbas = 29;
|
public static int limitbas = 29;
|
||||||
|
|
||||||
|
//piston
|
||||||
|
public static int pistondroiteouvre= 30;
|
||||||
|
public static int pistondroiteferme= 31;
|
||||||
|
public static int pistondgaucheouvre= 32;
|
||||||
|
public static int pistondgauchferme= 32;
|
||||||
}
|
}
|
||||||
|
48
src/main/java/frc/robot/command/Balayer.java
Normal file
48
src/main/java/frc/robot/command/Balayer.java
Normal file
@ -0,0 +1,48 @@
|
|||||||
|
// 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.Accumulateur;
|
||||||
|
import frc.robot.subsystem.Balayeuse;
|
||||||
|
|
||||||
|
public class Balayer extends Command {
|
||||||
|
private Balayeuse balayeuse;
|
||||||
|
private Accumulateur accumulateur;
|
||||||
|
/** Creates a new Balayer. */
|
||||||
|
public Balayer(Balayeuse balayeuse, Accumulateur accumulateur) {
|
||||||
|
this.balayeuse = balayeuse;
|
||||||
|
addRequirements(balayeuse, accumulateur);}
|
||||||
|
// 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() {
|
||||||
|
if(accumulateur.limitswitch()){
|
||||||
|
balayeuse.balaye(0);
|
||||||
|
accumulateur.Accumuler(0);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
balayeuse.balaye(0.6);
|
||||||
|
accumulateur.Accumuler(0.6);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Called once the command ends or is interrupted.
|
||||||
|
@Override
|
||||||
|
public void end(boolean interrupted) {
|
||||||
|
balayeuse.balaye(0);
|
||||||
|
accumulateur.Accumuler(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns true when the command should end.
|
||||||
|
@Override
|
||||||
|
public boolean isFinished() {
|
||||||
|
return accumulateur.limitswitch()==true;
|
||||||
|
}
|
||||||
|
}
|
40
src/main/java/frc/robot/command/Deaccumuler.java
Normal file
40
src/main/java/frc/robot/command/Deaccumuler.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.command;
|
||||||
|
|
||||||
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
|
import frc.robot.subsystem.Accumulateur;
|
||||||
|
|
||||||
|
public class Deaccumuler extends Command {
|
||||||
|
private Accumulateur accumulateur;
|
||||||
|
/** Creates a new Deaccumuler. */
|
||||||
|
public Deaccumuler(Accumulateur accumulateur) {
|
||||||
|
// Use addRequirements() here to declare subsystem dependencies.
|
||||||
|
this.accumulateur = accumulateur;
|
||||||
|
addRequirements(accumulateur);
|
||||||
|
}
|
||||||
|
|
||||||
|
// 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() {
|
||||||
|
accumulateur.Accumuler(0.5);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Called once the command ends or is interrupted.
|
||||||
|
@Override
|
||||||
|
public void end(boolean interrupted) {
|
||||||
|
accumulateur.Accumuler(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns true when the command should end.
|
||||||
|
@Override
|
||||||
|
public boolean isFinished() {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
42
src/main/java/frc/robot/command/Debalayer.java
Normal file
42
src/main/java/frc/robot/command/Debalayer.java
Normal file
@ -0,0 +1,42 @@
|
|||||||
|
// 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.Accumulateur;
|
||||||
|
import frc.robot.subsystem.Balayeuse;
|
||||||
|
|
||||||
|
public class Debalayer extends Command {
|
||||||
|
private Balayeuse balayeuse;
|
||||||
|
private Accumulateur accumulateur;
|
||||||
|
/** Creates a new Balayer. */
|
||||||
|
public Debalayer(Balayeuse balayeuse, Accumulateur accumulateur) {
|
||||||
|
this.balayeuse = balayeuse;
|
||||||
|
addRequirements(balayeuse, accumulateur);}
|
||||||
|
// 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() {
|
||||||
|
balayeuse.balaye(-0.6);
|
||||||
|
accumulateur.Accumuler(-0.6);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Called once the command ends or is interrupted.
|
||||||
|
@Override
|
||||||
|
public void end(boolean interrupted) {
|
||||||
|
balayeuse.balaye(0);
|
||||||
|
accumulateur.Accumuler(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns true when the command should end.
|
||||||
|
@Override
|
||||||
|
public boolean isFinished() {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
38
src/main/java/frc/robot/command/GrimpeurHaut.java
Normal file
38
src/main/java/frc/robot/command/GrimpeurHaut.java
Normal 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.command;
|
||||||
|
|
||||||
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
|
import frc.robot.subsystem.Grimpeur;
|
||||||
|
|
||||||
|
public class GrimpeurHaut extends Command {
|
||||||
|
private Grimpeur grimpeur;
|
||||||
|
/** Creates a new GrimpeurHaut. */
|
||||||
|
public GrimpeurHaut(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() {}
|
||||||
|
|
||||||
|
// 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) {}
|
||||||
|
|
||||||
|
// Returns true when the command should end.
|
||||||
|
@Override
|
||||||
|
public boolean isFinished() {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
@ -40,6 +40,6 @@ public class GuiderBas extends Command {
|
|||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
||||||
@Override
|
@Override
|
||||||
public boolean isFinished() {
|
public boolean isFinished() {
|
||||||
return false;
|
return guideur.bas()==true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -40,6 +40,6 @@ public class GuiderHaut extends Command {
|
|||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
||||||
@Override
|
@Override
|
||||||
public boolean isFinished() {
|
public boolean isFinished() {
|
||||||
return false;
|
return guideur.haut()==true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -12,16 +12,27 @@ import frc.robot.Constants;
|
|||||||
|
|
||||||
public class Accumulateur extends SubsystemBase {
|
public class Accumulateur extends SubsystemBase {
|
||||||
/** Creates a new Accumulateur. */
|
/** Creates a new Accumulateur. */
|
||||||
public Accumulateur() {}
|
|
||||||
|
|
||||||
final WPI_TalonSRX Moteuracc2 = new WPI_TalonSRX(Constants.Moteuracc2);
|
final WPI_TalonSRX Moteuracc2 = new WPI_TalonSRX(Constants.Moteuracc2);
|
||||||
final WPI_TalonSRX Moteuracc = new WPI_TalonSRX(Constants.Moteuracc);
|
final WPI_TalonSRX Moteuracc = new WPI_TalonSRX(Constants.Moteuracc);
|
||||||
final DigitalInput limitacc = new DigitalInput(Constants.limitacc);
|
final DigitalInput limitacc = new DigitalInput(Constants.limitacc);
|
||||||
final DigitalInput limitacc2 = new DigitalInput(Constants.limitacc2);
|
public void Deaccumuler(double vitesse){
|
||||||
public void Deaccumuler(double vitesse){Moteuracc2.set(vitesse);}
|
Moteuracc2.set(vitesse);
|
||||||
public void moteuraccfollow(){Moteuracc.follow(Moteuracc2); Moteuracc.setInverted(true);}
|
}
|
||||||
public boolean limitswitch1(){return limitacc.get();}
|
public void moteuraccfollow(){
|
||||||
public boolean limitswitch2(){return limitacc2.get();}
|
Moteuracc.follow(Moteuracc2);
|
||||||
|
Moteuracc.setInverted(true);
|
||||||
|
}
|
||||||
|
public boolean limitswitch(){
|
||||||
|
return limitacc.get();
|
||||||
|
}
|
||||||
|
public Accumulateur() {}
|
||||||
|
public void Accumuler(double vitesse){
|
||||||
|
Moteuracc.set(vitesse);
|
||||||
|
Moteuracc2.set(vitesse);
|
||||||
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void periodic() {
|
public void periodic() {
|
||||||
// This method will be called once per scheduler run
|
// This method will be called once per scheduler run
|
||||||
|
@ -15,9 +15,19 @@ public class Balayeuse extends SubsystemBase {
|
|||||||
|
|
||||||
public Balayeuse() {}
|
public Balayeuse() {}
|
||||||
final WPI_TalonSRX roue = new WPI_TalonSRX(Constants.roue);
|
final WPI_TalonSRX roue = new WPI_TalonSRX(Constants.roue);
|
||||||
final TalonSRX etoile = new TalonSRX(Constants.etoile);
|
final WPI_TalonSRX etoile = new WPI_TalonSRX(Constants.etoile);
|
||||||
public void Accumulation(double vitesse){roue.set(vitesse);}
|
|
||||||
public void balayeuse(){etoile.follow(roue); etoile.setInverted(true);}
|
public void Accumulation(double vitesse){
|
||||||
|
roue.set(vitesse);
|
||||||
|
}
|
||||||
|
public void balayeuse(){
|
||||||
|
etoile.follow(roue);
|
||||||
|
etoile.setInverted(true);
|
||||||
|
}
|
||||||
|
public void balaye(double vitesse){
|
||||||
|
roue.set(vitesse);
|
||||||
|
etoile.set(vitesse);
|
||||||
|
}
|
||||||
@Override
|
@Override
|
||||||
public void periodic() {
|
public void periodic() {
|
||||||
// This method will be called once per scheduler run
|
// This method will be called once per scheduler run
|
||||||
|
@ -9,6 +9,9 @@ import com.revrobotics.CANSparkMax;
|
|||||||
import com.revrobotics.CANSparkLowLevel.MotorType;
|
import com.revrobotics.CANSparkLowLevel.MotorType;
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj.DigitalInput;
|
import edu.wpi.first.wpilibj.DigitalInput;
|
||||||
|
import edu.wpi.first.wpilibj.DoubleSolenoid;
|
||||||
|
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||||
|
import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
|
||||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||||
import frc.robot.Constants;
|
import frc.robot.Constants;
|
||||||
|
|
||||||
@ -21,6 +24,8 @@ public class Grimpeur extends SubsystemBase {
|
|||||||
// limit switch
|
// limit switch
|
||||||
final DigitalInput limitdroite = new DigitalInput(Constants.limithaut);
|
final DigitalInput limitdroite = new DigitalInput(Constants.limithaut);
|
||||||
final DigitalInput limitgauche = new DigitalInput(Constants.limitbas);
|
final DigitalInput limitgauche = new DigitalInput(Constants.limitbas);
|
||||||
|
final DoubleSolenoid pistondroite= new DoubleSolenoid(PneumaticsModuleType.CTREPCM, Constants.pistondroiteouvre, Constants.pistondroiteouvre);
|
||||||
|
final DoubleSolenoid pistondgauche= new DoubleSolenoid(PneumaticsModuleType.CTREPCM, Constants.pistondgaucheouvre, Constants.pistondroiteouvre);
|
||||||
//fonction
|
//fonction
|
||||||
public void droit(double vitesse){
|
public void droit(double vitesse){
|
||||||
grimpeurd.set(vitesse);
|
grimpeurd.set(vitesse);
|
||||||
@ -40,10 +45,19 @@ public void resetencodeurd(){
|
|||||||
public void resetencodeurg(){
|
public void resetencodeurg(){
|
||||||
grimpeurg.getEncoder().setPosition(0);
|
grimpeurg.getEncoder().setPosition(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
public AHRS gyroscope = new AHRS();
|
public AHRS gyroscope = new AHRS();
|
||||||
public double getpitch(){
|
public double getpitch(){
|
||||||
return gyroscope.getPitch();
|
return gyroscope.getPitch();
|
||||||
}
|
}
|
||||||
|
public void pistonouvre(){
|
||||||
|
pistondroite.set(Value.kForward);
|
||||||
|
pistondgauche.set(Value.kForward);
|
||||||
|
}
|
||||||
|
public void pistonferme(){
|
||||||
|
pistondroite.set(Value.kReverse);
|
||||||
|
pistondgauche.set(Value.kReverse);
|
||||||
|
}
|
||||||
@Override
|
@Override
|
||||||
public void periodic() {
|
public void periodic() {
|
||||||
// This method will be called once per scheduler run
|
// This method will be called once per scheduler run
|
||||||
|
Loading…
x
Reference in New Issue
Block a user