dashboard acc
This commit is contained in:
		| @@ -30,7 +30,7 @@ public class Balayer extends Command { | |||||||
|   } |   } | ||||||
|   else{ |   else{ | ||||||
|     balayeuse.balaye(0.6); |     balayeuse.balaye(0.6); | ||||||
|     accumulateur.Accumuler(0.6); |     accumulateur.Accumuler(); | ||||||
|   } |   } | ||||||
| } | } | ||||||
|  |  | ||||||
|   | |||||||
| @@ -6,6 +6,7 @@ package frc.robot.subsystem; | |||||||
|  |  | ||||||
| import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; | import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; | ||||||
|  |  | ||||||
|  | import edu.wpi.first.networktables.GenericEntry; | ||||||
| import edu.wpi.first.wpilibj.DigitalInput; | import edu.wpi.first.wpilibj.DigitalInput; | ||||||
| import edu.wpi.first.wpilibj2.command.SubsystemBase; | import edu.wpi.first.wpilibj2.command.SubsystemBase; | ||||||
| import frc.robot.Constants; | import frc.robot.Constants; | ||||||
| @@ -18,6 +19,9 @@ public class Accumulateur extends SubsystemBase { | |||||||
|   /** Creates a new Accumulateur. */ |   /** Creates a new Accumulateur. */ | ||||||
|   |   | ||||||
|   ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard"); |   ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard"); | ||||||
|  |    private GenericEntry vitesse = | ||||||
|  |       dashboard.add("vitesseacc", 1) | ||||||
|  |          .getEntry();  | ||||||
|   final WPI_TalonSRX Moteuracc2 = new WPI_TalonSRX(Constants.Moteuracc2); |   final WPI_TalonSRX Moteuracc2 = new WPI_TalonSRX(Constants.Moteuracc2); | ||||||
|   final WPI_TalonSRX Moteuracc = new WPI_TalonSRX(Constants.Moteuracc); |   final WPI_TalonSRX Moteuracc = new WPI_TalonSRX(Constants.Moteuracc); | ||||||
|   final DigitalInput limitacc = new DigitalInput(Constants.limitacc); |   final DigitalInput limitacc = new DigitalInput(Constants.limitacc); | ||||||
| @@ -33,12 +37,16 @@ public class Accumulateur extends SubsystemBase { | |||||||
|     return limitacc.get(); |     return limitacc.get(); | ||||||
|   } |   } | ||||||
|   public Accumulateur() { |   public Accumulateur() { | ||||||
|  |      | ||||||
|     dashboard.addBoolean("limitacc", this::limitswitch); |     dashboard.addBoolean("limitacc", this::limitswitch); | ||||||
|   } |   } | ||||||
|   public void Accumuler(double vitesse){ |   public void Accumuler(double vitesse){ | ||||||
|     Moteuracc.set(vitesse); |     Moteuracc.set(vitesse); | ||||||
|     Moteuracc2.set(vitesse); |     Moteuracc2.set(vitesse); | ||||||
|   } |   } | ||||||
|  |   public void Accumuler(){ | ||||||
|  |     Accumuler(vitesse.getDouble(0.1)); | ||||||
|  |   } | ||||||
|  |  | ||||||
|   @Override |   @Override | ||||||
|   public void periodic() { |   public void periodic() { | ||||||
|   | |||||||
		Reference in New Issue
	
	Block a user