Message constuctif
This commit is contained in:
parent
c2fbb7f553
commit
077494b9fd
@ -5,9 +5,17 @@ public class Constants {
|
|||||||
public static int avantgauche = 1;
|
public static int avantgauche = 1;
|
||||||
public static int arrieredroit = 2;
|
public static int arrieredroit = 2;
|
||||||
public static int arrieregauche = 3;
|
public static int arrieregauche = 3;
|
||||||
|
public static int leverGratte = 0;
|
||||||
|
public static int baisserGratte = 1;
|
||||||
// pneumatique
|
// pneumatique
|
||||||
public static int pistonpinceouvre = 0;
|
public static int pistonpinceouvre = 0;
|
||||||
public static int pistonpinceferme = 1;
|
public static int pistonpinceferme = 1;
|
||||||
|
// DIO
|
||||||
|
public static int limitbd = 0;
|
||||||
|
public static int limitbg = 2;
|
||||||
|
public static int limithd = 3;
|
||||||
|
public static int limithg = 1;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -4,12 +4,40 @@
|
|||||||
|
|
||||||
package frc.robot.subsystems;
|
package frc.robot.subsystems;
|
||||||
|
|
||||||
|
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
|
||||||
|
import com.fasterxml.jackson.annotation.JacksonInject.Value;
|
||||||
|
|
||||||
|
import edu.wpi.first.wpilibj.DigitalInput;
|
||||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||||
|
import frc.robot.Constants;
|
||||||
|
|
||||||
public class Gratte extends SubsystemBase {
|
public class Gratte extends SubsystemBase {
|
||||||
|
private WPI_TalonSRX baisserGratte = new WPI_TalonSRX(Constants.leverGratte);
|
||||||
|
private WPI_TalonSRX leverGratte = new WPI_TalonSRX(Constants.baisserGratte);
|
||||||
|
private DigitalInput limithd = new DigitalInput(Constants.limithd);
|
||||||
|
private DigitalInput limithg = new DigitalInput(Constants.limithg);
|
||||||
|
private DigitalInput limitbd = new DigitalInput(Constants.limitbd);
|
||||||
|
private DigitalInput limitbg = new DigitalInput(Constants.limitbg);
|
||||||
|
public boolean hautd(){
|
||||||
|
return limithd.get();
|
||||||
|
}
|
||||||
|
|
||||||
|
public boolean hautg(){
|
||||||
|
return limithg.get();
|
||||||
|
}
|
||||||
|
|
||||||
|
public boolean basd(){
|
||||||
|
return limitbd.get();
|
||||||
|
}
|
||||||
|
public boolean basg(){
|
||||||
|
return limitbg.get();
|
||||||
|
}
|
||||||
/** Creates a new Gratte. */
|
/** Creates a new Gratte. */
|
||||||
public Gratte() {}
|
public Gratte() {}
|
||||||
|
public void BaisserLever(double vitesse){
|
||||||
|
baisserGratte.set(vitesse);
|
||||||
|
leverGratte.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
|
||||||
|
Loading…
x
Reference in New Issue
Block a user