This commit is contained in:
samuel desharnais
2026-04-07 19:53:33 -04:00

View File

@@ -4,6 +4,8 @@
package frc.robot.subsystems;
import com.revrobotics.PersistMode;
import com.revrobotics.ResetMode;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.config.SparkMaxConfig;
import com.revrobotics.spark.SparkLowLevel.MotorType;
@@ -18,12 +20,15 @@ public class Grimpeur extends SubsystemBase {
ShuffleboardTab teb = Shuffleboard.getTab("teb");
SparkMax grimpeur1 = new SparkMax(3,MotorType.kBrushless);
SparkMax grimpeur2 = new SparkMax(12,MotorType.kBrushless);
SparkMaxConfig slaveConfig = new SparkMaxConfig();
DigitalInput limit = new DigitalInput(0);
private GenericEntry EncodeurGrimpeur =
teb.add("Position haut grimpeur", 100).getEntry();
public void GrimperDroit(double vitesse){
grimpeur2.set(vitesse);
public void Grimper(double vitesse){
grimpeur1.configure(slaveConfig, ResetMode.kNoResetSafeParameters, PersistMode.kPersistParameters);
grimpeur2.configure(slaveConfig.follow(grimpeur1), ResetMode.kNoResetSafeParameters, PersistMode.kPersistParameters);
grimpeur1.set(vitesse);
}
public void GrimperGauche(double vitesse){
grimpeur1.set(vitesse);