This commit is contained in:
Olivier Dubois 2023-02-15 19:40:20 -05:00
commit e645feabc4
19 changed files with 370 additions and 71 deletions

View File

@ -5,7 +5,10 @@ public class Constants {
public static int avantgauche = 1;
public static int arrieredroit = 2;
public static int arrieregauche = 3;
public static int BrasTelescopique = 4;
public static int pivot = 5;
//moteur
public static int leverGratte = 0;
public static int baisserGratte = 1;
@ -20,7 +23,9 @@ public class Constants {
public static int limitbg = 2;
public static int limithd = 3;
public static int limithg = 1;
public static int photocell = 4;
public static int limitpivot = 5;
public static int BrasTelescopique = 5;
}

View File

@ -4,17 +4,85 @@
package frc.robot;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
//subsystems
import frc.robot.subsystems.BasePilotable;
import frc.robot.subsystems.Gratte;
import frc.robot.subsystems.bras.BrasTelescopique;
import frc.robot.subsystems.bras.Pince;
import frc.robot.subsystems.bras.Pivot;
import frc.robot.subsystems.Limelight;
// command
import frc.robot.commands.BrakeFerme;
import frc.robot.commands.BrakeOuvre;
import frc.robot.commands.GratteBaisser;
import frc.robot.commands.GratteMonte;
import frc.robot.commands.Gyro;
import frc.robot.commands.Reculer;
import frc.robot.commands.bras.FermePince;
import frc.robot.commands.bras.OuvrePince;
import frc.robot.commands.bras.PivotBrasRentre;
import frc.robot.commands.bras.PivoteBrasBas;
import frc.robot.commands.bras.PivoteBrasHaut;
import frc.robot.commands.bras.PivoteBrasMilieux;
public class RobotContainer {
public RobotContainer() {
configureBindings();
}
XboxController manette1 = new XboxController(0);
XboxController manette2 = new XboxController(1);
// subsystems
BasePilotable basePilotable = new BasePilotable();
Gratte gratte = new Gratte();
BrasTelescopique brasTelescopique = new BrasTelescopique();
Pince pince = new Pince();
Pivot pivot = new Pivot();
Limelight limelight = new Limelight();
//commands
BrakeFerme brakeFerme = new BrakeFerme(basePilotable);
BrakeOuvre brakeOuvre = new BrakeOuvre(basePilotable);
GratteBaisser gratteBaisser = new GratteBaisser(gratte);
GratteMonte gratteMonte = new GratteMonte(gratte);
Gyro gyro = new Gyro(basePilotable);
FermePince fermePince = new FermePince(pince);
OuvrePince ouvrePince = new OuvrePince(pince);
PivotBrasRentre pivotBrasRentre = new PivotBrasRentre(brasTelescopique, pivot);
PivoteBrasBas pivoteBrasBas = new PivoteBrasBas(brasTelescopique, pivot);
PivoteBrasMilieux pivoteBrasMilieux = new PivoteBrasMilieux(brasTelescopique, pivot);
PivoteBrasHaut pivoteBrasHaut = new PivoteBrasHaut(brasTelescopique, pivot);
private void configureBindings() {}
public RobotContainer() {
configureBindings();
basePilotable.setDefaultCommand(new RunCommand(() -> {
basePilotable.drive(-manette1.getLeftY(), manette1.getLeftX());
},basePilotable));
}
private void configureBindings() {
}
public Command getAutonomousCommand() {
return Commands.print("No autonomous command configured");
return new SequentialCommandGroup(
new PivoteBrasMilieux(brasTelescopique, pivot),
new OuvrePince(pince),
new PivotBrasRentre(brasTelescopique, pivot).alongWith(new Reculer(basePilotable)),
new Gyro(basePilotable)
);
}
}

View File

@ -3,10 +3,10 @@
// the WPILib BSD license file in the root directory of this project.
package frc.robot.commands;
import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.subsystems.Gratte;
public class GratteBaisser extends CommandBase {
private Gratte gratte;
/** Creates a new GratteBaisser. */
@ -23,7 +23,20 @@ public class GratteBaisser extends CommandBase {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
gratte.baiser(0.5);
if(gratte.basd()){
gratte.baiser(0);
}
else{
gratte.baiser(0.5);
}
if(gratte.basg()){
gratte.baiser(0);
}
else{
gratte.baiser(0.5);
}
}
// Called once the command ends or is interrupted.

View File

@ -23,7 +23,18 @@ public class GratteMonte extends CommandBase {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
gratte.Lever(0.5);
if(gratte.hautd()){
gratte.Lever(0);
}
else{
gratte.Lever(0.5);
}
if(gratte.hautg()) {
gratte.Lever(0.5);
}
else{
gratte.Lever(0.5);
}
}
// Called once the command ends or is interrupted.

View File

@ -23,13 +23,13 @@ public class Gyro extends CommandBase {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if(basePilotable.getpitch()<15)
if(basePilotable.getpitch()<10)
{
basePilotable.drive(0.2, 0, 0);
basePilotable.drive(0.4, 0, 0);
}
else if(basePilotable.getpitch()>-15)
else if(basePilotable.getpitch()>-10)
{
basePilotable.drive(-0.2, 0, 0);
basePilotable.drive(-0.4, 0, 0);
}
else
{

View File

@ -4,21 +4,30 @@
package frc.robot.commands;
import edu.wpi.first.wpilibj2.command.CommandBase;
public class StablePlateform extends CommandBase {
/** Creates a new StablePlateform. */
public StablePlateform() {
import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.subsystems.BasePilotable;
public class Reculer extends CommandBase {
BasePilotable basePilotable;
/** Creates a new Reculer. */
public Reculer(BasePilotable basePilotable) {
this.basePilotable = basePilotable;
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(basePilotable);
}
// Called when the command is initially scheduled.
@Override
public void initialize() {}
public void initialize() {
basePilotable.Reset();
}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {}
public void execute() {
basePilotable.drive(0.2, 0, 0);
}
// Called once the command ends or is interrupted.
@Override

View 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.commands.bras;
import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.subsystems.bras.BrasTelescopique;
import frc.robot.subsystems.bras.Pivot;
public class PivotBrasRentre extends CommandBase {
private BrasTelescopique brasTelescopique;
private Pivot pivot;
/** Creates a new PivotBrasRentre. */
public PivotBrasRentre(BrasTelescopique brasTelescopique, Pivot pivot) {
this.brasTelescopique = brasTelescopique;
this.pivot = pivot;
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(brasTelescopique);
addRequirements(pivot);
}
// 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(brasTelescopique.distance()>1){
brasTelescopique.AvanceRecule(0.5);
}
if (pivot.distance()>1){
pivot.monteDescendre(0.5);
}
else if(brasTelescopique.photocell()){
brasTelescopique.Reset();
brasTelescopique.AvanceRecule(0);
}
else{
brasTelescopique.AvanceRecule(.5);
}
if(pivot.limitpivot()){
pivot.Reset();
pivot.monteDescendre(0);
}
else{
pivot.monteDescendre(0.5);
}
}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {}
// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}

View File

@ -4,12 +4,22 @@
package frc.robot.commands.bras;
import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.subsystems.bras.BrasTelescopique;
import frc.robot.subsystems.bras.Pivot;
public class PivoteBrasBas extends CommandBase {
private BrasTelescopique brasTelescopique;
private Pivot pivot;
/** Creates a new PivoteBrasBas. */
public PivoteBrasBas() {
public PivoteBrasBas(BrasTelescopique brasTelescopique, Pivot pivot) {
this.brasTelescopique = brasTelescopique;
this.pivot = pivot;
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(brasTelescopique);
addRequirements(pivot);
}
// Called when the command is initially scheduled.
@ -18,7 +28,28 @@ public class PivoteBrasBas extends CommandBase {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {}
public void execute() {
if(brasTelescopique.distance()<10){
brasTelescopique.AvanceRecule(0.5);
}
else if(brasTelescopique.distance()>11) {
brasTelescopique.AvanceRecule(-0.5);
}
else {
brasTelescopique.AvanceRecule(0);
}
if (pivot.distance()<10){
pivot.monteDescendre(0.5);
}
else if(pivot.distance()>11) {
pivot.monteDescendre(-0.5);
}
else{
pivot.monteDescendre(0);
}
}
// Called once the command ends or is interrupted.
@Override

View File

@ -5,11 +5,19 @@
package frc.robot.commands.bras;
import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.subsystems.bras.BrasTelescopique;
import frc.robot.subsystems.bras.Pivot;
public class PivoteBrasHaut extends CommandBase {
private BrasTelescopique brasTelescopique;
private Pivot pivot;
/** Creates a new PivoteBrasHaut. */
public PivoteBrasHaut() {
public PivoteBrasHaut(BrasTelescopique brasTelescopique, Pivot pivot) {
this.brasTelescopique = brasTelescopique;
this.pivot = pivot;
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(brasTelescopique);
addRequirements(pivot);
}
// Called when the command is initially scheduled.
@ -18,7 +26,26 @@ public class PivoteBrasHaut extends CommandBase {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {}
public void execute() {
if(brasTelescopique.distance()<10){
brasTelescopique.AvanceRecule(0.5);
}
else if(brasTelescopique.distance()>11) {
brasTelescopique.AvanceRecule(-0.5);
}
else {
brasTelescopique.AvanceRecule(0);
}
if (pivot.distance()<10){
pivot.monteDescendre(0.5);
}
else if(pivot.distance()>11) {
pivot.monteDescendre(-0.5);
}
else{
pivot.monteDescendre(0);
}
}
// Called once the command ends or is interrupted.
@Override

View File

@ -5,11 +5,19 @@
package frc.robot.commands.bras;
import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.subsystems.bras.BrasTelescopique;
import frc.robot.subsystems.bras.Pivot;
public class PivoteBrasMilieux extends CommandBase {
private BrasTelescopique brasTelescopique;
private Pivot pivot;
/** Creates a new PivoteBrasMilieux. */
public PivoteBrasMilieux() {
public PivoteBrasMilieux(BrasTelescopique brasTelescopique, Pivot pivot) {
this.brasTelescopique = brasTelescopique;
this.pivot = pivot;
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(brasTelescopique);
addRequirements(pivot);
}
// Called when the command is initially scheduled.
@ -18,7 +26,27 @@ public class PivoteBrasMilieux extends CommandBase {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {}
public void execute() {
if(brasTelescopique.distance()<10){
brasTelescopique.AvanceRecule(0.5);
}
else if(brasTelescopique.distance()>11) {
brasTelescopique.AvanceRecule(-0.5);
}
else {
brasTelescopique.AvanceRecule(0);
}
if (pivot.distance()<10){
pivot.monteDescendre(0.5);
}
else if(pivot.distance()>11) {
pivot.monteDescendre(-0.5);
}
else{
pivot.monteDescendre(0);
}
}
// Called once the command ends or is interrupted.
@Override

View File

@ -1,32 +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.commands;
import edu.wpi.first.wpilibj2.command.CommandBase;
public class limelight extends CommandBase {
/** Creates a new limelight. */
public limelight() {
// 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() {}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {}
// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}

View File

@ -7,7 +7,6 @@ package frc.robot.subsystems;
import com.kauailabs.navx.frc.AHRS;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.PneumaticsModuleType;
import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
@ -33,7 +32,7 @@ public class BasePilotable extends SubsystemBase {
return gyroscope.getPitch();
}
public void drive(double xSpeed, double zRotation, int i){
public void drive(double xSpeed, double zRotation, double d){
drive.arcadeDrive(xSpeed, zRotation);
}
public double distance(){

View File

@ -5,18 +5,14 @@
package frc.robot.subsystems;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
import edu.wpi.first.wpilibj.DigitalInput;
<<<<<<< HEAD
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
=======
>>>>>>> b20ba544a81d82752f6f8e390de38cbcfdc79f08
import frc.robot.Constants;
public class Gratte extends SubsystemBase {
private WPI_TalonSRX Gratted = new WPI_TalonSRX(Constants.leverGratte);
private WPI_TalonSRX Gratteg = new WPI_TalonSRX(Constants.baisserGratte);

View File

@ -4,13 +4,44 @@
package frc.robot.subsystems;
<<<<<<< HEAD
import edu.wpi.first.cameraserver.CameraServer;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
=======
import org.photonvision.PhotonCamera;
import org.photonvision.common.hardware.VisionLEDMode;
import edu.wpi.first.net.PortForwarder;
>>>>>>> b20ba544a81d82752f6f8e390de38cbcfdc79f08
import edu.wpi.first.wpilibj2.command.SubsystemBase;
public class Limelight extends SubsystemBase {
PhotonCamera limelight = new PhotonCamera("limelight");
/** Creates a new Limelight. */
public Limelight() {}
public Limelight() {
PortForwarder.add(5800, "photonvision.local", 5800);
}
public void cube() {
limelight.setLED(VisionLEDMode.kOff);
limelight.setPipelineIndex(3);
}
public void cone() {
limelight.setLED(VisionLEDMode.kOff);
limelight.setPipelineIndex(2);
}
public void apriltag() {
limelight.setLED(VisionLEDMode.kOff);
limelight.setPipelineIndex(0);
}
public void tape() {
limelight.setLED(VisionLEDMode.kOn);
limelight.setPipelineIndex(1);
}
@Override
public void periodic() {

View File

@ -8,6 +8,7 @@ package frc.robot.subsystems.bras;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
@ -15,6 +16,7 @@ public class BrasTelescopique extends SubsystemBase {
/** Creates a new BrasTelescopique. */
public BrasTelescopique() {}
final CANSparkMax Winch = new CANSparkMax(Constants.BrasTelescopique,MotorType.kBrushless);
private DigitalInput photocell = new DigitalInput(Constants.photocell);
public void AvanceRecule(double vitesse) {
Winch.set(vitesse);
}
@ -24,7 +26,9 @@ public class BrasTelescopique extends SubsystemBase {
public void Reset() {
Winch.getEncoder().setPosition(0);
}
public boolean photocell(){
return photocell.get();
}
@Override
public void periodic() {
// This method will be called once per scheduler run

View File

@ -4,14 +4,17 @@
package frc.robot.subsystems.bras;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
import static frc.robot.Constants.*;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
public class Pivot extends SubsystemBase {
// moteur
private CANSparkMax pivot = new CANSparkMax(actuateur, MotorType.kBrushless);
private CANSparkMax pivot = new CANSparkMax(Constants.pivot,MotorType.kBrushless);
private DigitalInput limitpivot = new DigitalInput(Constants.limitpivot);
// function
public void monteDescendre(double vitesse) {
@ -23,6 +26,10 @@ public class Pivot extends SubsystemBase {
}
public void Reset(){
pivot.getEncoder().setPosition(0);
}
public boolean limitpivot(){
return limitpivot.get();
}
@Override
public void periodic() {

41
vendordeps/photonlib.json Normal file
View File

@ -0,0 +1,41 @@
{
"fileName": "photonlib.json",
"name": "photonlib",
"version": "v2023.3.0",
"uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004 ",
"mavenUrls": [
"https://maven.photonvision.org/repository/internal",
"https://maven.photonvision.org/repository/snapshots"
],
"jsonUrl": "https://maven.photonvision.org/repository/internal/org/photonvision/PhotonLib-json/1.0/PhotonLib-json-1.0.json",
"jniDependencies": [],
"cppDependencies": [
{
"groupId": "org.photonvision",
"artifactId": "PhotonLib-cpp",
"version": "v2023.3.0",
"libName": "Photon",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxathena",
"linuxx86-64",
"osxuniversal"
]
}
],
"javaDependencies": [
{
"groupId": "org.photonvision",
"artifactId": "PhotonLib-java",
"version": "v2023.3.0"
},
{
"groupId": "org.photonvision",
"artifactId": "PhotonTargeting-java",
"version": "v2023.3.0"
}
]
}