Merge branch 'pince' of https://git.demerso.net/PLS5618/Reefscape-2025
This commit is contained in:
@ -11,7 +11,7 @@ import com.ctre.phoenix.led.RainbowAnimation;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Bougie extends SubsystemBase {
|
||||
CANdle candle = new CANdle(5);
|
||||
CANdle candle = new CANdle(23);
|
||||
CANdleConfiguration config = new CANdleConfiguration();
|
||||
RainbowAnimation rainbowAnim = new RainbowAnimation(1, 0.5, 64);
|
||||
/** Creates a new Bougie. */
|
||||
@ -20,14 +20,29 @@ public class Bougie extends SubsystemBase {
|
||||
candle.configAllSettings(config);
|
||||
}
|
||||
public void Rouge() {
|
||||
candle.setLEDs(255, 0, 0);
|
||||
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);
|
||||
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);
|
||||
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
|
||||
@ -35,4 +50,3 @@ public class Bougie extends SubsystemBase {
|
||||
// This method will be called once per scheduler run
|
||||
}
|
||||
}
|
||||
|
||||
|
37
src/main/java/frc/robot/subsystems/Elevateur.java
Normal file
37
src/main/java/frc/robot/subsystems/Elevateur.java
Normal file
@ -0,0 +1,37 @@
|
||||
// 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.networktables.GenericEntry;
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import com.revrobotics.spark.SparkMax;
|
||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||
public class Elevateur extends SubsystemBase {
|
||||
/** Creates a new Elevateur. */
|
||||
public Elevateur() {}
|
||||
final SparkMax monte = new SparkMax(22, MotorType.kBrushless);
|
||||
final DigitalInput limit2 = new DigitalInput(1);
|
||||
GenericEntry teb = Shuffleboard.getTab("teb")
|
||||
.add("elevateur encodeur",position())
|
||||
.getEntry();
|
||||
public double position(){
|
||||
return monte.getEncoder().getPosition();
|
||||
}
|
||||
public void vitesse(double vitesse){
|
||||
monte.set(vitesse);
|
||||
}
|
||||
public boolean limit2(){
|
||||
return limit2.get();
|
||||
}
|
||||
public void reset(){
|
||||
monte.getEncoder().setPosition(0);
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
}
|
||||
}
|
@ -1,26 +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.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.Spark;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Grimpeur extends SubsystemBase {
|
||||
/** Creates a new Grimpeur. */
|
||||
public Grimpeur() {}
|
||||
final Spark grimpeur = new Spark(0);
|
||||
final DigitalInput limit1 = new DigitalInput(0);
|
||||
public void grimpe(double vitesse){
|
||||
grimpeur.set(vitesse);
|
||||
}
|
||||
final void stop(){
|
||||
limit1.get();
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
}
|
||||
}
|
61
src/main/java/frc/robot/subsystems/Pince.java
Normal file
61
src/main/java/frc/robot/subsystems/Pince.java
Normal file
@ -0,0 +1,61 @@
|
||||
// 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.SparkLowLevel.MotorType;
|
||||
import com.revrobotics.spark.SparkMax;
|
||||
|
||||
import edu.wpi.first.networktables.GenericEntry;
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Pince extends SubsystemBase {
|
||||
/** Creates a new Pince. */
|
||||
public Pince() {}
|
||||
final SparkMax coral = new SparkMax(20, MotorType.kBrushless);
|
||||
final SparkMax pivoti = new SparkMax(14, MotorType.kBrushless);
|
||||
final SparkMax algue1 = new SparkMax(16, MotorType.kBrushless);
|
||||
final SparkMax algue2 = new SparkMax(19, MotorType.kBrushless);
|
||||
final DigitalInput limit6 = new DigitalInput(0);
|
||||
GenericEntry teb = Shuffleboard.getTab("teb")
|
||||
.add("pince encodeur",encodeurpivot())
|
||||
.getEntry();
|
||||
public void aspirecoral(double vitesse){
|
||||
coral.set(vitesse);
|
||||
}
|
||||
public void pivote(double vitesse){
|
||||
pivoti.set(vitesse);
|
||||
}
|
||||
public void aspirealgue(double vitesse){
|
||||
algue2.set(vitesse);
|
||||
algue1.set(-vitesse);
|
||||
}
|
||||
public double encodeurpivot(){
|
||||
return pivoti.getEncoder().getPosition();
|
||||
}
|
||||
public boolean position(){
|
||||
return limit6.get();
|
||||
}
|
||||
public void reset(){
|
||||
pivoti.getEncoder().setPosition(0);
|
||||
}
|
||||
public double emperagecoral(){
|
||||
return coral.getOutputCurrent();
|
||||
}
|
||||
public double emperagealgue(){
|
||||
return algue1.getOutputCurrent();
|
||||
}
|
||||
public void algue1Test(double vitesse){
|
||||
algue1.set(vitesse);
|
||||
}
|
||||
public void algue2Test(double vitesse){
|
||||
algue2.set(vitesse);
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
}
|
||||
}
|
Reference in New Issue
Block a user