Merge branch 'main' of https://demerso.net/pls5618/2023/robot
This commit is contained in:
commit
7c8f6b19a9
@ -11,7 +11,9 @@ public class Constants {
|
||||
// pneumatique
|
||||
public static int pistonpinceouvre = 0;
|
||||
public static int pistonpinceferme = 1;
|
||||
public static int actuateur = 4;
|
||||
public static int actuateur = 2;
|
||||
public static int brakedroit = 3;
|
||||
public static int brakegauche = 4;
|
||||
// DIO
|
||||
public static int limitbd = 0;
|
||||
public static int limitbg = 2;
|
||||
|
@ -6,6 +6,9 @@ package frc.robot.subsystems;
|
||||
|
||||
import com.revrobotics.CANSparkMax;
|
||||
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
|
||||
|
||||
import edu.wpi.first.wpilibj.DoubleSolenoid;
|
||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
@ -16,7 +19,8 @@ public class BasePilotable extends SubsystemBase {
|
||||
final CANSparkMax avantgauche = new CANSparkMax(Constants.avantgauche, MotorType.kBrushless);
|
||||
final CANSparkMax arrieredroit = new CANSparkMax(Constants.arrieredroit, MotorType.kBrushless);
|
||||
final CANSparkMax arrieregauche = new CANSparkMax(Constants.arrieregauche, MotorType.kBrushless);
|
||||
|
||||
private DoubleSolenoid brakedroit = new DoubleSolenoid(PneumaticsModuleType.CTREPCM,Constants.pistonpinceouvre, Constants.pistonpinceferme);
|
||||
private DoubleSolenoid brakegauche = new DoubleSolenoid(PneumaticsModuleType.CTREPCM,Constants.pistonpinceouvre, Constants.pistonpinceferme);
|
||||
final MotorControllerGroup droit = new MotorControllerGroup(avantdroit, arrieredroit);
|
||||
final MotorControllerGroup gauche = new MotorControllerGroup(avantgauche, arrieregauche);
|
||||
|
||||
|
Loading…
x
Reference in New Issue
Block a user