This commit is contained in:
EdwardFaucher 2024-10-30 19:41:45 -04:00
commit 0e4efef6ee
9 changed files with 1434 additions and 16 deletions

File diff suppressed because one or more lines are too long

View File

@ -19,7 +19,7 @@ public class Desaccumuler extends Command {
// Called when the command is initially scheduled.
@Override
public void initialize() {
accumulateur.resetencodeur();
}
// Called every time the scheduler runs while the command is scheduled.

View File

@ -0,0 +1,55 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc.robot.Commands;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.Subsystems.Drive;
import frc.robot.Subsystems.Lanceur;
import frc.robot.Subsystems.Limelight3G;
public class FollowAprilTag extends Command {
private Limelight3G enlignement;
private Lanceur lanceur;
/** Creates a new Limelight3g. */
public FollowAprilTag(Limelight3G enlignement, Lanceur lanceur) {
// Use addRequirements() here to declare subsystem dependencies.
this.lanceur = lanceur;
this.enlignement = enlignement;
addRequirements(lanceur, enlignement);
}
// Called when the command is initially scheduled.
@Override
public void initialize() {}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if (enlignement.getv()==1)
{
lanceur.tourelRotation(0,0, enlignement.getx()/30);
}
else
{
lanceur.tourelRotation(0, 0, 0);
}
}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
lanceur.tourelRotation(0, 0, 0);
}
// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}

View File

@ -19,7 +19,7 @@ public class Lancer extends Command {
// Called when the command is initially scheduled.
@Override
public void initialize() {
lanceur.setPID(0, 0, 0);
lanceur.PIDlanceur(0, 0, 0);
}
// Called every time the scheduler runs while the command is scheduled.

File diff suppressed because it is too large Load Diff

View File

@ -4,11 +4,20 @@
package frc.robot;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
public class RobotContainer {
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
public RobotContainer() {
dashboard.addCamera("limelight3G", "limelight3G","limelight.local:5800")
.withSize(3,4)
.withPosition(0,0);
dashboard.addCamera("limelight3", "limelight3","limelight.local:5800")
.withSize(3,4)
.withPosition(3,0);
configureBindings();
}

View File

@ -4,23 +4,47 @@
package frc.robot.Subsystems;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.networktables.GenericEntry;
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 com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
public class Accumulateur extends SubsystemBase {
/** Creates a new Accumulateur. */
public Accumulateur() {}
public Accumulateur() {dashboard.addBoolean("photocellacc", this::limitswitch)
.withSize(1, 1)
.withPosition(0, 1);
}
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
private GenericEntry vitesse =
dashboard.add("vitesseacc", 0.1)
.withSize(1, 1)
.withPosition(0, 4)
.getEntry();
final WPI_TalonSRX accumulateur1 = new WPI_TalonSRX(0);
final WPI_TalonSRX accumulateur2 = new WPI_TalonSRX(10);
Encoder encoder = new Encoder(1,0);
public void resetencodeur(){
encoder.reset();
final DigitalInput photocell = new DigitalInput(94);
public void encodeur(){
}
public boolean limitswitch(){
return !photocell.get();
}
public void desaccumule(double vitesse){
accumulateur1.set(vitesse);
accumulateur2.set(-vitesse);
}
public void desaccumule(){
desaccumule(vitesse.getDouble(0.9));
}
@Override
public void periodic() {
// This method will be called once per scheduler run

View File

@ -6,11 +6,13 @@ package frc.robot.Subsystems;
import com.ctre.phoenix.motorcontrol.FeedbackDevice;
import com.ctre.phoenix.motorcontrol.StatusFrameEnhanced;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkLowLevel.MotorType;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
@ -20,19 +22,30 @@ public class Lanceur extends SubsystemBase {
final WPI_TalonSRX lanceur1 = new WPI_TalonSRX(0);
final WPI_TalonSRX lanceur2 = new WPI_TalonSRX(1);
final CANSparkMax tourel = new CANSparkMax(2, MotorType.kBrushed);
Encoder encoder = new Encoder(0, 1);
final CANSparkMax tourelle = new CANSparkMax(2, MotorType.kBrushed);
public void encodeur(double distance){
encoder.setDistancePerPulse(distance);
lanceur1.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative);
lanceur2.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative);
lanceur1.setStatusFramePeriod(StatusFrameEnhanced.Status_2_Feedback0, 1);
}
public void masterslave(){
lanceur2.follow(lanceur1);
lanceur2.setInverted(true);
}
public void lance(double vitesse){
lanceur1.set(vitesse);
lanceur2.set(-vitesse);
}
public void tourelRotation(double vitesse){
tourel.set(vitesse);
public void tourelRotation(double x, double y, double rotation){
tourelle.set(rotation);
}
public void setPID(double p, double i, int d) {
public double distancetourel(){
return(tourelle.getEncoder().getPosition());
}
public void PIDlanceur(double p, double i, double d) {
lanceur1.config_kP(0, p);
lanceur1.config_kI(0, i);
lanceur1.config_kD(0, d);
}
@Override
public void periodic() {

View File

@ -0,0 +1,48 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc.robot.Subsystems;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.net.PortForwarder;
import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableEntry;
import edu.wpi.first.networktables.NetworkTableInstance;
public class Limelight3G extends SubsystemBase {
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight");
NetworkTableEntry tx = table.getEntry("tx");
NetworkTableEntry ty = table.getEntry("ty");
NetworkTableEntry pipeline = table.getEntry("pipeline");
NetworkTableEntry tv = table.getEntry("tv");
NetworkTableEntry camMode = table.getEntry("camMode");
NetworkTableEntry tid = table.getEntry("tid");
/** Creates a new Limelight. */
public Limelight3G() {
for (int port = 5800; port <= 5807; port++) {
PortForwarder.add(port, "limelight.local", port);
}}
public double getx(){
return tx.getDouble(0);
}
public double gety(){
return ty.getDouble(0);
}
public double getv(){
return tv.getDouble(0);
}
public void setpipeline(){
pipeline.setNumber(0);
}
public void setcamMode(){
camMode.setNumber(0);
}
public double getTid(){
return tid.getDouble(0);
}
@Override
public void periodic() {
// This method will be called once per scheduler run
}
}