Merge branch 'main' of https://git.demerso.net/PLS5618/pratique-2025
This commit is contained in:
		
							
								
								
									
										54
									
								
								src/main/java/frc/robot/Commands/FollowAprilTag.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										54
									
								
								src/main/java/frc/robot/Commands/FollowAprilTag.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,54 @@ | |||||||
|  | // 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.Limelight3G; | ||||||
|  |  | ||||||
|  | public class FollowAprilTag extends Command { | ||||||
|  |  | ||||||
|  |   private Limelight3G enlignement; | ||||||
|  |   private Drive drive; | ||||||
|  |   /** Creates a new Limelight3g. */ | ||||||
|  |   public FollowAprilTag(Limelight3G enlignement, Drive drive) { | ||||||
|  |     // Use addRequirements() here to declare subsystem dependencies. | ||||||
|  |     this.drive = drive; | ||||||
|  |     this.enlignement = enlignement; | ||||||
|  |  | ||||||
|  |     addRequirements(drive, 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) | ||||||
|  |     { | ||||||
|  |       drive.drive(0, 0, enlignement.getx()/30); | ||||||
|  |     } | ||||||
|  |     else | ||||||
|  |     { | ||||||
|  |       drive.drive(0, 0, 0); | ||||||
|  |     } | ||||||
|  |  | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Called once the command ends or is interrupted. | ||||||
|  |   @Override | ||||||
|  |   public void end(boolean interrupted) { | ||||||
|  |     drive.drive(0, 0, 0); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Returns true when the command should end. | ||||||
|  |   @Override | ||||||
|  |   public boolean isFinished() { | ||||||
|  |     return false; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										1265
									
								
								src/main/java/frc/robot/LimelightHelpers.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										1265
									
								
								src/main/java/frc/robot/LimelightHelpers.java
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							| @@ -4,11 +4,20 @@ | |||||||
|  |  | ||||||
| package frc.robot; | 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.Command; | ||||||
| import edu.wpi.first.wpilibj2.command.Commands; | import edu.wpi.first.wpilibj2.command.Commands; | ||||||
|  |  | ||||||
| public class RobotContainer { | public class RobotContainer { | ||||||
|  |   ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard"); | ||||||
|   public RobotContainer() { |   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(); |     configureBindings(); | ||||||
|   } |   } | ||||||
|  |  | ||||||
|   | |||||||
| @@ -5,6 +5,10 @@ | |||||||
| package frc.robot.Subsystems; | 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 edu.wpi.first.wpilibj2.command.SubsystemBase; | ||||||
|  |  | ||||||
|  |  | ||||||
| @@ -12,15 +16,35 @@ import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; | |||||||
| public class Accumulateur extends SubsystemBase { | public class Accumulateur extends SubsystemBase { | ||||||
|    |    | ||||||
|   /** Creates a new Accumulateur. */ |   /** 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 accumulateur1 = new WPI_TalonSRX(0); | ||||||
|   final WPI_TalonSRX accumulateur2 = new WPI_TalonSRX(10); |   final WPI_TalonSRX accumulateur2 = new WPI_TalonSRX(10); | ||||||
|  |   final DigitalInput photocell = new DigitalInput(94); | ||||||
|   public void encodeur(){ |   public void encodeur(){ | ||||||
|   } |   } | ||||||
|  |   public boolean limitswitch(){ | ||||||
|  |     return !photocell.get(); | ||||||
|  |   } | ||||||
|   public void desaccumule(double vitesse){ |   public void desaccumule(double vitesse){ | ||||||
|     accumulateur1.set(vitesse); |     accumulateur1.set(vitesse); | ||||||
|     accumulateur2.set(-vitesse); |     accumulateur2.set(-vitesse); | ||||||
|   } |   } | ||||||
|  |   public void desaccumule(){ | ||||||
|  |     desaccumule(vitesse.getDouble(0.9)); | ||||||
|  |   } | ||||||
|  |  | ||||||
|   @Override |   @Override | ||||||
|   public void periodic() { |   public void periodic() { | ||||||
|     // This method will be called once per scheduler run |     // This method will be called once per scheduler run | ||||||
|   | |||||||
| @@ -1,28 +0,0 @@ | |||||||
| // 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.networktables.NetworkTable; |  | ||||||
| import edu.wpi.first.networktables.NetworkTableEntry; |  | ||||||
| import edu.wpi.first.networktables.NetworkTableInstance; |  | ||||||
| public class Limelight extends SubsystemBase { |  | ||||||
| NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight"); |  | ||||||
| NetworkTableEntry tx = table.getEntry("tx"); |  | ||||||
| NetworkTableEntry ty = table.getEntry("ty"); |  | ||||||
| NetworkTableEntry ta = table.getEntry("ta"); |  | ||||||
|  |  | ||||||
| //read values periodically |  | ||||||
| double x = tx.getDouble(0.0); |  | ||||||
| double y = ty.getDouble(0.0); |  | ||||||
| double area = ta.getDouble(0.0); |  | ||||||
|   /** Creates a new Limelight. */ |  | ||||||
|   public Limelight() {} |  | ||||||
|  |  | ||||||
|   @Override |  | ||||||
|   public void periodic() { |  | ||||||
|     // This method will be called once per scheduler run |  | ||||||
|   } |  | ||||||
| } |  | ||||||
							
								
								
									
										48
									
								
								src/main/java/frc/robot/Subsystems/Limelight3G.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										48
									
								
								src/main/java/frc/robot/Subsystems/Limelight3G.java
									
									
									
									
									
										Normal 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 | ||||||
|  |   } | ||||||
|  | } | ||||||
		Reference in New Issue
	
	Block a user