Merge branch 'main' of https://git.demerso.net/pls5618/2024/robot
This commit is contained in:
@ -6,17 +6,47 @@ package frc.robot;
|
||||
|
||||
/** Add your docs here. */
|
||||
public class Constants {
|
||||
//moteur
|
||||
public static int lanceur = 1;
|
||||
public static int lancer2 = 2;
|
||||
public static int roue = 3;
|
||||
public static int etoile = 4;
|
||||
public static int Moteuracc2 = 5;
|
||||
public static int Moteuracc = 6;
|
||||
public static int guideur = 7;
|
||||
// limit switsh
|
||||
public static int guideurhaut = 8;
|
||||
public static int guideurbas = 9;
|
||||
public static int limitacc = 58;
|
||||
// Lanceur
|
||||
public static int lanceur = 10;
|
||||
public static int lancer2 = 13;
|
||||
public static int lancer3 = 14;
|
||||
public static int lancer4 = 15;
|
||||
// Ballayeuse
|
||||
public static int roue = 16;
|
||||
public static int etoile = 19;
|
||||
|
||||
// Accumulateur
|
||||
public static int Moteuracc2 = 20;
|
||||
public static int Moteuracc = 21;
|
||||
|
||||
// Guideur
|
||||
public static int guideur = 22;
|
||||
|
||||
//grimpeur
|
||||
public static int grimpeurd = 26;
|
||||
public static int grimpeurg = 27;
|
||||
|
||||
// Swerve
|
||||
public static int AvantDroitDrive = 17;
|
||||
public static int AvantDroitAngle = 18;
|
||||
public static int AvantGaucheDrive = 2;
|
||||
public static int AvantGaucheAngle = 3;
|
||||
public static int ArriereDroitDrive = 11;
|
||||
public static int ArriereDroitAngle = 12;
|
||||
public static int ArriereGaucheDrive = 8;
|
||||
public static int ArriereGaucheAngle = 9;
|
||||
|
||||
// CanCoder
|
||||
public static int AvantDroit = 5;
|
||||
public static int AvantGauche = 4;
|
||||
public static int ArriereDroit = 6;
|
||||
public static int ArriereGauche = 7;
|
||||
|
||||
// Limit switsh
|
||||
public static int guideurhaut = 23;
|
||||
public static int guideurbas = 24;
|
||||
public static int limitacc = 25;
|
||||
public static int limithaut = 28;
|
||||
public static int limitbas = 29;
|
||||
|
||||
}
|
||||
|
@ -13,6 +13,7 @@ import frc.robot.Constants;
|
||||
public class Accumulateur extends SubsystemBase {
|
||||
/** Creates a new Accumulateur. */
|
||||
public Accumulateur() {}
|
||||
|
||||
final WPI_TalonSRX Moteuracc2 = new WPI_TalonSRX(Constants.Moteuracc2);
|
||||
final WPI_TalonSRX Moteuracc = new WPI_TalonSRX(Constants.Moteuracc);
|
||||
final DigitalInput limitacc = new DigitalInput(0);
|
||||
|
@ -6,7 +6,6 @@ package frc.robot.subsystem;
|
||||
|
||||
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
|
||||
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
|
||||
import com.revrobotics.CANSparkMax;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.Constants;
|
||||
|
@ -4,11 +4,41 @@
|
||||
|
||||
package frc.robot.subsystem;
|
||||
|
||||
import java.io.File;
|
||||
import java.io.IOException;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.kinematics.SwerveModulePosition;
|
||||
import edu.wpi.first.wpilibj.Filesystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import swervelib.SwerveDrive;
|
||||
import swervelib.parser.SwerveParser;
|
||||
|
||||
public class Drive extends SubsystemBase {
|
||||
/** Creates a new Drive. */
|
||||
public Drive() {}
|
||||
|
||||
SwerveDrive swerveDrive;
|
||||
|
||||
File swerveJsonDirectory = new File(Filesystem.getDeployDirectory(),"swerve");
|
||||
|
||||
public void drive(double x, double y, double zRotation){
|
||||
swerveDrive.drive(new Translation2d(x*2, y*2), zRotation, true, false);
|
||||
}
|
||||
|
||||
public Drive() {
|
||||
|
||||
try {
|
||||
this.swerveDrive = new SwerveParser(swerveJsonDirectory).createSwerveDrive(2);
|
||||
} catch (IOException e) {
|
||||
e.printStackTrace();
|
||||
}
|
||||
}
|
||||
|
||||
public SwerveModulePosition[] distance(){
|
||||
return swerveDrive.getModulePositions();
|
||||
}
|
||||
public void reset(){
|
||||
|
||||
}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
|
60
src/main/java/frc/robot/subsystem/Grimpeur.java
Normal file
60
src/main/java/frc/robot/subsystem/Grimpeur.java
Normal file
@ -0,0 +1,60 @@
|
||||
// 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 com.kauailabs.navx.frc.AHRS;
|
||||
import com.revrobotics.CANSparkMax;
|
||||
import com.revrobotics.CANSparkLowLevel.MotorType;
|
||||
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.Constants;
|
||||
|
||||
public class Grimpeur extends SubsystemBase {
|
||||
/** Creates a new Acrocheur. */
|
||||
// moteur
|
||||
public Grimpeur() {}
|
||||
final CANSparkMax grimpeurd = new CANSparkMax(Constants.grimpeurd,MotorType.kBrushless);
|
||||
final CANSparkMax grimpeurg = new CANSparkMax(Constants.grimpeurg,MotorType.kBrushless);
|
||||
// limit switch
|
||||
final DigitalInput limitdroite = new DigitalInput(Constants.limithaut);
|
||||
final DigitalInput limitgauche = new DigitalInput(Constants.limitbas);
|
||||
//fonction
|
||||
public void droit(double vitesse){
|
||||
grimpeurd.set(vitesse);
|
||||
}
|
||||
public void gauche(double vitesse){
|
||||
grimpeurg.set(vitesse);
|
||||
}
|
||||
public boolean droite(){
|
||||
return limitdroite.get();
|
||||
}
|
||||
public boolean gauche(){
|
||||
return limitgauche.get();
|
||||
}
|
||||
public void resetencodeurd(){
|
||||
grimpeurd.getEncoder().setPosition(0);
|
||||
}
|
||||
public void resetencodeurg(){
|
||||
grimpeurg.getEncoder().setPosition(0);
|
||||
}
|
||||
public void grimpeur(){
|
||||
grimpeurg.follow(grimpeurd);
|
||||
}
|
||||
public AHRS gyroscope = new AHRS();
|
||||
public double getpitch(){
|
||||
return gyroscope.getPitch();
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
if(droite()) {
|
||||
resetencodeurd();
|
||||
}
|
||||
if(gauche()) {
|
||||
resetencodeurg();
|
||||
}
|
||||
}
|
||||
}
|
@ -13,9 +13,20 @@ import frc.robot.Constants;
|
||||
public class Guideur extends SubsystemBase {
|
||||
/** Creates a new Guideur. */
|
||||
public Guideur() {}
|
||||
|
||||
final WPI_TalonSRX guideur = new WPI_TalonSRX(Constants.guideur);
|
||||
private DigitalInput guideurhaut = new DigitalInput(Constants.guideurhaut);
|
||||
private DigitalInput guideurbas = new DigitalInput(Constants.guideurhaut);
|
||||
final DigitalInput guideurhaut = new DigitalInput(Constants.guideurhaut);
|
||||
final DigitalInput guideurbas = new DigitalInput(Constants.guideurhaut);
|
||||
|
||||
public void guider(double vitesse){
|
||||
guideur.set(vitesse);
|
||||
}
|
||||
public boolean haut(){
|
||||
return guideurhaut.get();
|
||||
}
|
||||
public boolean bas(){
|
||||
return guideurbas.get();
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
|
@ -18,16 +18,20 @@ public class Lanceur extends SubsystemBase {
|
||||
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.lanceur, MotorType.kBrushless);
|
||||
final CANSparkMax lancer4 = new CANSparkMax(Constants.lancer2, MotorType.kBrushless);
|
||||
|
||||
public void lancer(double vitesse){
|
||||
lancer.set(vitesse);
|
||||
}
|
||||
public void lanceur(){
|
||||
lancer2.follow(lancer);
|
||||
lancer3.follow(lancer);
|
||||
lancer4.follow(lancer);
|
||||
lancer3.setInverted(true);
|
||||
lancer4.setInverted(true);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
@Override
|
||||
public void periodic() {}
|
||||
// This method will be called once per scheduler run
|
||||
|
18
src/main/java/frc/robot/subsystem/Pixy.java
Normal file
18
src/main/java/frc/robot/subsystem/Pixy.java
Normal file
@ -0,0 +1,18 @@
|
||||
// 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;
|
||||
|
||||
public class Pixy extends SubsystemBase {
|
||||
|
||||
/** Creates a new Pixy. */
|
||||
public Pixy() {}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
}
|
||||
}
|
Reference in New Issue
Block a user