Compare commits
2 Commits
954c82a7a0
...
910caa963e
Author | SHA1 | Date | |
---|---|---|---|
910caa963e | |||
bf63394d77 |
@ -22,7 +22,8 @@ public class Desaccumuler extends Command {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
accumulateur.desaccumule(0.1);
|
||||
if(accumulateur.photocell()){accumulateur.desaccumule(0.1);}
|
||||
|
||||
}
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
|
@ -12,9 +12,8 @@ import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
|
||||
public class Accumulateur extends SubsystemBase {
|
||||
|
||||
/** Creates a new Accumulateur. */
|
||||
public Accumulateur() {dashboard.addBoolean("photocellacc", this::limitswitch)
|
||||
.withSize(1, 1)
|
||||
.withPosition(0, 1);
|
||||
public Accumulateur() {dashboard.addBoolean("photocellacc", this::photocell).withSize(1, 1).withPosition(0, 1);
|
||||
|
||||
}
|
||||
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
|
||||
|
||||
@ -29,8 +28,8 @@ public class Accumulateur extends SubsystemBase {
|
||||
final DigitalInput photocell = new DigitalInput(94);
|
||||
public void encodeur(){
|
||||
}
|
||||
public boolean limitswitch(){
|
||||
return !photocell.get();
|
||||
public boolean photocell(){
|
||||
return photocell.get();
|
||||
}
|
||||
public void desaccumule(double vitesse){
|
||||
accumulateur1.set(vitesse);
|
||||
|
@ -30,6 +30,11 @@ public class Lanceur extends SubsystemBase {
|
||||
.withSize(0,0)
|
||||
.withPosition(1, 4)
|
||||
.getEntry();
|
||||
private GenericEntry rotation =
|
||||
dashboard.add("rottourel", 0.2)
|
||||
.withSize(0,0)
|
||||
.withPosition(1, 5)
|
||||
.getEntry();
|
||||
public void encodeur(double distance){
|
||||
lanceur1.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative);
|
||||
lanceur2.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative);
|
||||
@ -40,7 +45,7 @@ public class Lanceur extends SubsystemBase {
|
||||
lanceur2.setInverted(true);
|
||||
}
|
||||
public void lance(double vitesse){
|
||||
lanceur1.set(vitesse);
|
||||
lanceur1.set(vitesse);lanceur2.set(vitesse);
|
||||
}
|
||||
public void lance(){
|
||||
lance(vitesse.getDouble(0.2));
|
||||
@ -48,6 +53,9 @@ public class Lanceur extends SubsystemBase {
|
||||
public void tourelRotation(double x, double y, double rotation){
|
||||
tourelle.set(rotation);
|
||||
}
|
||||
public void tourelRotation(){
|
||||
tourelle.set(rotation.getDouble(0.1));
|
||||
}
|
||||
public double vitessetourel(){
|
||||
return(tourelle.getEncoder().getVelocity());
|
||||
}
|
||||
|
@ -6,11 +6,20 @@ package frc.robot.Subsystems;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.net.PortForwarder;
|
||||
import edu.wpi.first.networktables.GenericEntry;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
|
||||
public class Limelight3G extends SubsystemBase {
|
||||
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
|
||||
private GenericEntry orientation =
|
||||
dashboard.add("orientation tourel", 0.1)
|
||||
.withSize(0, 0)
|
||||
.withPosition(2, 4)
|
||||
.getEntry();
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight");
|
||||
NetworkTableEntry tx = table.getEntry("tx");
|
||||
NetworkTableEntry ty = table.getEntry("ty");
|
||||
|
Loading…
x
Reference in New Issue
Block a user