code fini
This commit is contained in:
@@ -24,7 +24,7 @@ public class DescendreBalyeuse extends Command {
|
|||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void execute() {
|
public void execute() {
|
||||||
if(balayeuse.Distance() < 10){
|
if(balayeuse.Distance() < balayeuse.EncodeurBalayeuse()){
|
||||||
balayeuse.Pivoter(-0.2);
|
balayeuse.Pivoter(-0.2);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -61,7 +61,7 @@ public class Lancer extends Command {
|
|||||||
else{
|
else{
|
||||||
balayeuse.Reset();
|
balayeuse.Reset();
|
||||||
balayeuse.Pivoter(0);
|
balayeuse.Pivoter(0);
|
||||||
double vitesse = (100-limeLight3G.getTA())/100;
|
double vitesse = (100-limeLight3G.getTA())/lanceur.Vitesse();
|
||||||
double output = pidController.calculate(lanceur.Vitesse(),vitesse);
|
double output = pidController.calculate(lanceur.Vitesse(),vitesse);
|
||||||
lanceur.Lancer(output);
|
lanceur.Lancer(output);
|
||||||
if(lanceur.Vitesse() >= vitesse){
|
if(lanceur.Vitesse() >= vitesse){
|
||||||
|
|||||||
@@ -23,7 +23,7 @@ public class MonterGrimpeur extends Command {
|
|||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void execute() {
|
public void execute() {
|
||||||
if(grimpeur.Position() < 10){
|
if(grimpeur.Position() < grimpeur.PositionFinal()){
|
||||||
grimpeur.Grimper(0.5);
|
grimpeur.Grimper(0.5);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -8,16 +8,22 @@ import com.revrobotics.spark.SparkFlex;
|
|||||||
import com.revrobotics.spark.SparkMax;
|
import com.revrobotics.spark.SparkMax;
|
||||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||||
|
|
||||||
|
import edu.wpi.first.networktables.GenericEntry;
|
||||||
import edu.wpi.first.units.measure.Time;
|
import edu.wpi.first.units.measure.Time;
|
||||||
import edu.wpi.first.wpilibj.DigitalInput;
|
import edu.wpi.first.wpilibj.DigitalInput;
|
||||||
import edu.wpi.first.wpilibj.Timer;
|
import edu.wpi.first.wpilibj.Timer;
|
||||||
|
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||||
|
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||||
|
|
||||||
public class Balayeuse extends SubsystemBase {
|
public class Balayeuse extends SubsystemBase {
|
||||||
|
ShuffleboardTab teb = Shuffleboard.getTab("teb");
|
||||||
SparkFlex Balaye1 = new SparkFlex(5, MotorType.kBrushless);
|
SparkFlex Balaye1 = new SparkFlex(5, MotorType.kBrushless);
|
||||||
SparkFlex Balaye2 = new SparkFlex(5, MotorType.kBrushless);
|
SparkFlex Balaye2 = new SparkFlex(6, MotorType.kBrushless);
|
||||||
SparkMax Pivot = new SparkMax(6, MotorType.kBrushless);
|
SparkMax Pivot = new SparkMax(7, MotorType.kBrushless);
|
||||||
DigitalInput limit = new DigitalInput(0);
|
DigitalInput limit = new DigitalInput(0);
|
||||||
|
private GenericEntry EncodeurBalayeuse =
|
||||||
|
teb.add("Position bas balayeuse", 10).getEntry();
|
||||||
public void Balayer(double vitesse){
|
public void Balayer(double vitesse){
|
||||||
Balaye1.set(vitesse);
|
Balaye1.set(vitesse);
|
||||||
Balaye2.set(vitesse);
|
Balaye2.set(vitesse);
|
||||||
@@ -40,10 +46,15 @@ public class Balayeuse extends SubsystemBase {
|
|||||||
public void Temps(){
|
public void Temps(){
|
||||||
Timer timer = new Timer();
|
Timer timer = new Timer();
|
||||||
timer.start();
|
timer.start();
|
||||||
|
}
|
||||||
|
public double EncodeurBalayeuse(){
|
||||||
|
return EncodeurBalayeuse.getDouble(10);
|
||||||
}
|
}
|
||||||
/** Creates a new Balayeuse. */
|
/** Creates a new Balayeuse. */
|
||||||
public Balayeuse() {}
|
public Balayeuse() {
|
||||||
|
teb.addBoolean("limit balayeuse", this::GetLimiSwtich);
|
||||||
|
teb.addDouble("encodeur balayeuse", this::Distance);
|
||||||
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void periodic() {
|
public void periodic() {
|
||||||
|
|||||||
@@ -7,18 +7,24 @@ package frc.robot.subsystems;
|
|||||||
import com.revrobotics.spark.SparkMax;
|
import com.revrobotics.spark.SparkMax;
|
||||||
import com.revrobotics.spark.config.SparkMaxConfig;
|
import com.revrobotics.spark.config.SparkMaxConfig;
|
||||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||||
|
|
||||||
|
import edu.wpi.first.networktables.GenericEntry;
|
||||||
import edu.wpi.first.wpilibj.DigitalInput;
|
import edu.wpi.first.wpilibj.DigitalInput;
|
||||||
|
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||||
|
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||||
|
|
||||||
public class Grimpeur extends SubsystemBase {
|
public class Grimpeur extends SubsystemBase {
|
||||||
|
ShuffleboardTab teb = Shuffleboard.getTab("teb");
|
||||||
SparkMax grimpeur1 = new SparkMax(8,MotorType.kBrushless);
|
SparkMax grimpeur1 = new SparkMax(8,MotorType.kBrushless);
|
||||||
SparkMax grimpeur2 = new SparkMax(9,MotorType.kBrushless);
|
SparkMax grimpeur2 = new SparkMax(9,MotorType.kBrushless);
|
||||||
SparkMaxConfig slaveConfig = new SparkMaxConfig();
|
SparkMaxConfig slaveConfig = new SparkMaxConfig();
|
||||||
DigitalInput limit = new DigitalInput(1);
|
DigitalInput limit = new DigitalInput(1);
|
||||||
|
private GenericEntry EncodeurGrimpeur =
|
||||||
|
teb.add("Position haut grimpeur", 10).getEntry();
|
||||||
public void Grimper(double vitesse){
|
public void Grimper(double vitesse){
|
||||||
grimpeur1.set(vitesse);
|
grimpeur1.set(vitesse);
|
||||||
grimpeur2.set(vitesse);
|
grimpeur2.set(vitesse);
|
||||||
|
|
||||||
}
|
}
|
||||||
public double Position(){
|
public double Position(){
|
||||||
return grimpeur1.getEncoder().getPosition();
|
return grimpeur1.getEncoder().getPosition();
|
||||||
@@ -29,8 +35,14 @@ public class Grimpeur extends SubsystemBase {
|
|||||||
public boolean Limit(){
|
public boolean Limit(){
|
||||||
return limit.get();
|
return limit.get();
|
||||||
}
|
}
|
||||||
|
public double PositionFinal(){
|
||||||
|
return EncodeurGrimpeur.getDouble(10);
|
||||||
|
}
|
||||||
/** Creates a new Grimpeur. */
|
/** Creates a new Grimpeur. */
|
||||||
public Grimpeur() {}
|
public Grimpeur() {
|
||||||
|
teb.addDouble("encodeur grimpeur", this::Position);
|
||||||
|
teb.addBoolean("limit grimpeur", this::Limit);
|
||||||
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void periodic() {
|
public void periodic() {
|
||||||
|
|||||||
@@ -7,27 +7,37 @@ package frc.robot.subsystems;
|
|||||||
import com.revrobotics.spark.SparkFlex;
|
import com.revrobotics.spark.SparkFlex;
|
||||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||||
|
|
||||||
|
import edu.wpi.first.networktables.GenericEntry;
|
||||||
|
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||||
|
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||||
|
|
||||||
public class Lanceur extends SubsystemBase {
|
public class Lanceur extends SubsystemBase {
|
||||||
SparkFlex moteur1 = new SparkFlex(2, MotorType.kBrushless);
|
ShuffleboardTab teb = Shuffleboard.getTab("teb");
|
||||||
SparkFlex moteur2 = new SparkFlex(3, MotorType.kBrushless);
|
SparkFlex moteur1 = new SparkFlex(2, MotorType.kBrushless);
|
||||||
SparkFlex Demeleur = new SparkFlex(4, MotorType.kBrushless);
|
SparkFlex moteur2 = new SparkFlex(3, MotorType.kBrushless);
|
||||||
public void Lancer(double vitesse){
|
SparkFlex Demeleur = new SparkFlex(4, MotorType.kBrushless);
|
||||||
moteur1.set(vitesse);
|
GenericEntry vitesse =
|
||||||
moteur2.set(-vitesse);
|
teb.add("vitesse lanceur",100).getEntry();
|
||||||
}
|
public void Lancer(double vitesse){
|
||||||
public void Demeler(double vitesse){
|
moteur1.set(vitesse);
|
||||||
Demeleur.set(vitesse);
|
moteur2.set(-vitesse);
|
||||||
}
|
}
|
||||||
public double Vitesse(){
|
public void Demeler(double vitesse){
|
||||||
return moteur1.getEncoder().getVelocity();
|
Demeleur.set(vitesse);
|
||||||
}
|
}
|
||||||
public double Amp(){
|
public double Vitesse(){
|
||||||
return moteur1.getOutputCurrent();
|
return moteur1.getEncoder().getVelocity();
|
||||||
}
|
}
|
||||||
|
public double Amp(){
|
||||||
|
return moteur1.getOutputCurrent();
|
||||||
|
}
|
||||||
|
public double vitesseDemander(){
|
||||||
|
return vitesse.getDouble(100);
|
||||||
|
}
|
||||||
/** Creates a new Lanceur. */
|
/** Creates a new Lanceur. */
|
||||||
public Lanceur() {
|
public Lanceur() {
|
||||||
|
teb.addDouble("amperage lanceur", this::Amp);
|
||||||
}
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
|
|||||||
@@ -9,10 +9,17 @@ import java.util.Optional;
|
|||||||
import com.ctre.phoenix.led.CANdle;
|
import com.ctre.phoenix.led.CANdle;
|
||||||
import com.ctre.phoenix.led.RainbowAnimation;
|
import com.ctre.phoenix.led.RainbowAnimation;
|
||||||
|
|
||||||
|
import edu.wpi.first.networktables.GenericEntry;
|
||||||
import edu.wpi.first.wpilibj.DriverStation;
|
import edu.wpi.first.wpilibj.DriverStation;
|
||||||
|
import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
|
||||||
|
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||||
|
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||||
|
|
||||||
public class Led extends SubsystemBase {
|
public class Led extends SubsystemBase {
|
||||||
|
ShuffleboardTab teb = Shuffleboard.getTab("teb");
|
||||||
|
private GenericEntry equipe =
|
||||||
|
teb.add("equipe commence (bleu = ouvert, rouge = fermé)", true).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
||||||
CANdle CANDle = new CANdle(7);
|
CANdle CANDle = new CANdle(7);
|
||||||
RainbowAnimation rainbowAnim = new RainbowAnimation();
|
RainbowAnimation rainbowAnim = new RainbowAnimation();
|
||||||
public void bleu(){
|
public void bleu(){
|
||||||
@@ -78,13 +85,7 @@ public class Led extends SubsystemBase {
|
|||||||
CANDle.animate(null);
|
CANDle.animate(null);
|
||||||
}
|
}
|
||||||
public boolean Equipe(){
|
public boolean Equipe(){
|
||||||
Optional<DriverStation.Alliance> alliance = DriverStation.getAlliance();
|
return equipe.getBoolean(true);
|
||||||
if(alliance.get() == DriverStation.Alliance.Blue){
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
else{
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
/** Creates a new Led. */
|
/** Creates a new Led. */
|
||||||
public Led() {}
|
public Led() {}
|
||||||
|
|||||||
Reference in New Issue
Block a user