Compare commits
	
		
			14 Commits
		
	
	
		
			grimpe
			...
			29227dd2f6
		
	
	| Author | SHA1 | Date | |
|---|---|---|---|
|  | 29227dd2f6 | ||
|  | dc36eea320 | ||
|  | eaa14fb1b1 | ||
|  | 3458203225 | ||
|  | 6683613c7f | ||
|  | 2ac9cfe8ff | ||
|  | 56704c3e68 | ||
|  | 4c49ad4e51 | ||
|  | afe25cf046 | ||
|  | eec4eee2ff | ||
|  | 15be1d67ea | ||
|  | e4c7a12606 | ||
|  | 72da7b7d74 | ||
|  | fd8ab8663b | 
							
								
								
									
										109
									
								
								simgui-ds.json
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										109
									
								
								simgui-ds.json
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,109 @@ | |||||||
|  | { | ||||||
|  |   "FMS": { | ||||||
|  |     "window": { | ||||||
|  |       "visible": false | ||||||
|  |     } | ||||||
|  |   }, | ||||||
|  |   "Joysticks": { | ||||||
|  |     "window": { | ||||||
|  |       "visible": false | ||||||
|  |     } | ||||||
|  |   }, | ||||||
|  |   "keyboardJoysticks": [ | ||||||
|  |     { | ||||||
|  |       "axisConfig": [ | ||||||
|  |         { | ||||||
|  |           "decKey": 65, | ||||||
|  |           "incKey": 68 | ||||||
|  |         }, | ||||||
|  |         { | ||||||
|  |           "decKey": 87, | ||||||
|  |           "incKey": 83 | ||||||
|  |         }, | ||||||
|  |         { | ||||||
|  |           "decKey": 69, | ||||||
|  |           "decayRate": 0.0, | ||||||
|  |           "incKey": 82, | ||||||
|  |           "keyRate": 0.009999999776482582 | ||||||
|  |         } | ||||||
|  |       ], | ||||||
|  |       "axisCount": 3, | ||||||
|  |       "buttonCount": 4, | ||||||
|  |       "buttonKeys": [ | ||||||
|  |         90, | ||||||
|  |         88, | ||||||
|  |         67, | ||||||
|  |         86 | ||||||
|  |       ], | ||||||
|  |       "povConfig": [ | ||||||
|  |         { | ||||||
|  |           "key0": 328, | ||||||
|  |           "key135": 323, | ||||||
|  |           "key180": 322, | ||||||
|  |           "key225": 321, | ||||||
|  |           "key270": 324, | ||||||
|  |           "key315": 327, | ||||||
|  |           "key45": 329, | ||||||
|  |           "key90": 326 | ||||||
|  |         } | ||||||
|  |       ], | ||||||
|  |       "povCount": 1 | ||||||
|  |     }, | ||||||
|  |     { | ||||||
|  |       "axisConfig": [ | ||||||
|  |         { | ||||||
|  |           "decKey": 74, | ||||||
|  |           "incKey": 76 | ||||||
|  |         }, | ||||||
|  |         { | ||||||
|  |           "decKey": 73, | ||||||
|  |           "incKey": 75 | ||||||
|  |         } | ||||||
|  |       ], | ||||||
|  |       "axisCount": 2, | ||||||
|  |       "buttonCount": 4, | ||||||
|  |       "buttonKeys": [ | ||||||
|  |         77, | ||||||
|  |         44, | ||||||
|  |         46, | ||||||
|  |         47 | ||||||
|  |       ], | ||||||
|  |       "povCount": 0 | ||||||
|  |     }, | ||||||
|  |     { | ||||||
|  |       "axisConfig": [ | ||||||
|  |         { | ||||||
|  |           "decKey": 263, | ||||||
|  |           "incKey": 262 | ||||||
|  |         }, | ||||||
|  |         { | ||||||
|  |           "decKey": 265, | ||||||
|  |           "incKey": 264 | ||||||
|  |         } | ||||||
|  |       ], | ||||||
|  |       "axisCount": 2, | ||||||
|  |       "buttonCount": 6, | ||||||
|  |       "buttonKeys": [ | ||||||
|  |         260, | ||||||
|  |         268, | ||||||
|  |         266, | ||||||
|  |         261, | ||||||
|  |         269, | ||||||
|  |         267 | ||||||
|  |       ], | ||||||
|  |       "povCount": 0 | ||||||
|  |     }, | ||||||
|  |     { | ||||||
|  |       "axisCount": 0, | ||||||
|  |       "buttonCount": 0, | ||||||
|  |       "povCount": 0 | ||||||
|  |     } | ||||||
|  |   ], | ||||||
|  |   "robotJoysticks": [ | ||||||
|  |     {}, | ||||||
|  |     { | ||||||
|  |       "guid": "78696e70757401000000000000000000", | ||||||
|  |       "useGamepad": true | ||||||
|  |     } | ||||||
|  |   ] | ||||||
|  | } | ||||||
| @@ -6,13 +6,28 @@ package frc.robot; | |||||||
|  |  | ||||||
| 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; | ||||||
|  | import edu.wpi.first.wpilibj2.command.button.CommandXboxController; | ||||||
|  | import frc.robot.commands.BalayeuseAlgue; | ||||||
|  | import frc.robot.commands.BalayeuseCoral; | ||||||
|  | import frc.robot.commands.BalayeuseHaut; | ||||||
|  | import frc.robot.commands.L1Requin; | ||||||
|  | import frc.robot.subsystems.Requin; | ||||||
|  | import frc.robot.subsystems.Bougie; | ||||||
| public class RobotContainer { | public class RobotContainer { | ||||||
|  |   CommandXboxController manette1 = new CommandXboxController(0); | ||||||
|  |   CommandXboxController manette2 = new CommandXboxController(1); | ||||||
|  |   Requin requin = new Requin(); | ||||||
|  |   Bougie bougie = new Bougie(); | ||||||
|   public RobotContainer() { |   public RobotContainer() { | ||||||
|     configureBindings(); |     configureBindings(); | ||||||
|   } |   } | ||||||
|  |  | ||||||
|   private void configureBindings() {} |   private void configureBindings() { | ||||||
|  |     manette2.b().whileTrue(new BalayeuseAlgue(requin)); | ||||||
|  |     manette2.x().whileTrue(new BalayeuseCoral(requin)); | ||||||
|  |     manette2.y().whileTrue(new L1Requin(requin,bougie)); | ||||||
|  |     manette2.rightBumper().whileTrue(new BalayeuseHaut(requin)); | ||||||
|  |   } | ||||||
|  |  | ||||||
|   public Command getAutonomousCommand() { |   public Command getAutonomousCommand() { | ||||||
|     return Commands.print("No autonomous command configured"); |     return Commands.print("No autonomous command configured"); | ||||||
|   | |||||||
							
								
								
									
										62
									
								
								src/main/java/frc/robot/commands/BalayeuseAlgue.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										62
									
								
								src/main/java/frc/robot/commands/BalayeuseAlgue.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,62 @@ | |||||||
|  | // 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.Bougie; | ||||||
|  | import frc.robot.subsystems.Requin; | ||||||
|  |  | ||||||
|  | /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||||
|  | public class BalayeuseAlgue extends Command { | ||||||
|  |   private Requin requin; | ||||||
|  |   private Bougie bougie; | ||||||
|  |   /** Creates a new Balayeuse. */ | ||||||
|  |   public BalayeuseAlgue(Requin requin) { | ||||||
|  |     this.requin = requin; | ||||||
|  |     this.bougie =bougie; | ||||||
|  |     addRequirements(requin); | ||||||
|  |     // 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(requin.encodeur()>=500 &&  requin.encodeur()<=510){ | ||||||
|  |        requin.rotationer(0); | ||||||
|  |        if(requin.stop()){ | ||||||
|  |        requin.balaye(0); | ||||||
|  |        bougie.Vert(); | ||||||
|  |      } | ||||||
|  |          else{ | ||||||
|  |            | ||||||
|  |            requin.balaye(0.5); | ||||||
|  |      } | ||||||
|  |      } | ||||||
|  |      else if(requin.encodeur()>=510){ | ||||||
|  |      requin.rotationer(0.5); | ||||||
|  |      } | ||||||
|  |      else{ | ||||||
|  |       requin.rotationer(-0.5); | ||||||
|  |      } | ||||||
|  |      | ||||||
|  |    } | ||||||
|  |  | ||||||
|  |   // Called once the command ends or is interrupted. | ||||||
|  |   @Override | ||||||
|  |   public void end(boolean interrupted) { | ||||||
|  |     requin.rotationer(0); | ||||||
|  |     requin.balaye(0); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Returns true when the command should end. | ||||||
|  |   @Override | ||||||
|  |   public boolean isFinished() { | ||||||
|  |     return false; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										67
									
								
								src/main/java/frc/robot/commands/BalayeuseCoral.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										67
									
								
								src/main/java/frc/robot/commands/BalayeuseCoral.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,67 @@ | |||||||
|  | // 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.Bougie; | ||||||
|  | import frc.robot.subsystems.Requin; | ||||||
|  |  | ||||||
|  | /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||||
|  | public class BalayeuseCoral extends Command { | ||||||
|  |   private Requin requin; | ||||||
|  |   private Bougie bougie; | ||||||
|  |   /** Creates a new Balayeuse. */ | ||||||
|  |   public BalayeuseCoral(Requin requin) { | ||||||
|  |     this.requin = requin; | ||||||
|  |     this.bougie = bougie; | ||||||
|  |     addRequirements(requin); | ||||||
|  |     // 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(requin.encodeur()>=100 &&  requin.encodeur()<=110){ | ||||||
|  |        requin.rotationer(0); | ||||||
|  |       if(requin.amp()>8){ | ||||||
|  |       requin.balaye(0); | ||||||
|  |        bougie.Vert(); | ||||||
|  |        if(requin.enHaut()){ | ||||||
|  |         requin.rotationer(0); | ||||||
|  |        } | ||||||
|  |         else{ | ||||||
|  |           requin.rotationer(0.5); | ||||||
|  |         } | ||||||
|  |     } | ||||||
|  |      else{ | ||||||
|  |        requin.balaye(0.5); | ||||||
|  |      } | ||||||
|  |      } | ||||||
|  |      else if(requin.encodeur()>=110){ | ||||||
|  |      requin.rotationer(0.5); | ||||||
|  |      } | ||||||
|  |      else{ | ||||||
|  |        requin.rotationer(-0.5); | ||||||
|  |      } | ||||||
|  |      | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Called once the command ends or is interrupted. | ||||||
|  |   @Override | ||||||
|  |   public void end(boolean interrupted) { | ||||||
|  |     requin.rotationer(0); | ||||||
|  |     requin.balaye(0); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Returns true when the command should end. | ||||||
|  |   @Override | ||||||
|  |   public boolean isFinished() { | ||||||
|  |     return false; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										47
									
								
								src/main/java/frc/robot/commands/BalayeuseHaut.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										47
									
								
								src/main/java/frc/robot/commands/BalayeuseHaut.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,47 @@ | |||||||
|  | // 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.Requin; | ||||||
|  |  | ||||||
|  | /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||||
|  | public class BalayeuseHaut extends Command { | ||||||
|  |   private Requin requin; | ||||||
|  |   /** Creates a new Balayeuse. */ | ||||||
|  |   public BalayeuseHaut(Requin requin) { | ||||||
|  |     this.requin = requin; | ||||||
|  |     addRequirements(requin); | ||||||
|  |     // 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(requin.enHaut()==true){ | ||||||
|  |       requin.rotationer(0); | ||||||
|  |       requin.reset(); | ||||||
|  |     } | ||||||
|  |     else{ | ||||||
|  |       requin.rotationer(0.5); | ||||||
|  |     } | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Called once the command ends or is interrupted. | ||||||
|  |   @Override | ||||||
|  |   public void end(boolean interrupted) { | ||||||
|  |     requin.rotationer(0); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Returns true when the command should end. | ||||||
|  |   @Override | ||||||
|  |   public boolean isFinished() { | ||||||
|  |     return false; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										40
									
								
								src/main/java/frc/robot/commands/ExpireAlgue.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										40
									
								
								src/main/java/frc/robot/commands/ExpireAlgue.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,40 @@ | |||||||
|  | // 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.Requin; | ||||||
|  |  | ||||||
|  | /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||||
|  | public class ExpireAlgue extends Command { | ||||||
|  |   private Requin requin; | ||||||
|  |   /** Creates a new ExpireAlgue. */ | ||||||
|  |   public ExpireAlgue(Requin requin) { | ||||||
|  |     this.requin = requin; | ||||||
|  |     // 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() { | ||||||
|  |     requin.balaye(0.5); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Called once the command ends or is interrupted. | ||||||
|  |   @Override | ||||||
|  |   public void end(boolean interrupted) { | ||||||
|  |     requin.balaye(0); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Returns true when the command should end. | ||||||
|  |   @Override | ||||||
|  |   public boolean isFinished() { | ||||||
|  |     return false; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										65
									
								
								src/main/java/frc/robot/commands/L1Requin.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										65
									
								
								src/main/java/frc/robot/commands/L1Requin.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,65 @@ | |||||||
|  | // 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.Bougie; | ||||||
|  | import frc.robot.subsystems.Requin; | ||||||
|  |  | ||||||
|  | /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||||
|  | public class L1Requin extends Command { | ||||||
|  |   private Requin requin; | ||||||
|  |   private Bougie bougie; | ||||||
|  |   /** Creates a new Balayeuse. */ | ||||||
|  |   public L1Requin(Requin requin,Bougie bougie) { | ||||||
|  |     this.requin = requin; | ||||||
|  |     this.bougie = bougie; | ||||||
|  |     addRequirements(requin,bougie); | ||||||
|  |     // 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(requin.encodeur()>=800 &&  requin.encodeur()<=810){ | ||||||
|  |       requin.rotationer(0); | ||||||
|  |       if(requin.amp()>8){ | ||||||
|  |       requin.balaye(-0.5); | ||||||
|  |     } | ||||||
|  |         else{ | ||||||
|  |           requin.balaye(0);  | ||||||
|  |           bougie.Rouge(); | ||||||
|  |       } | ||||||
|  |     } | ||||||
|  |     else if(requin.encodeur()>=810){ | ||||||
|  |     requin.rotationer(0.5); | ||||||
|  |     } | ||||||
|  |     else{ | ||||||
|  |       requin.rotationer(-0.5); | ||||||
|  |     } | ||||||
|  |      | ||||||
|  |      | ||||||
|  |        | ||||||
|  |      | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Called once the command ends or is interrupted. | ||||||
|  |   @Override | ||||||
|  |   public void end(boolean interrupted) { | ||||||
|  |     requin.rotationer(0); | ||||||
|  |     requin.balaye(0); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Returns true when the command should end. | ||||||
|  |   @Override | ||||||
|  |   public boolean isFinished() { | ||||||
|  |     return false; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										52
									
								
								src/main/java/frc/robot/subsystems/Bougie.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										52
									
								
								src/main/java/frc/robot/subsystems/Bougie.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,52 @@ | |||||||
|  | // 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 com.ctre.phoenix.led.CANdle; | ||||||
|  | import com.ctre.phoenix.led.CANdleConfiguration; | ||||||
|  | import com.ctre.phoenix.led.RainbowAnimation; | ||||||
|  |  | ||||||
|  | import edu.wpi.first.wpilibj2.command.SubsystemBase; | ||||||
|  |  | ||||||
|  | public class Bougie extends SubsystemBase { | ||||||
|  |   CANdle candle = new CANdle(50); | ||||||
|  |   CANdleConfiguration config = new CANdleConfiguration(); | ||||||
|  |   RainbowAnimation rainbowAnim = new RainbowAnimation(1, 0.5, 64); | ||||||
|  |   /** Creates a new Bougie. */ | ||||||
|  |   public Bougie() { | ||||||
|  |     config.brightnessScalar = 0.5; | ||||||
|  |     candle.configAllSettings(config); | ||||||
|  |   } | ||||||
|  |   public void Rouge() { | ||||||
|  |    candle.setLEDs(255, 0, 0,0,8,8); | ||||||
|  |    candle.setLEDs(255, 0, 0,0,24,8); | ||||||
|  |    candle.setLEDs(255, 0, 0,0,40,8); | ||||||
|  |    candle.setLEDs(255, 0, 0,0,56,8); | ||||||
|  |   } | ||||||
|  |   public void Vert() { | ||||||
|  |    candle.setLEDs(0, 255, 0,0,8,8); | ||||||
|  |    candle.setLEDs(0, 255, 0,0,24,8); | ||||||
|  |    candle.setLEDs(0, 255, 0,0,40,8); | ||||||
|  |    candle.setLEDs(0, 255, 0,0,56,8); | ||||||
|  |   } | ||||||
|  |   public void Bleu() { | ||||||
|  |     candle.setLEDs(0, 0, 255,0,16,8); | ||||||
|  |     candle.setLEDs(0, 0, 255,0,32,8); | ||||||
|  |     candle.setLEDs(0, 0, 255,0,48,8); | ||||||
|  |     candle.setLEDs(0, 0, 255,0,64,8); | ||||||
|  |   } | ||||||
|  |    public void Jaune() { | ||||||
|  |    candle.setLEDs(255, 215, 0,0,16,8); | ||||||
|  |    candle.setLEDs(255, 215, 0,0,32,8); | ||||||
|  |    candle.setLEDs(255, 215, 0,0,48,8); | ||||||
|  |    candle.setLEDs(255, 215, 0,0,64,8); | ||||||
|  |    } | ||||||
|  |   public void RainBow(){candle.animate(rainbowAnim);} | ||||||
|  |   public void RainBowStop(){candle.animate(null);} | ||||||
|  |   @Override | ||||||
|  |   public void periodic() { | ||||||
|  |     // This method will be called once per scheduler run | ||||||
|  |   } | ||||||
|  | } | ||||||
| @@ -11,7 +11,7 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase; | |||||||
| public class Grimpeur extends SubsystemBase { | public class Grimpeur extends SubsystemBase { | ||||||
|   /** Creates a new Grimpeur. */ |   /** Creates a new Grimpeur. */ | ||||||
|   public Grimpeur() {} |   public Grimpeur() {} | ||||||
|   final Spark grimpeur = new Spark(0); |   final Spark grimpeur = new Spark(16); | ||||||
|   final DigitalInput limit1 = new DigitalInput(0); |   final DigitalInput limit1 = new DigitalInput(0); | ||||||
|   public void grimpe(double vitesse){ |   public void grimpe(double vitesse){ | ||||||
|     grimpeur.set(vitesse); |     grimpeur.set(vitesse); | ||||||
|   | |||||||
							
								
								
									
										46
									
								
								src/main/java/frc/robot/subsystems/Requin.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										46
									
								
								src/main/java/frc/robot/subsystems/Requin.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,46 @@ | |||||||
|  | // 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 com.revrobotics.spark.SparkFlex; | ||||||
|  | import com.revrobotics.spark.SparkMax; | ||||||
|  | import com.revrobotics.spark.SparkLowLevel.MotorType; | ||||||
|  |  | ||||||
|  | import edu.wpi.first.wpilibj.DigitalInput; | ||||||
|  | import edu.wpi.first.wpilibj2.command.SubsystemBase; | ||||||
|  |  | ||||||
|  | public class Requin extends SubsystemBase { | ||||||
|  |   /** Creates a new Requin. */ | ||||||
|  |   public Requin() {} | ||||||
|  |   final SparkFlex balaye = new SparkFlex(15, MotorType.kBrushless); | ||||||
|  |   final SparkMax rotatione = new SparkMax(17, MotorType.kBrushless); | ||||||
|  |   final DigitalInput limit3 = new DigitalInput(4); | ||||||
|  |   final DigitalInput limit5 = new DigitalInput(5); | ||||||
|  |   public void balaye(double vitesse){ | ||||||
|  |     balaye.set(vitesse); | ||||||
|  |   } | ||||||
|  |   public void rotationer(double vitesse){ | ||||||
|  |   rotatione.set(vitesse); | ||||||
|  |   } | ||||||
|  |   public boolean enHaut(){ | ||||||
|  |   return limit3.get(); | ||||||
|  |   }  | ||||||
|  |   public boolean stop(){ | ||||||
|  |   return  limit5.get(); | ||||||
|  |   } | ||||||
|  |   public double encodeur(){ | ||||||
|  |   return rotatione.getEncoder().getPosition(); | ||||||
|  |   } | ||||||
|  |   public void reset(){ | ||||||
|  |     rotatione.getEncoder().setPosition(0); | ||||||
|  |   } | ||||||
|  |   public double amp(){ | ||||||
|  |     return balaye.getOutputCurrent(); | ||||||
|  |   } | ||||||
|  |   @Override | ||||||
|  |   public void periodic() { | ||||||
|  |     // This method will be called once per scheduler run | ||||||
|  |   } | ||||||
|  | } | ||||||
		Reference in New Issue
	
	Block a user