From 24ac20a097a59de8e21996738d8a4df14b2d4ed5 Mon Sep 17 00:00:00 2001 From: samuel desharnais Date: Mon, 22 Jan 2024 19:32:35 -0500 Subject: [PATCH] grimpeur --- src/main/java/frc/robot/Constants.java | 6 +-- .../java/frc/robot/subsystem/Grimpeur.java | 41 ++++++++++++++++++- 2 files changed, 41 insertions(+), 6 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 66aaf3b..2ee83c7 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -22,9 +22,7 @@ public class Constants { public static int guideurhaut = 10; public static int guideurbas = 11; public static int limitacc = 12; - public static int limitbasd =15; - public static int limitbasg =16; - public static int limithautd =17; - public static int limithautg =18; + public static int limitbas =15; + public static int limithaut =16; } diff --git a/src/main/java/frc/robot/subsystem/Grimpeur.java b/src/main/java/frc/robot/subsystem/Grimpeur.java index cff76db..b61e3c5 100644 --- a/src/main/java/frc/robot/subsystem/Grimpeur.java +++ b/src/main/java/frc/robot/subsystem/Grimpeur.java @@ -4,15 +4,52 @@ package frc.robot.subsystem; +import com.revrobotics.CANSparkMax; +import com.revrobotics.CANSparkLowLevel.MotorType; + +import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.Constants; public class Grimpeur extends SubsystemBase { /** Creates a new Acrocheur. */ + // moteur public Grimpeur() {} - final - + final CANSparkMax grimpeurd = new CANSparkMax(Constants.grimpeurd,MotorType.kBrushless); + final CANSparkMax grimpeurg = new CANSparkMax(Constants.grimpeurg,MotorType.kBrushless); + // limit switch + final DigitalInput limitdroite = new DigitalInput(Constants.limithaut); + final DigitalInput limitgauche = new DigitalInput(Constants.limitbas); + //fonction +public void droit(double vitesse){ + grimpeurd.set(vitesse); +} +public void gauche(double vitesse){ + grimpeurg.set(vitesse); +} +public boolean droite(){ + return limitdroite.get(); +} +public boolean gauche(){ + return limitgauche.get(); +} +public void resetencodeurd(){ + grimpeurd.getEncoder().setPosition(0); +} +public void resetencodeurg(){ + grimpeurg.getEncoder().setPosition(0); +} +public void grimpeur(){ + grimpeurg.follow(grimpeurd); +} @Override public void periodic() { // This method will be called once per scheduler run + if(droite()) { + resetencodeurd(); + } + if(gauche()) { + resetencodeurg(); + } } }