This commit is contained in:
Antoine PerreaultE
2024-02-06 19:57:52 -05:00
56 changed files with 2117 additions and 162 deletions

View File

@ -6,17 +6,22 @@ package frc.robot.subsystem;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
import edu.wpi.first.networktables.GenericEntry;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
public class Accumulateur extends SubsystemBase {
/** Creates a new Accumulateur. */
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
private GenericEntry vitesse =
dashboard.add("vitesseacc", 1)
.getEntry();
final WPI_TalonSRX Moteuracc2 = new WPI_TalonSRX(Constants.Moteuracc2);
final WPI_TalonSRX Moteuracc = new WPI_TalonSRX(Constants.Moteuracc);
final DigitalInput limitacc = new DigitalInput(Constants.limitacc);
@ -32,12 +37,16 @@ public class Accumulateur extends SubsystemBase {
return limitacc.get();
}
public Accumulateur() {
dashboard.addBoolean("limitacc", this::limitswitch);
}
public void Accumuler(double vitesse){
Moteuracc.set(vitesse);
Moteuracc2.set(vitesse);
}
public void Accumuler(){
Accumuler(vitesse.getDouble(0.1));
}
@Override
public void periodic() {

View File

@ -4,7 +4,7 @@
package frc.robot.subsystem;
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

View File

@ -6,8 +6,15 @@ package frc.robot.subsystem;
import java.io.File;
import java.io.IOException;
import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.util.HolonomicPathFollowerConfig;
import com.pathplanner.lib.util.PIDConstants;
import com.pathplanner.lib.util.ReplanningConfig;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Filesystem;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import swervelib.SwerveDrive;
@ -25,7 +32,17 @@ public class Drive extends SubsystemBase {
}
public Drive() {
AutoBuilder.configureHolonomic(swerveDrive::getPose, swerveDrive::resetOdometry, swerveDrive::getRobotVelocity, swerveDrive::setChassisSpeeds, new HolonomicPathFollowerConfig(
new PIDConstants(5,0,0), new PIDConstants(5,0,0), 4.5,
0.275,
new ReplanningConfig()
), ()->{
var alliance = DriverStation.getAlliance();
if(alliance.isPresent()){
return alliance.get() == DriverStation.Alliance.Red;
}
return false;
}, this);
try {
this.swerveDrive = new SwerveParser(swerveJsonDirectory).createSwerveDrive(2);
} catch (IOException e) {

View File

@ -16,7 +16,7 @@ public class Guideur extends SubsystemBase {
final WPI_TalonSRX guideur = new WPI_TalonSRX(Constants.guideur);
final DigitalInput guideurhaut = new DigitalInput(Constants.guideurhaut);
final DigitalInput guideurbas = new DigitalInput(Constants.guideurhaut);
final DigitalInput guideurbas = new DigitalInput(Constants.guideurbas);
public void guider(double vitesse){
guideur.set(vitesse);

View File

@ -0,0 +1,27 @@
// 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.subsystem;
import edu.wpi.first.wpilibj.AddressableLED;
import edu.wpi.first.wpilibj.AddressableLEDBuffer;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
public class LED extends SubsystemBase {
/** Creates a new LED. */
public LED() {}
AddressableLED led = new AddressableLED(9);
AddressableLEDBuffer ledBuffer = new AddressableLEDBuffer(60);
public void led(){
led.setData(ledBuffer);
led.start();
}
public void couleur(int R, int G, int B){
ledBuffer.setRGB(0, R, G, B);
}
@Override
public void periodic() {
// This method will be called once per scheduler run
}
}

View File

@ -7,29 +7,49 @@ package frc.robot.subsystem;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkLowLevel.MotorType;
import edu.wpi.first.networktables.GenericEntry;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
public class Lanceur extends SubsystemBase {
/** Creates a new Lanceur. */
public Lanceur() {}
final CANSparkMax lancer = new CANSparkMax(Constants.lanceur, MotorType.kBrushless);
final CANSparkMax lancer2 = new CANSparkMax(Constants.lancer2, MotorType.kBrushless);
final CANSparkMax lancer3 = new CANSparkMax(Constants.lancer3, MotorType.kBrushless);
final CANSparkMax lancer4 = new CANSparkMax(Constants.lancer4, MotorType.kBrushless);
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
private GenericEntry vitesse =
dashboard.add("vitesse", 1)
.getEntry();
private GenericEntry vitesseamp =
dashboard.add("vitesseamp", 1)
.getEntry();
public Lanceur() {
}
final CANSparkMax lanceur1 = new CANSparkMax(Constants.lanceur, MotorType.kBrushless);
final CANSparkMax lanceur2 = new CANSparkMax(Constants.lancer2, MotorType.kBrushless);
final CANSparkMax lanceur3 = new CANSparkMax(Constants.lancer3, MotorType.kBrushless);
final CANSparkMax lanceur4 = new CANSparkMax(Constants.lancer4, MotorType.kBrushless);
public void pid(){
lanceur1.getPIDController();
}
public void lancer(double vitesse){
lancer.set(vitesse);
lanceur1.set(vitesse);
}
public void lancerspeaker(){
lancer(vitesse.getDouble(0.1));
}
public void lanceramp(){
lancer(vitesseamp.getDouble(0.5));
}
public double vitesse(double vitesse){
return lanceur1.getEncoder().getVelocity();
}
public void lanceur(){
lancer2.follow(lancer);
lancer3.follow(lancer);
lancer4.follow(lancer);
lancer3.setInverted(true);
lancer4.setInverted(true);
lanceur2.follow(lanceur1);
lanceur3.follow(lanceur1);
lanceur4.follow(lanceur1);
lanceur3.setInverted(true);
lanceur4.setInverted(true);
}
@Override

View File

@ -1,18 +1,75 @@
// 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.subsystem;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.PixyException;
import frc.robot.PixyPacket;
import edu.wpi.first.wpilibj.SerialPort;
import edu.wpi.first.wpilibj.SerialPort.Port;
//Warning: if the pixy is plugged in through mini usb, this code WILL NOT WORK b/c the pixy is smart and detects where it should send data
public class Pixy extends SubsystemBase {
/** Creates a new Pixy. */
public Pixy() {}
SerialPort pixy;
Port port = Port.kMXP;
PixyPacket[] packets;
PixyException pExc;
String print;
@Override
public void periodic() {
// This method will be called once per scheduler run
}
}
public Pixy() {
pixy = new SerialPort(19200, port);
pixy.setReadBufferSize(14);
packets = new PixyPacket[7];
pExc = new PixyException(print);
}
//This method parses raw data from the pixy into readable integers
public int cvt(byte upper, byte lower) {
return (((int)upper & 0xff) << 8) | ((int)lower & 0xff);
}
public void pixyReset(){
pixy.reset();
}
//This method gathers data, then parses that data, and assigns the ints to global variables
public PixyPacket readPacket(int Signature) throws PixyException {
int Checksum;
int Sig;
byte[] rawData = new byte[32];
try{
rawData = pixy.read(32);
} catch (RuntimeException e){
}
if(rawData.length < 32){
return null;
}
for (int i = 0; i <= 16; i++) {
int syncWord = cvt(rawData[i+1], rawData[i+0]); //Parse first 2 bytes
if (syncWord == 0xaa55) { //Check is first 2 bytes equal a "sync word", which indicates the start of a packet of valid data
syncWord = cvt(rawData[i+3], rawData[i+2]); //Parse the next 2 bytes
if (syncWord != 0xaa55){ //Shifts everything in the case that one syncword is sent
i -= 2;
}
//This next block parses the rest of the data
Checksum = cvt(rawData[i+5], rawData[i+4]);
Sig = cvt(rawData[i+7], rawData[i+6]);
if(Sig <= 0 || Sig > packets.length){
break;
}
packets[Sig - 1] = new PixyPacket();
packets[Sig - 1].X = cvt(rawData[i+9], rawData[i+8]);
packets[Sig - 1].Y = cvt(rawData[i+11], rawData[i+10]);
packets[Sig - 1].Width = cvt(rawData[i+13], rawData[i+12]);
packets[Sig - 1].Height = cvt(rawData[i+15], rawData[i+14]);
//Checks whether the data is valid using the checksum *This if block should never be entered*
if (Checksum != Sig + packets[Sig - 1].X + packets[Sig - 1].Y + packets[Sig - 1].Width + packets[Sig - 1].Height) {
packets[Sig - 1] = null;
throw pExc;
}
break;
}
}
//Assigns our packet to a temp packet, then deletes data so that we dont return old data
PixyPacket pkt = packets[Signature - 1];
packets[Signature - 1] = null;
return pkt;
}
}