Merge branch 'main' of https://git.demerso.net/PLS5618/pratique-2025
This commit is contained in:
commit
910caa963e
File diff suppressed because one or more lines are too long
@ -3,7 +3,6 @@
|
||||
// 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.Accumulateur;
|
||||
|
||||
@ -15,26 +14,22 @@ public class Desaccumuler extends Command {
|
||||
addRequirements(accumulateur);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// 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(accumulateur.photocell()){accumulateur.desaccumule(0.1);}
|
||||
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
accumulateur.desaccumule(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
|
@ -3,9 +3,7 @@
|
||||
// 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;
|
||||
|
||||
@ -18,7 +16,6 @@ public class FollowAprilTag extends Command {
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
this.lanceur = lanceur;
|
||||
this.enlignement = enlignement;
|
||||
|
||||
addRequirements(lanceur, enlignement);
|
||||
}
|
||||
|
||||
@ -46,7 +43,6 @@ public class FollowAprilTag extends Command {
|
||||
public void end(boolean interrupted) {
|
||||
lanceur.tourelRotation(0, 0, 0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
|
@ -3,7 +3,6 @@
|
||||
// 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.Lanceur;
|
||||
|
||||
@ -15,25 +14,21 @@ public class Lancer extends Command {
|
||||
addRequirements(lanceur);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
lanceur.PIDlanceur(0, 0, 0);
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
lanceur.lance(0.5);
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
lanceur.lance(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
|
@ -16,14 +16,12 @@ import edu.wpi.first.math.geometry.Translation3d;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.math.geometry.Rotation3d;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
|
||||
import java.io.IOException;
|
||||
import java.net.HttpURLConnection;
|
||||
import java.net.MalformedURLException;
|
||||
import java.net.URL;
|
||||
import java.util.Map;
|
||||
import java.util.concurrent.CompletableFuture;
|
||||
|
||||
import com.fasterxml.jackson.annotation.JsonFormat;
|
||||
import com.fasterxml.jackson.annotation.JsonFormat.Shape;
|
||||
import com.fasterxml.jackson.annotation.JsonProperty;
|
||||
|
@ -8,8 +8,16 @@ 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;
|
||||
import frc.robot.Subsystems.Accumulateur;
|
||||
import frc.robot.Subsystems.Drive;
|
||||
import frc.robot.Subsystems.Lanceur;
|
||||
import frc.robot.Subsystems.Limelight3G;
|
||||
|
||||
public class RobotContainer {
|
||||
Lanceur lanceur= new Lanceur();
|
||||
Accumulateur accumulateur = new Accumulateur();
|
||||
Limelight3G limelight3G = new Limelight3G();
|
||||
Drive drive = new Drive();
|
||||
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
|
||||
public RobotContainer() {
|
||||
dashboard.addCamera("limelight3G", "limelight3G","limelight.local:5800")
|
||||
|
@ -3,15 +3,11 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot.Subsystems;
|
||||
|
||||
|
||||
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 {
|
||||
|
||||
@ -42,7 +38,6 @@ public class Accumulateur extends SubsystemBase {
|
||||
public void desaccumule(){
|
||||
desaccumule(vitesse.getDouble(0.9));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
|
@ -3,12 +3,9 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot.Subsystems;
|
||||
|
||||
import java.io.File;
|
||||
import java.io.IOException;
|
||||
|
||||
import com.ctre.phoenix6.hardware.Pigeon2;
|
||||
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.kinematics.SwerveModulePosition;
|
||||
import edu.wpi.first.wpilibj.Filesystem;
|
||||
@ -16,7 +13,6 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import swervelib.SwerveDrive;
|
||||
import swervelib.parser.SwerveParser;
|
||||
|
||||
|
||||
public class Drive extends SubsystemBase {
|
||||
|
||||
SwerveDrive swerveDrive;
|
||||
|
@ -39,7 +39,6 @@ public class Lanceur extends SubsystemBase {
|
||||
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);
|
||||
@ -57,8 +56,8 @@ public class Lanceur extends SubsystemBase {
|
||||
public void tourelRotation(){
|
||||
tourelle.set(rotation.getDouble(0.1));
|
||||
}
|
||||
public void vitesseTourel(){
|
||||
tourelle.set(0.1);
|
||||
public double vitessetourel(){
|
||||
return(tourelle.getEncoder().getVelocity());
|
||||
}
|
||||
public double distancetourel(){
|
||||
return(tourelle.getEncoder().getPosition());
|
||||
|
@ -12,6 +12,7 @@ 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 =
|
||||
@ -20,7 +21,6 @@ public class Limelight3G extends SubsystemBase {
|
||||
.withPosition(2, 4)
|
||||
.getEntry();
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight");
|
||||
|
||||
NetworkTableEntry tx = table.getEntry("tx");
|
||||
NetworkTableEntry ty = table.getEntry("ty");
|
||||
NetworkTableEntry pipeline = table.getEntry("pipeline");
|
||||
|
Loading…
x
Reference in New Issue
Block a user