This commit is contained in:
EdwardFaucher
2023-03-13 18:47:31 -04:00
parent de5b5213cb
commit 6ba1dfbb2c
19 changed files with 256 additions and 156 deletions

View File

@@ -13,9 +13,7 @@ import edu.wpi.first.wpilibj.PneumaticsModuleType;
import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
@@ -30,23 +28,21 @@ public class BasePilotable extends SubsystemBase {
final DifferentialDrive drive = new DifferentialDrive(gauche, droit);
//piston
private DoubleSolenoid brakedroit = new DoubleSolenoid(PneumaticsModuleType.CTREPCM,Constants.brakedroit, Constants.brakedroit);
private DoubleSolenoid brakegauche = new DoubleSolenoid(PneumaticsModuleType.CTREPCM,Constants.brakegauche, Constants.brakegauche);
private DoubleSolenoid brake = new DoubleSolenoid(PneumaticsModuleType.CTREPCM,Constants.brakeouvre, Constants.brakeferme);
//gyro
ShuffleboardTab teb = Shuffleboard.getTab("teb");
ShuffleboardLayout layout = Shuffleboard.getTab("teb")
.getLayout ("encodeurs base pilotable", BuiltInLayouts.kList)
.withSize(2, 2);
private AHRS gyroscope = new AHRS();public double getangle() {return gyroscope.getAngle();}
double pitchoffset = 0;
private AHRS gyroscope = new AHRS();
public double getpitch() {
return gyroscope.getPitch();
return -gyroscope.getPitch() + pitchoffset;
}
public void drive(double xSpeed, double zRotation){
drive.arcadeDrive(xSpeed, zRotation);
}
public double distance(){
teb .add ("distance",0.1);
return (-avantdroit.getEncoder().getPosition()
+avantgauche.getEncoder().getPosition()
-arrieredroit.getEncoder().getPosition()
@@ -59,21 +55,21 @@ public class BasePilotable extends SubsystemBase {
arrieregauche.getEncoder().setPosition(0);
}
public void resetGyro(){
{gyroscope.reset();
}
pitchoffset = gyroscope.getPitch();
}
public void BrakeOuvre(){
brakedroit.set(Value.kForward);
brakegauche.set(Value.kForward);
brake.set(Value.kForward);
}
public void BrakeFerme(){
brakedroit.set(Value.kReverse);
brakegauche.set(Value.kReverse);
brake.set(Value.kReverse);
}
/** Creates a new BasePilotable. */
public BasePilotable() {
droit.setInverted(true);
teb.add(drive);
teb.addDouble("distancerobot",this::distance);
teb.addDouble("angle gyro", this::getpitch);
}
@Override