Compare commits
44 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
41f6e4747f | ||
|
|
7908d4c5df | ||
|
|
2263961829 | ||
|
|
27ea9d96e3 | ||
|
|
01edf1cb01 | ||
|
|
0b4c0e09ff | ||
|
|
6c86b2ed5c | ||
|
|
6885b80d6a | ||
|
|
2472c67adf | ||
|
|
c8d0ee3a03 | ||
|
|
3300d74a78 | ||
|
|
bdffb48ece | ||
|
|
5f44d5304a | ||
|
|
9aa7018812 | ||
|
|
d98dc4e467 | ||
|
|
b0ad34519e | ||
|
|
7b734cc046 | ||
|
|
cdca0230a4 | ||
|
|
56b28100df | ||
|
|
db935eceda | ||
|
|
da28ff48db | ||
|
|
5b6e3ac7b2 | ||
|
|
9585c17bdb | ||
|
|
07eeaffa32 | ||
|
|
8202b012cb | ||
|
|
e5f7b05063 | ||
|
|
5916f4f141 | ||
| 4438560698 | |||
| b2d4647e41 | |||
| 75922f581c | |||
| a429b936d2 | |||
|
|
3b06cbd447 | ||
|
|
7b535a845f | ||
|
|
42e35fca8a | ||
|
|
272f89962a | ||
|
|
52c72e9a61 | ||
|
|
4d1b353e25 | ||
|
|
9d09af20b0 | ||
|
|
ae9a6bd046 | ||
|
|
10b0110315 | ||
| 098f16665a | |||
| 1240160ed7 | |||
| 4068016d36 | |||
|
|
6afc342006 |
@@ -33,7 +33,7 @@ deploy {
|
||||
frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) {
|
||||
files = project.fileTree('src/main/deploy')
|
||||
directory = '/home/lvuser/deploy'
|
||||
deleteOldFiles = true // Change to true to delete files on roboRIO that no
|
||||
deleteOldFiles = false // Change to true to delete files on roboRIO that no
|
||||
// longer exist in deploy directory of this project
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1,4 +1,9 @@
|
||||
{
|
||||
"System Joysticks": {
|
||||
"window": {
|
||||
"enabled": false
|
||||
}
|
||||
},
|
||||
"keyboardJoysticks": [
|
||||
{
|
||||
"axisConfig": [
|
||||
|
||||
@@ -14,6 +14,12 @@
|
||||
"type": "deadline",
|
||||
"data": {
|
||||
"commands": [
|
||||
{
|
||||
"type": "wait",
|
||||
"data": {
|
||||
"waitTime": 3.0
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "path",
|
||||
"data": {
|
||||
@@ -36,21 +42,22 @@
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"type": "deadline",
|
||||
"data": {
|
||||
"name": "Limelighter"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "Lancer"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "TournerAZero"
|
||||
"commands": [
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "Lancer"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "Aspirer"
|
||||
}
|
||||
}
|
||||
]
|
||||
}
|
||||
},
|
||||
{
|
||||
@@ -72,9 +79,9 @@
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "path",
|
||||
"type": "named",
|
||||
"data": {
|
||||
"pathName": "MonterReservoir"
|
||||
"name": "gauche"
|
||||
}
|
||||
},
|
||||
{
|
||||
@@ -35,12 +35,6 @@
|
||||
"pathName": "Tir"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "Limelighter"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
|
||||
@@ -14,6 +14,12 @@
|
||||
"type": "deadline",
|
||||
"data": {
|
||||
"commands": [
|
||||
{
|
||||
"type": "wait",
|
||||
"data": {
|
||||
"waitTime": 3.0
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "path",
|
||||
"data": {
|
||||
@@ -36,21 +42,22 @@
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"type": "deadline",
|
||||
"data": {
|
||||
"name": "Limelighter"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "Lancer"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "TournerA180"
|
||||
"commands": [
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "Lancer"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "Aspirer"
|
||||
}
|
||||
}
|
||||
]
|
||||
}
|
||||
},
|
||||
{
|
||||
@@ -72,9 +79,9 @@
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "path",
|
||||
"type": "named",
|
||||
"data": {
|
||||
"pathName": "MonterMur"
|
||||
"name": "droite"
|
||||
}
|
||||
},
|
||||
{
|
||||
|
||||
@@ -1,37 +0,0 @@
|
||||
{
|
||||
"version": "2025.0",
|
||||
"command": {
|
||||
"type": "sequential",
|
||||
"data": {
|
||||
"commands": [
|
||||
{
|
||||
"type": "path",
|
||||
"data": {
|
||||
"pathName": "TirerSimple"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "DescendreBalayeuse"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "Limelighter"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "Lancer"
|
||||
}
|
||||
}
|
||||
]
|
||||
}
|
||||
},
|
||||
"resetOdom": true,
|
||||
"folder": null,
|
||||
"choreoAuto": false
|
||||
}
|
||||
68
src/main/deploy/pathplanner/autos/Tirgrimpe.auto
Normal file
68
src/main/deploy/pathplanner/autos/Tirgrimpe.auto
Normal file
@@ -0,0 +1,68 @@
|
||||
{
|
||||
"version": "2025.0",
|
||||
"command": {
|
||||
"type": "sequential",
|
||||
"data": {
|
||||
"commands": [
|
||||
{
|
||||
"type": "path",
|
||||
"data": {
|
||||
"pathName": "tirgrimpe1"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "DescendreBalayeuse"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "deadline",
|
||||
"data": {
|
||||
"commands": [
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "Lancer"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "Aspirer"
|
||||
}
|
||||
}
|
||||
]
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "GrimperReservoir"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "MonterGrimpeur"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "gauche"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "DescendreGrimpeur"
|
||||
}
|
||||
}
|
||||
]
|
||||
}
|
||||
},
|
||||
"resetOdom": true,
|
||||
"folder": null,
|
||||
"choreoAuto": false
|
||||
}
|
||||
@@ -16,11 +16,11 @@
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 0.4938659058487873,
|
||||
"x": 0.23509272467902986,
|
||||
"y": 5.917574893009986
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 1.0372895863052785,
|
||||
"x": 0.778516405135521,
|
||||
"y": 5.930513552068473
|
||||
},
|
||||
"nextControl": null,
|
||||
|
||||
@@ -3,25 +3,25 @@
|
||||
"waypoints": [
|
||||
{
|
||||
"anchor": {
|
||||
"x": 2.4476034236804565,
|
||||
"y": 4.85660485021398
|
||||
"x": 1.878,
|
||||
"y": 5.154
|
||||
},
|
||||
"prevControl": null,
|
||||
"nextControl": {
|
||||
"x": 1.6971611982881591,
|
||||
"y": 4.85660485021398
|
||||
"x": 1.1275577746077026,
|
||||
"y": 5.154
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 1.0761055634807417,
|
||||
"y": 4.85660485021398
|
||||
"x": 1.0372895863052778,
|
||||
"y": 5.011868758915835
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 1.503081312410841,
|
||||
"y": 4.869543509272469
|
||||
"x": 1.4642653352353772,
|
||||
"y": 5.024807417974324
|
||||
},
|
||||
"nextControl": null,
|
||||
"isLocked": false,
|
||||
|
||||
@@ -3,25 +3,25 @@
|
||||
"waypoints": [
|
||||
{
|
||||
"anchor": {
|
||||
"x": 2.4476034236804565,
|
||||
"y": 4.85660485021398
|
||||
"x": 1.878,
|
||||
"y": 5.154
|
||||
},
|
||||
"prevControl": null,
|
||||
"nextControl": {
|
||||
"x": 2.3958487874465044,
|
||||
"y": 2.695848787446506
|
||||
"x": 1.8262453637660478,
|
||||
"y": 2.993243937232526
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 1.0502282453637657,
|
||||
"y": 2.4758915834522113
|
||||
"x": 2.0076890156918683,
|
||||
"y": 2.2041797432239663
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 2.292339514978602,
|
||||
"y": 2.3982596291012843
|
||||
"x": 3.2498002853067054,
|
||||
"y": 2.1265477888730393
|
||||
},
|
||||
"nextControl": null,
|
||||
"isLocked": false,
|
||||
@@ -42,7 +42,7 @@
|
||||
},
|
||||
"goalEndState": {
|
||||
"velocity": 0,
|
||||
"rotation": 0.0
|
||||
"rotation": 32.10625595511781
|
||||
},
|
||||
"reversed": false,
|
||||
"folder": null,
|
||||
|
||||
@@ -3,25 +3,25 @@
|
||||
"waypoints": [
|
||||
{
|
||||
"anchor": {
|
||||
"x": 1.0502282453637657,
|
||||
"y": 2.4758915834522113
|
||||
"x": 1.0,
|
||||
"y": 2.6
|
||||
},
|
||||
"prevControl": null,
|
||||
"nextControl": {
|
||||
"x": 1.0408884389937225,
|
||||
"y": 2.742159765250622
|
||||
"x": 0.9906601936299568,
|
||||
"y": 2.866268181798411
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 1.0502282453637657,
|
||||
"y": 2.7734807417974334
|
||||
"x": 1.0,
|
||||
"y": 2.9
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 1.0547546338516156,
|
||||
"y": 2.523521721541598
|
||||
"x": 1.00452638848785,
|
||||
"y": 2.6500409797441646
|
||||
},
|
||||
"nextControl": null,
|
||||
"isLocked": false,
|
||||
|
||||
@@ -3,25 +3,25 @@
|
||||
"waypoints": [
|
||||
{
|
||||
"anchor": {
|
||||
"x": 0.5197432239657629,
|
||||
"y": 5.930513552068473
|
||||
"x": 0.29978601997146925,
|
||||
"y": 5.917574893009986
|
||||
},
|
||||
"prevControl": null,
|
||||
"nextControl": {
|
||||
"x": 1.6971611982881594,
|
||||
"y": 5.995206847360913
|
||||
"x": 1.4772039942938657,
|
||||
"y": 5.982268188302426
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 2.4476034236804565,
|
||||
"y": 4.85660485021398
|
||||
"x": 1.8783024251069897,
|
||||
"y": 5.154194008559203
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 2.382910128388017,
|
||||
"y": 5.400028530670471
|
||||
"x": 1.8136091298145502,
|
||||
"y": 5.6976176890156935
|
||||
},
|
||||
"nextControl": null,
|
||||
"isLocked": false,
|
||||
|
||||
54
src/main/deploy/pathplanner/paths/tirgrimpe1.path
Normal file
54
src/main/deploy/pathplanner/paths/tirgrimpe1.path
Normal file
@@ -0,0 +1,54 @@
|
||||
{
|
||||
"version": "2025.0",
|
||||
"waypoints": [
|
||||
{
|
||||
"anchor": {
|
||||
"x": 3.5991440798858774,
|
||||
"y": 2.3465049928673327
|
||||
},
|
||||
"prevControl": null,
|
||||
"nextControl": {
|
||||
"x": 2.589928673323822,
|
||||
"y": 1.7513266761768898
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 1.8783024251069897,
|
||||
"y": 2.3465049928673327
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 2.706376604850214,
|
||||
"y": 1.7125106990014274
|
||||
},
|
||||
"nextControl": null,
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
}
|
||||
],
|
||||
"rotationTargets": [],
|
||||
"constraintZones": [],
|
||||
"pointTowardsZones": [],
|
||||
"eventMarkers": [],
|
||||
"globalConstraints": {
|
||||
"maxVelocity": 3.0,
|
||||
"maxAcceleration": 3.0,
|
||||
"maxAngularVelocity": 540.0,
|
||||
"maxAngularAcceleration": 720.0,
|
||||
"nominalVoltage": 12.0,
|
||||
"unlimited": false
|
||||
},
|
||||
"goalEndState": {
|
||||
"velocity": 0,
|
||||
"rotation": 33.11134196037204
|
||||
},
|
||||
"reversed": false,
|
||||
"folder": null,
|
||||
"idealStartingState": {
|
||||
"velocity": 0,
|
||||
"rotation": 180.0
|
||||
},
|
||||
"useDefaultConstraints": true
|
||||
}
|
||||
@@ -1,67 +0,0 @@
|
||||
package frc.robot;
|
||||
|
||||
import java.util.function.Supplier;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Commands;
|
||||
import frc.robot.subsystems.Balayeuse;
|
||||
import frc.robot.subsystems.CommandSwerveDrivetrain;
|
||||
import frc.robot.subsystems.Demeleur;
|
||||
import frc.robot.subsystems.Grimpeur;
|
||||
import frc.robot.subsystems.Lanceur;
|
||||
import frc.robot.subsystems.PivotBalayeuse;
|
||||
|
||||
public class Commandes {
|
||||
|
||||
private final CommandSwerveDrivetrain drivetrain;
|
||||
private final Lanceur lanceur;
|
||||
private final Demeleur demeleur;
|
||||
private final Balayeuse balayeuse;
|
||||
private final Grimpeur grimpeur;
|
||||
private final PivotBalayeuse pivotBalayeuse;
|
||||
|
||||
public Commandes(CommandSwerveDrivetrain drivetrain,
|
||||
Lanceur lanceur,
|
||||
Demeleur demeleur,
|
||||
Balayeuse balayeuse,
|
||||
Grimpeur grimpeur,
|
||||
PivotBalayeuse pivotBalayeuse) {
|
||||
this.drivetrain = drivetrain;
|
||||
this.lanceur = lanceur;
|
||||
this.demeleur = demeleur;
|
||||
this.balayeuse = balayeuse;
|
||||
this.grimpeur = grimpeur;
|
||||
this.pivotBalayeuse = pivotBalayeuse;
|
||||
}
|
||||
|
||||
public double vitesseLanceur() {
|
||||
return Coordinates.diffFromHub(drivetrain.getState().Pose.getTranslation()).getNorm() * 410.57 + 2250;
|
||||
}
|
||||
|
||||
public Command viserLancer() {
|
||||
return viserLancer(() -> 0.0, () -> 0.0);
|
||||
}
|
||||
|
||||
public Command viserLancer(Supplier<Double> vitesseX, Supplier<Double> vitesseY) {
|
||||
return Commands.parallel(
|
||||
drivetrain.viserReservoir(vitesseX, vitesseY),
|
||||
this.lancer());
|
||||
}
|
||||
|
||||
public Command lancer() {
|
||||
return lancer(this::vitesseLanceur);
|
||||
}
|
||||
|
||||
public Command lancer(Supplier<Double> vitesse) {
|
||||
return Commands.parallel(
|
||||
lanceur.lancer(vitesse),
|
||||
Commands.waitUntil(lanceur::setPointAtteint).andThen(demeleur.run()));
|
||||
}
|
||||
|
||||
public Command lancerAspirer() {
|
||||
return Commands.parallel(
|
||||
this.lancer(),
|
||||
balayeuse.aspirer());
|
||||
}
|
||||
|
||||
}
|
||||
@@ -1,41 +0,0 @@
|
||||
package frc.robot;
|
||||
|
||||
import static edu.wpi.first.units.Units.Meters;
|
||||
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
||||
|
||||
public final class Coordinates {
|
||||
public static final Translation2d kRedHub = new Translation2d(Meters.of(16.5 - 4.6), Meters.of(4.03));
|
||||
public static final Translation2d kBlueHub = new Translation2d(Meters.of(4.6), Meters.of(4.03));
|
||||
|
||||
public static final Translation2d kGrimpeDepotRouge = new Translation2d(Meters.of(16.5 - 1.1), Meters.of(4.9));
|
||||
public static final Translation2d kGrimpeMurRouge = new Translation2d(Meters.of(16.5 - 1.1), Meters.of(3.7));
|
||||
public static final Translation2d kGrimpeDepotBleu = new Translation2d(Meters.of(1.1), Meters.of(3.1));
|
||||
public static final Translation2d kGrimpeMurBleu = new Translation2d(Meters.of(1.1), Meters.of(4.4));
|
||||
|
||||
public static Translation2d diffFromHub(Translation2d robotTranslation) {
|
||||
if (DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Blue) {
|
||||
return kBlueHub.minus(robotTranslation);
|
||||
} else {
|
||||
return kRedHub.minus(robotTranslation);
|
||||
}
|
||||
}
|
||||
|
||||
public static Translation2d diffFromGrimpeMur(Translation2d robotTranslation) {
|
||||
if (DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Blue) {
|
||||
return kGrimpeMurBleu.minus(robotTranslation);
|
||||
} else {
|
||||
return kGrimpeMurRouge.minus(robotTranslation);
|
||||
}
|
||||
}
|
||||
|
||||
public static Translation2d diffFromGrimpeDepot(Translation2d robotTranslation) {
|
||||
if (DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Blue) {
|
||||
return kGrimpeDepotBleu.minus(robotTranslation);
|
||||
} else {
|
||||
return kGrimpeDepotRouge.minus(robotTranslation);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,75 +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;
|
||||
|
||||
import edu.wpi.first.net.PortForwarder;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
|
||||
public class LimeLight3 {
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-balaie");
|
||||
NetworkTableEntry pipeline = table.getEntry("pipeline");
|
||||
|
||||
/** Creates a new LimeLight3. */
|
||||
public LimeLight3() {
|
||||
for (int port = 5800; port <= 5807; port++) {
|
||||
PortForwarder.add(port, "limelight.local", port);
|
||||
}
|
||||
}
|
||||
|
||||
public double[] getBotPoseBlue() {
|
||||
NetworkTable limelightTable = NetworkTableInstance.getDefault().getTable("limelight-balaie");
|
||||
NetworkTableEntry BotPoseEntry = limelightTable.getEntry("botpose_orb_wpiblue");
|
||||
double[] BotPose = BotPoseEntry.getDoubleArray(new double[7]);
|
||||
return BotPose;
|
||||
}
|
||||
|
||||
public double[] getBotPoseRed() {
|
||||
NetworkTable limelightTable = NetworkTableInstance.getDefault().getTable("limelight-balaie");
|
||||
NetworkTableEntry BotPoseEntry = limelightTable.getEntry("botpose_orb_wpired");
|
||||
double[] BotPose = BotPoseEntry.getDoubleArray(new double[7]);
|
||||
return BotPose;
|
||||
}
|
||||
|
||||
public double getTx() {
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-balaie");
|
||||
NetworkTableEntry tx = table.getEntry("tx");
|
||||
return tx.getDouble(0.0);
|
||||
}
|
||||
|
||||
public double getTId() {
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-balaie");
|
||||
NetworkTableEntry tid = table.getEntry("tid");
|
||||
return tid.getDouble(0.0);
|
||||
}
|
||||
|
||||
public double getTA() {
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-balaie");
|
||||
NetworkTableEntry ta = table.getEntry("ta");
|
||||
return ta.getDouble(0.0);
|
||||
}
|
||||
|
||||
public boolean getV() {
|
||||
return LimelightHelpers.getTV("limelight-balaie");
|
||||
}
|
||||
|
||||
public void AprilTag() {
|
||||
pipeline.setNumber(0);
|
||||
}
|
||||
|
||||
public void Forme() {
|
||||
pipeline.setNumber(1);
|
||||
}
|
||||
|
||||
public double Calcule(double x1, double x2, double y1, double y2, double angle) {
|
||||
if (x1 > 4) {
|
||||
return (Math.abs(Math.atan2(x2 - x1, y2 - y1)) * (180 / Math.PI) - angle) / 90;
|
||||
} else {
|
||||
return (Math.abs(Math.atan2(x2 - x1, y2 - y1)) * (180 / Math.PI) + angle) * -1 / 90;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
@@ -1,74 +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;
|
||||
|
||||
import edu.wpi.first.net.PortForwarder;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
|
||||
public class Limelight3G {
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-tag");
|
||||
NetworkTableEntry pipeline = table.getEntry("pipeline");
|
||||
|
||||
/** Creates a new LimeLight3. */
|
||||
public Limelight3G() {
|
||||
for (int port = 5800; port <= 5807; port++) {
|
||||
PortForwarder.add(port, "limelight.local", port);
|
||||
}
|
||||
}
|
||||
|
||||
public double[] getBotPoseBlue() {
|
||||
NetworkTable limelightTable = NetworkTableInstance.getDefault().getTable("limelight-tag");
|
||||
NetworkTableEntry BotPoseEntry = limelightTable.getEntry("botpose_wpiblue");
|
||||
double[] BotPose = BotPoseEntry.getDoubleArray(new double[7]);
|
||||
return BotPose;
|
||||
}
|
||||
|
||||
public double[] getBotPoseRed() {
|
||||
NetworkTable limelightTable = NetworkTableInstance.getDefault().getTable("limelight-tag");
|
||||
NetworkTableEntry BotPoseEntry = limelightTable.getEntry("botpose_wpired");
|
||||
double[] BotPose = BotPoseEntry.getDoubleArray(new double[7]);
|
||||
return BotPose;
|
||||
}
|
||||
|
||||
public double getTx() {
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-tag");
|
||||
NetworkTableEntry tx = table.getEntry("tx");
|
||||
return tx.getDouble(0.0);
|
||||
}
|
||||
|
||||
public double getTId() {
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-tag");
|
||||
NetworkTableEntry tid = table.getEntry("tid");
|
||||
return tid.getDouble(0.0);
|
||||
}
|
||||
|
||||
public double getTA() {
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-tag");
|
||||
NetworkTableEntry ta = table.getEntry("ta");
|
||||
return ta.getDouble(0.0);
|
||||
}
|
||||
|
||||
public boolean getV() {
|
||||
return LimelightHelpers.getTV("limelight-tag");
|
||||
}
|
||||
|
||||
public double Calcule(double x1, double x2, double y1, double y2, double angle) {
|
||||
if (x1 > x2) {
|
||||
if (y1 > y2) {
|
||||
return Math.atan(90 - ((x2 - x1) / (y2 - y1))) * (180 / Math.PI) - angle;
|
||||
} else {
|
||||
return Math.atan((x2 - x1) / (y2 - y1)) * (180 / Math.PI) + 90 - angle;
|
||||
}
|
||||
} else {
|
||||
if (y1 > y2) {
|
||||
return Math.atan(90 - ((x2 - x1) / (y2 - y1))) * (180 / Math.PI) + 270 - angle;
|
||||
} else {
|
||||
return Math.atan((x2 - x1) / (y2 - y1)) * (180 / Math.PI) + 180 - angle;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -4,7 +4,6 @@
|
||||
|
||||
package frc.robot;
|
||||
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
@@ -28,28 +27,19 @@ public class Robot extends TimedRobot {
|
||||
|
||||
LimelightHelpers.SetRobotOrientation("limelight_tag", headingDeg, 0, 0, 0, 0, 0);
|
||||
var llMeasurement = LimelightHelpers.getBotPoseEstimate_wpiBlue_MegaTag2("limelight_tag");
|
||||
var stdDevs = LimelightHelpers.getLimelightDoubleArrayEntry("limelight_tag", "stddevs");
|
||||
var limelightStdDevs = VecBuilder.fill(.5, .5, 9999999);
|
||||
if (stdDevs.exists()) {
|
||||
limelightStdDevs = VecBuilder.fill(stdDevs.get()[6], stdDevs.get()[7], stdDevs.get()[12]);
|
||||
}
|
||||
if (llMeasurement != null && llMeasurement.tagCount > 0 && Math.abs(omegaRps) < 2.0) {
|
||||
m_robotContainer.drivetrain.addVisionMeasurement(llMeasurement.pose, llMeasurement.timestampSeconds,
|
||||
limelightStdDevs);
|
||||
m_robotContainer.drivetrain.addVisionMeasurement(llMeasurement.pose, llMeasurement.timestampSeconds);
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void disabledInit() {
|
||||
}
|
||||
public void disabledInit() {}
|
||||
|
||||
@Override
|
||||
public void disabledPeriodic() {
|
||||
}
|
||||
public void disabledPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void disabledExit() {
|
||||
}
|
||||
public void disabledExit() {}
|
||||
|
||||
@Override
|
||||
public void autonomousInit() {
|
||||
@@ -61,12 +51,10 @@ public class Robot extends TimedRobot {
|
||||
}
|
||||
|
||||
@Override
|
||||
public void autonomousPeriodic() {
|
||||
}
|
||||
public void autonomousPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void autonomousExit() {
|
||||
}
|
||||
public void autonomousExit() {}
|
||||
|
||||
@Override
|
||||
public void teleopInit() {
|
||||
@@ -76,12 +64,10 @@ public class Robot extends TimedRobot {
|
||||
}
|
||||
|
||||
@Override
|
||||
public void teleopPeriodic() {
|
||||
}
|
||||
public void teleopPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void teleopExit() {
|
||||
}
|
||||
public void teleopExit() {}
|
||||
|
||||
@Override
|
||||
public void testInit() {
|
||||
@@ -89,10 +75,8 @@ public class Robot extends TimedRobot {
|
||||
}
|
||||
|
||||
@Override
|
||||
public void testPeriodic() {
|
||||
}
|
||||
public void testPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void testExit() {
|
||||
}
|
||||
public void testExit() {}
|
||||
}
|
||||
|
||||
@@ -4,9 +4,7 @@
|
||||
|
||||
package frc.robot;
|
||||
|
||||
import static edu.wpi.first.units.Units.MetersPerSecond;
|
||||
import static edu.wpi.first.units.Units.RadiansPerSecond;
|
||||
import static edu.wpi.first.units.Units.RotationsPerSecond;
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
|
||||
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
|
||||
import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||
@@ -14,11 +12,32 @@ import com.pathplanner.lib.auto.AutoBuilder;
|
||||
import com.pathplanner.lib.auto.NamedCommands;
|
||||
|
||||
import edu.wpi.first.cameraserver.CameraServer;
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Commands;
|
||||
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
||||
import frc.robot.commands.Aspirer;
|
||||
import frc.robot.commands.DescendreBalyeuse;
|
||||
import frc.robot.commands.DescendreGrimpeur;
|
||||
import frc.robot.commands.DescendreGrimpeurPlus;
|
||||
import frc.robot.commands.Inverser;
|
||||
import frc.robot.commands.Lancer;
|
||||
import frc.robot.commands.LancerAspirer;
|
||||
import frc.robot.commands.LancerBaseVitesse;
|
||||
import frc.robot.commands.Limelighter;
|
||||
import frc.robot.commands.ModeOposer;
|
||||
import frc.robot.commands.ModeOposerBalayeuse;
|
||||
import frc.robot.commands.ModeOposerDemeleur;
|
||||
import frc.robot.commands.MonterBalyeuse;
|
||||
import frc.robot.commands.MonterGrimpeur;
|
||||
import frc.robot.commands.ModeAuto.AspirerAuto;
|
||||
import frc.robot.commands.ModeAuto.BougerDroiteAuto;
|
||||
import frc.robot.commands.ModeAuto.BougerGaucheAuto;
|
||||
import frc.robot.commands.ModeAuto.GrimperMur;
|
||||
import frc.robot.commands.ModeAuto.GrimperReservoir;
|
||||
import frc.robot.commands.ModeAuto.LancerAuto;
|
||||
import frc.robot.commands.ModeAuto.LimelighterAuto;
|
||||
import frc.robot.commands.ModeAuto.RetourMilieuDroite;
|
||||
import frc.robot.commands.ModeAuto.RetourMilieuGauche;
|
||||
import frc.robot.commands.ModeAuto.TournerVersMur;
|
||||
@@ -26,50 +45,48 @@ import frc.robot.commands.ModeAuto.TournerVersReservoir;
|
||||
import frc.robot.generated.TunerConstants;
|
||||
import frc.robot.subsystems.Balayeuse;
|
||||
import frc.robot.subsystems.CommandSwerveDrivetrain;
|
||||
import frc.robot.subsystems.Demeleur;
|
||||
import frc.robot.subsystems.Grimpeur;
|
||||
//import frc.robot.subsystems.LEDSubsystem;
|
||||
import frc.robot.subsystems.Lanceur;
|
||||
import frc.robot.subsystems.Led;
|
||||
import frc.robot.subsystems.PivotBalayeuse;
|
||||
import frc.robot.subsystems.LimeLight3;
|
||||
import frc.robot.subsystems.Limelight3G;
|
||||
|
||||
public class RobotContainer {
|
||||
private final SendableChooser<Command> autoChooser;
|
||||
public final CommandSwerveDrivetrain drivetrain = TunerConstants.createDrivetrain();
|
||||
private final Balayeuse balayeuse = new Balayeuse();
|
||||
private final PivotBalayeuse pivotBalayeuse = new PivotBalayeuse();
|
||||
private final Demeleur demeleur = new Demeleur();
|
||||
private final Grimpeur grimpeur = new Grimpeur();
|
||||
private final Lanceur lanceur = new Lanceur();
|
||||
private final Commandes commandes = new Commandes(drivetrain, lanceur, demeleur, balayeuse, grimpeur, pivotBalayeuse);
|
||||
private final LimeLight3 limeLight3 = new LimeLight3();
|
||||
private final Limelight3G limeLight3G = new Limelight3G();
|
||||
private final Led led = new Led();
|
||||
private final CommandXboxController manette = new CommandXboxController(0);
|
||||
private final CommandXboxController manette1 = new CommandXboxController(1);
|
||||
Balayeuse balayeuse = new Balayeuse();
|
||||
Grimpeur grimpeur = new Grimpeur();
|
||||
Lanceur lanceur = new Lanceur();
|
||||
LimeLight3 limeLight3 = new LimeLight3();
|
||||
Limelight3G limeLight3G = new Limelight3G();
|
||||
//LEDSubsystem ledSubsystem = new LEDSubsystem();
|
||||
CommandXboxController manette = new CommandXboxController(0);
|
||||
CommandXboxController manette1 = new CommandXboxController(1);
|
||||
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond); // kSpeedAt12Volts desired top speed
|
||||
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond); // 3/4 of a rotation per second max
|
||||
// angular velocity
|
||||
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond); // 3/4 of a rotation per second max angular velocity
|
||||
|
||||
/* Setting up bindings for necessary control of the swerve drive platform */
|
||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1) // Add a 10% deadband
|
||||
.withDriveRequestType(DriveRequestType.OpenLoopVoltage); // Use open-loop control for drive motors
|
||||
/* Setting up bindings for necessary control of the swerve drive platform */
|
||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1) // Add a 10% deadband
|
||||
.withDriveRequestType(DriveRequestType.OpenLoopVoltage); // Use open-loop control for drive motors
|
||||
|
||||
public final CommandSwerveDrivetrain drivetrain = TunerConstants.createDrivetrain();
|
||||
|
||||
private final Telemetry logger = new Telemetry(MaxSpeed);
|
||||
|
||||
public RobotContainer() {
|
||||
NamedCommands.registerCommand("GrimperMur", drivetrain.allerGrimpeMur());
|
||||
NamedCommands.registerCommand("GrimperReservoir", drivetrain.allerGrimpeDepot());
|
||||
NamedCommands.registerCommand("Lancer", commandes.lancer());
|
||||
NamedCommands.registerCommand("RetourMilieuDroite", new RetourMilieuDroite(drivetrain, limeLight3G));
|
||||
NamedCommands.registerCommand("droite", new BougerDroiteAuto(drivetrain));
|
||||
NamedCommands.registerCommand("gauche", new BougerGaucheAuto(drivetrain));
|
||||
NamedCommands.registerCommand("GrimperMur", new GrimperMur(limeLight3,drivetrain));
|
||||
NamedCommands.registerCommand("GrimperReservoir", new GrimperReservoir(limeLight3G,drivetrain));
|
||||
NamedCommands.registerCommand("Lancer", new LancerAuto(lanceur, limeLight3G));
|
||||
NamedCommands.registerCommand("RetourMilieuDroite", new RetourMilieuDroite(drivetrain,limeLight3G));
|
||||
NamedCommands.registerCommand("RetourMilieuGauche", new RetourMilieuGauche(drivetrain, limeLight3G));
|
||||
NamedCommands.registerCommand("Limelighter", commandes.viserLancer());
|
||||
NamedCommands.registerCommand("DescendreBalayeuse", pivotBalayeuse.descendre());
|
||||
NamedCommands.registerCommand("Aspirer", balayeuse.aspirer());
|
||||
NamedCommands.registerCommand("Limelighter", new LimelighterAuto(limeLight3G,drivetrain));
|
||||
NamedCommands.registerCommand("DescendreBalayeuse", new DescendreBalyeuse(balayeuse));
|
||||
NamedCommands.registerCommand("Aspirer", new AspirerAuto(balayeuse));
|
||||
NamedCommands.registerCommand("TournerA180", new TournerVersReservoir(drivetrain));
|
||||
NamedCommands.registerCommand("TournerAZero", new TournerVersMur(drivetrain));
|
||||
NamedCommands.registerCommand("MonterGrimpeur", grimpeur.sortir());
|
||||
NamedCommands.registerCommand("DescendreGrimpeur", grimpeur.rentrer());
|
||||
NamedCommands.registerCommand("MonterGrimpeur", new MonterGrimpeur(grimpeur));
|
||||
NamedCommands.registerCommand("DescendreGrimpeur", new DescendreGrimpeur(grimpeur));
|
||||
autoChooser = AutoBuilder.buildAutoChooser();
|
||||
SmartDashboard.putData("Auto Chooser", autoChooser);
|
||||
|
||||
@@ -79,36 +96,43 @@ public class RobotContainer {
|
||||
}
|
||||
|
||||
private void configureBindings() {
|
||||
|
||||
// Manette 0 (pilote)
|
||||
//ledSubsystem.setDefaultCommand(ledSubsystem.updateLEDs());
|
||||
drivetrain.setDefaultCommand(
|
||||
drivetrain.applyRequest(() -> drive
|
||||
.withVelocityY(-manette.getLeftX() * MaxSpeed * 0.7)
|
||||
.withVelocityX(-manette.getLeftY() * MaxSpeed * 0.7)
|
||||
.withRotationalRate(-manette.getRightX() * MaxAngularRate)));
|
||||
manette.rightBumper().whileTrue(balayeuse.aspirer());
|
||||
manette.povUp().whileTrue(grimpeur.sortir());
|
||||
manette.povDown().whileTrue(grimpeur.rentrer());
|
||||
drivetrain.applyRequest(() ->
|
||||
drive.withVelocityY(MathUtil.applyDeadband(-manette.getLeftX()*Math.abs(-manette.getLeftX())*MaxSpeed*0.7, 0.05))
|
||||
.withVelocityX(MathUtil.applyDeadband(-manette.getLeftY()*Math.abs(-manette.getLeftY())*MaxSpeed*0.7, 0.05))
|
||||
.withRotationalRate(MathUtil.applyDeadband(-manette.getRightX()*Math.abs(-manette.getRightX())*MaxAngularRate*1.5, 0.05))
|
||||
)
|
||||
);
|
||||
//manette 1
|
||||
// manette1.povUp().whileTrue(drivetrain.sysIdQuasistatic(SysIdRoutine.Direction.kForward));
|
||||
// manette1.povDown().whileTrue(drivetrain.sysIdQuasistatic(SysIdRoutine.Direction.kReverse));
|
||||
// manette1.povRight().whileTrue(drivetrain.sysIdDynamic(SysIdRoutine.Direction.kForward));
|
||||
// manette1.povLeft().whileTrue(drivetrain.sysIdDynamic(SysIdRoutine.Direction.kReverse));
|
||||
|
||||
manette.rightTrigger().whileTrue(commandes.lancer());
|
||||
manette.leftTrigger().whileTrue(
|
||||
commandes.viserLancer(() -> -manette.getLeftY() * MaxSpeed * 0.7, () -> -manette.getLeftX() * MaxSpeed * 0.7));
|
||||
manette.leftBumper().whileTrue(pivotBalayeuse.descendre());
|
||||
manette.b().whileTrue(drivetrain.allerGrimpeDepot());
|
||||
manette.x().whileTrue(drivetrain.allerGrimpeMur());
|
||||
manette.povUp().whileTrue(new MonterGrimpeur(grimpeur));
|
||||
manette.povDown().whileTrue(new DescendreGrimpeurPlus(grimpeur));
|
||||
manette.rightTrigger().whileTrue(new Lancer(lanceur, limeLight3G));
|
||||
manette.leftTrigger().whileTrue(new Limelighter(limeLight3G, drivetrain));
|
||||
manette.leftBumper().whileTrue(new DescendreBalyeuse(balayeuse));
|
||||
manette.rightBumper().whileTrue(new Aspirer(balayeuse));
|
||||
manette.b().whileTrue(new GrimperReservoir(limeLight3G, drivetrain));
|
||||
manette.x().whileTrue(new GrimperMur(limeLight3, drivetrain));
|
||||
|
||||
// Manette 1 (co-pilote)
|
||||
manette1.rightTrigger().whileTrue(balayeuse.aspirer());
|
||||
|
||||
manette1.rightBumper().whileTrue(pivotBalayeuse.monter());
|
||||
manette1.leftTrigger().whileTrue(commandes.lancer(() -> lanceur.ntBasseVitesse()));
|
||||
manette1.leftBumper().whileTrue(pivotBalayeuse.descendre());
|
||||
manette1.x().whileTrue(commandes.lancerAspirer());
|
||||
manette1.b().whileTrue(Commands.parallel(lanceur.inverse(), demeleur.inverse()));
|
||||
manette1.a().whileTrue(demeleur.inverse());
|
||||
manette1.y().whileTrue(balayeuse.ejecter());
|
||||
|
||||
drivetrain.registerTelemetry(logger::telemeterize);
|
||||
//manette 2
|
||||
manette1.rightTrigger().whileTrue(new Aspirer(balayeuse));
|
||||
manette1.rightBumper().whileTrue(new MonterBalyeuse(balayeuse));
|
||||
manette1.leftTrigger().whileTrue(new LancerBaseVitesse(lanceur));
|
||||
manette1.leftBumper().whileTrue(new DescendreBalyeuse(balayeuse));
|
||||
manette1.x().whileTrue(new LancerAspirer(lanceur, balayeuse, limeLight3G));
|
||||
manette1.b().whileTrue(new ModeOposer(lanceur));
|
||||
manette1.a().whileTrue(new ModeOposerDemeleur(lanceur));
|
||||
manette1.y().whileTrue(new ModeOposerBalayeuse(balayeuse));
|
||||
manette1.povRight().whileTrue(new BougerDroiteAuto(drivetrain));
|
||||
manette1.povLeft().whileTrue(new BougerGaucheAuto(drivetrain));
|
||||
manette1.povDown().whileTrue(new DescendreGrimpeur(grimpeur));
|
||||
manette1.start().whileTrue(new Inverser(drivetrain));
|
||||
}
|
||||
|
||||
public Command getAutonomousCommand() {
|
||||
|
||||
44
src/main/java/frc/robot/commands/Aspirer.java
Normal file
44
src/main/java/frc/robot/commands/Aspirer.java
Normal file
@@ -0,0 +1,44 @@
|
||||
// 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.Balayeuse;
|
||||
|
||||
/* 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 Aspirer extends Command {
|
||||
private Balayeuse balayeuse;
|
||||
/** Creates a new Aspirer. */
|
||||
public Aspirer(Balayeuse balayeuse) {
|
||||
this.balayeuse = balayeuse;
|
||||
addRequirements(balayeuse);
|
||||
// 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() {
|
||||
balayeuse.BalayerEnbas(-0.5);
|
||||
balayeuse.BalayerPadle(-0.2);
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
balayeuse.BalayerEnbas(0);
|
||||
balayeuse.BalayerPadle(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
46
src/main/java/frc/robot/commands/DescendreBalyeuse.java
Normal file
46
src/main/java/frc/robot/commands/DescendreBalyeuse.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.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.subsystems.Balayeuse;
|
||||
|
||||
/* 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 DescendreBalyeuse extends Command {
|
||||
private Balayeuse balayeuse;
|
||||
/** Creates a new Descendre. */
|
||||
public DescendreBalyeuse(Balayeuse balayeuse) {
|
||||
this.balayeuse = balayeuse;
|
||||
addRequirements(balayeuse);
|
||||
// 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(Math.abs(balayeuse.Distance()) < balayeuse.EncodeurBalayeuse()){
|
||||
balayeuse.Pivoter(-0.5);
|
||||
}
|
||||
else{
|
||||
balayeuse.Pivoter(0);
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
balayeuse.Pivoter(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return Math.abs(balayeuse.Distance()) > balayeuse.EncodeurBalayeuse();
|
||||
}
|
||||
}
|
||||
50
src/main/java/frc/robot/commands/DescendreGrimpeur.java
Normal file
50
src/main/java/frc/robot/commands/DescendreGrimpeur.java
Normal file
@@ -0,0 +1,50 @@
|
||||
// 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.Grimpeur;
|
||||
|
||||
/* 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 DescendreGrimpeur extends Command {
|
||||
private Grimpeur grimpeur;
|
||||
/** Creates a new DescendreGrimpeur. */
|
||||
public DescendreGrimpeur(Grimpeur grimpeur) {
|
||||
this.grimpeur = grimpeur;
|
||||
addRequirements(grimpeur);
|
||||
// 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(!grimpeur.Limit()){
|
||||
grimpeur.GrimperGauche(-0.4);
|
||||
grimpeur.GrimperDroit(-0.4);
|
||||
}
|
||||
else{
|
||||
grimpeur.Reset();
|
||||
grimpeur.GrimperGauche(0);
|
||||
grimpeur.GrimperDroit(0);
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
grimpeur.GrimperGauche(0);
|
||||
grimpeur.GrimperDroit(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
50
src/main/java/frc/robot/commands/DescendreGrimpeurPlus.java
Normal file
50
src/main/java/frc/robot/commands/DescendreGrimpeurPlus.java
Normal file
@@ -0,0 +1,50 @@
|
||||
// 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.Grimpeur;
|
||||
|
||||
/* 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 DescendreGrimpeurPlus extends Command {
|
||||
private Grimpeur grimpeur;
|
||||
/** Creates a new DescendreGrimpeur. */
|
||||
public DescendreGrimpeurPlus(Grimpeur grimpeur) {
|
||||
this.grimpeur = grimpeur;
|
||||
addRequirements(grimpeur);
|
||||
// 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(!grimpeur.Limit()){
|
||||
grimpeur.GrimperGauche(-0.4);
|
||||
grimpeur.GrimperDroit(-0.4);
|
||||
}
|
||||
else{
|
||||
grimpeur.Reset();
|
||||
grimpeur.GrimperGauche(0);
|
||||
grimpeur.GrimperDroit(0);
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
grimpeur.GrimperGauche(0);
|
||||
grimpeur.GrimperDroit(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
41
src/main/java/frc/robot/commands/Inverser.java
Normal file
41
src/main/java/frc/robot/commands/Inverser.java
Normal file
@@ -0,0 +1,41 @@
|
||||
// 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.CommandSwerveDrivetrain;
|
||||
|
||||
/* 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 Inverser extends Command {
|
||||
CommandSwerveDrivetrain drivetrain;
|
||||
boolean inverse = false;
|
||||
/** Creates a new Inverser. */
|
||||
public Inverser(CommandSwerveDrivetrain drivetrain) {
|
||||
this.drivetrain = drivetrain;
|
||||
addRequirements(drivetrain);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
drivetrain.getPigeon2().setYaw(drivetrain.getPigeon2().getYaw().getValueAsDouble()+180);
|
||||
}
|
||||
|
||||
// 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;
|
||||
}
|
||||
}
|
||||
97
src/main/java/frc/robot/commands/Lancer.java
Normal file
97
src/main/java/frc/robot/commands/Lancer.java
Normal file
@@ -0,0 +1,97 @@
|
||||
// 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 java.util.Optional;
|
||||
|
||||
import edu.wpi.first.math.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.subsystems.Lanceur;
|
||||
import frc.robot.subsystems.Limelight3G;
|
||||
|
||||
/* 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 Lancer extends Command {
|
||||
private Lanceur lanceur;
|
||||
private PIDController pidController;
|
||||
private Limelight3G limeLight3G;
|
||||
private Timer timer;
|
||||
double vitesse = 0;
|
||||
double botx = 0;
|
||||
double boty = 0;
|
||||
Optional<Alliance> alliance = DriverStation.getAlliance();
|
||||
|
||||
/** Creates a new Lancer. */
|
||||
public Lancer(Lanceur lanceur, Limelight3G limeLight3G) {
|
||||
this.lanceur = lanceur;
|
||||
this.timer = new Timer();
|
||||
this.limeLight3G = limeLight3G;
|
||||
addRequirements(lanceur, limeLight3G);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
if(limeLight3G.getV()){}
|
||||
pidController = new PIDController(0.0007, 0,0, 0.001);
|
||||
timer.reset();
|
||||
alliance = DriverStation.getAlliance();
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
double[] BotPose = new double[6];
|
||||
if(limeLight3G.getV()){
|
||||
if(!alliance.isPresent()){
|
||||
return;
|
||||
}
|
||||
if(alliance.get() == Alliance.Blue){
|
||||
BotPose = limeLight3G.getBotPoseBlue();
|
||||
}
|
||||
else{
|
||||
BotPose = limeLight3G.getBotPoseRed();
|
||||
}
|
||||
botx = BotPose[0];
|
||||
boty = BotPose[1];
|
||||
vitesse = 410.57 * ((Math.sqrt(Math.pow(Math.abs(4.625594-botx), 2) + Math.pow(Math.abs(4.034536-boty), 2)))) + 2250;
|
||||
}
|
||||
// if(limeLight3G.getV()){
|
||||
|
||||
if(vitesse > 2000){
|
||||
double output = pidController.calculate(lanceur.Vitesse(),vitesse);
|
||||
lanceur.Lancer(output);
|
||||
System.out.println(output);
|
||||
if(lanceur.Vitesse() >= vitesse-800){
|
||||
timer.start();
|
||||
if(timer.get() >1){
|
||||
lanceur.Demeler(1);
|
||||
}
|
||||
}
|
||||
else{
|
||||
lanceur.Lancer(3500);
|
||||
}
|
||||
}
|
||||
// }
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
lanceur.Demeler(0);
|
||||
lanceur.Lancer(0);
|
||||
timer.reset();
|
||||
timer.stop();
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
23
src/main/java/frc/robot/commands/LancerAspirer.java
Normal file
23
src/main/java/frc/robot/commands/LancerAspirer.java
Normal file
@@ -0,0 +1,23 @@
|
||||
// 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.ParallelCommandGroup;
|
||||
import frc.robot.subsystems.Balayeuse;
|
||||
import frc.robot.subsystems.Lanceur;
|
||||
import frc.robot.subsystems.Limelight3G;
|
||||
|
||||
|
||||
// NOTE: Consider using this command inline, rather than writing a subclass. For more
|
||||
// information, see:
|
||||
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
|
||||
public class LancerAspirer extends ParallelCommandGroup {
|
||||
/** Creates a new LacerAspirer. */
|
||||
public LancerAspirer(Lanceur lanceur, Balayeuse balayeuse, Limelight3G limeLight3G) {
|
||||
addCommands(new Lancer(lanceur, limeLight3G), new Aspirer(balayeuse));
|
||||
// Add your commands in the addCommands() call, e.g.
|
||||
// addCommands(new FooCommand(), new BarCommand());
|
||||
}
|
||||
}
|
||||
63
src/main/java/frc/robot/commands/LancerBaseVitesse.java
Normal file
63
src/main/java/frc/robot/commands/LancerBaseVitesse.java
Normal file
@@ -0,0 +1,63 @@
|
||||
// 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.math.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.subsystems.Lanceur;
|
||||
|
||||
/* 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 LancerBaseVitesse extends Command {
|
||||
private Lanceur lanceur;
|
||||
private PIDController pidController;
|
||||
private Timer timer;
|
||||
double tempsDebut = 0;
|
||||
/** Creates a new Lancer. */
|
||||
public LancerBaseVitesse(Lanceur lanceur) {
|
||||
this.lanceur = lanceur;
|
||||
this.timer = new Timer();
|
||||
addRequirements(lanceur);
|
||||
//this.temp = 0;
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
pidController = new PIDController(0.0007, 0,0, 0.001);
|
||||
timer.reset();
|
||||
timer.start();
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
System.out.println(DriverStation.getMatchTime());
|
||||
double vitesse = lanceur.vitesseDemander();
|
||||
double output = pidController.calculate(lanceur.Vitesse(),vitesse);
|
||||
lanceur.Lancer(output);
|
||||
if(timer.get() > 1){
|
||||
lanceur.Demeler(1);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
lanceur.Demeler(0);
|
||||
lanceur.Lancer(0);
|
||||
timer.reset();
|
||||
timer.stop();
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
134
src/main/java/frc/robot/commands/Limelighter.java
Normal file
134
src/main/java/frc/robot/commands/Limelighter.java
Normal file
@@ -0,0 +1,134 @@
|
||||
// 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 com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
|
||||
import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.generated.TunerConstants;
|
||||
import frc.robot.subsystems.CommandSwerveDrivetrain;
|
||||
import frc.robot.subsystems.Limelight3G;
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
|
||||
import java.util.Optional;
|
||||
|
||||
/* 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 Limelighter extends Command {
|
||||
Limelight3G limelight3g;
|
||||
CommandSwerveDrivetrain drivetrain;
|
||||
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
|
||||
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond);
|
||||
double botx;
|
||||
double boty;
|
||||
double angle;
|
||||
double calcul;
|
||||
double x;
|
||||
Optional<Alliance> alliance = DriverStation.getAlliance();
|
||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
|
||||
.withDriveRequestType(DriveRequestType.OpenLoopVoltage);
|
||||
|
||||
/** Creates a new Limelighter. */
|
||||
public Limelighter(Limelight3G limelight3g, CommandSwerveDrivetrain drivetrain) {
|
||||
this.limelight3g = limelight3g;
|
||||
this.drivetrain = drivetrain;
|
||||
addRequirements(drivetrain, limelight3g);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
alliance = DriverStation.getAlliance();
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
double[] BotPose = new double[6];
|
||||
if (limelight3g.getV()) {
|
||||
BotPose = limelight3g.getBotPoseBlue();
|
||||
if (!alliance.isPresent()) {
|
||||
return;
|
||||
}
|
||||
if (alliance.get() == Alliance.Blue) {
|
||||
x = 4.6;
|
||||
BotPose = limelight3g.getBotPoseBlue();
|
||||
}
|
||||
else {
|
||||
//x = 11.915394;
|
||||
x = 4.6;
|
||||
BotPose = limelight3g.getBotPoseRed();
|
||||
}
|
||||
botx = BotPose[0];
|
||||
boty = BotPose[1];
|
||||
angle = BotPose[5];
|
||||
calcul = Math.toRadians(limelight3g.Calcule(boty, 4,botx, x, angle));
|
||||
System.out.println(calcul);
|
||||
//drivetrain.setControl(drive.withRotationalRate(MathUtil.clamp(calcul, -3, 3)));
|
||||
if(calcul > -5 && calcul < 5){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(0));
|
||||
}
|
||||
else if(calcul > 5){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(2));
|
||||
}
|
||||
else if(calcul < -5){
|
||||
drivetrain.setControl(drive.withRotationalRate(-2));
|
||||
}
|
||||
botx = BotPose[1];
|
||||
boty = BotPose[0];
|
||||
angle = drivetrain.getPigeon2().getYaw().getValueAsDouble();
|
||||
calcul = limelight3g.Calcule(botx, x, boty, 4, angle);
|
||||
if(calcul < -5 && calcul > -180){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(0.5*(2*Math.PI)));
|
||||
}
|
||||
else if(calcul > 5 && calcul < 180){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||
}
|
||||
else if(calcul < -5){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||
}
|
||||
else if(calcul <= -180){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(0.5*(2*Math.PI)));
|
||||
}
|
||||
else{
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(0));
|
||||
}
|
||||
drivetrain.setControl(
|
||||
drive.withVelocityX(0).withVelocityY(0).withRotationalRate(calcul));
|
||||
System.out.println(angle);
|
||||
if (calcul < 0.2 && calcul > -0.2) {
|
||||
drivetrain.setControl(drive.withRotationalRate(0));
|
||||
}
|
||||
}
|
||||
else{
|
||||
drivetrain.setControl(drive.withRotationalRate(0));
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
drivetrain.setControl(drive.withRotationalRate(0));
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
43
src/main/java/frc/robot/commands/ModeAuto/AspirerAuto.java
Normal file
43
src/main/java/frc/robot/commands/ModeAuto/AspirerAuto.java
Normal file
@@ -0,0 +1,43 @@
|
||||
// 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.ModeAuto;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.subsystems.Balayeuse;
|
||||
|
||||
/* 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 AspirerAuto extends Command {
|
||||
Balayeuse balayeuse;
|
||||
/** Creates a new AspirerAuto. */
|
||||
public AspirerAuto(Balayeuse balayeuse) {
|
||||
this.balayeuse = balayeuse;
|
||||
addRequirements(balayeuse);
|
||||
// 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() {
|
||||
balayeuse.BalayerEnbas(-0.5);
|
||||
balayeuse.BalayerPadle(-0.2);
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
balayeuse.BalayerEnbas(0);
|
||||
balayeuse.BalayerPadle(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,69 @@
|
||||
// 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.ModeAuto;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
|
||||
import java.util.Optional;
|
||||
|
||||
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
|
||||
import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.generated.TunerConstants;
|
||||
import frc.robot.subsystems.CommandSwerveDrivetrain;
|
||||
|
||||
/* 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 BougerDroiteAuto extends Command {
|
||||
CommandSwerveDrivetrain drivetrain;
|
||||
Timer timer = new Timer();
|
||||
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
|
||||
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond);
|
||||
Optional<Alliance> alliance;
|
||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
|
||||
.withDriveRequestType(DriveRequestType.OpenLoopVoltage);
|
||||
/** Creates a new AvanceAuto. */
|
||||
public BougerDroiteAuto(CommandSwerveDrivetrain drivetrain) {
|
||||
this.drivetrain = drivetrain;
|
||||
addRequirements(drivetrain);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
alliance = DriverStation.getAlliance();
|
||||
timer.reset();
|
||||
timer.start();
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(timer.get() < 1.25){
|
||||
drivetrain.setControl(drive.withVelocityY(-1.5));
|
||||
}
|
||||
else{
|
||||
drivetrain.setControl(drive.withVelocityY(0));
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
drivetrain.setControl(drive.withVelocityY(0));
|
||||
timer.stop();
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return timer.get() > 1;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,69 @@
|
||||
// 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.ModeAuto;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
|
||||
import java.util.Optional;
|
||||
|
||||
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
|
||||
import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.generated.TunerConstants;
|
||||
import frc.robot.subsystems.CommandSwerveDrivetrain;
|
||||
|
||||
/* 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 BougerGaucheAuto extends Command {
|
||||
CommandSwerveDrivetrain drivetrain;
|
||||
Timer timer = new Timer();
|
||||
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
|
||||
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond);
|
||||
Optional<Alliance> alliance;
|
||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
|
||||
.withDriveRequestType(DriveRequestType.OpenLoopVoltage);
|
||||
/** Creates a new AvanceAuto. */
|
||||
public BougerGaucheAuto(CommandSwerveDrivetrain drivetrain) {
|
||||
this.drivetrain = drivetrain;
|
||||
addRequirements(drivetrain);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
alliance = DriverStation.getAlliance();
|
||||
timer.reset();
|
||||
timer.start();
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(timer.get() < 1.25){
|
||||
drivetrain.setControl(drive.withVelocityY(1.5));
|
||||
}
|
||||
else{
|
||||
drivetrain.setControl(drive.withVelocityY(0));
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
drivetrain.setControl(drive.withVelocityY(0));
|
||||
timer.stop();
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return timer.get() > 1;
|
||||
}
|
||||
}
|
||||
125
src/main/java/frc/robot/commands/ModeAuto/GrimperMur.java
Normal file
125
src/main/java/frc/robot/commands/ModeAuto/GrimperMur.java
Normal file
@@ -0,0 +1,125 @@
|
||||
// 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.ModeAuto;
|
||||
|
||||
import static edu.wpi.first.units.Units.MetersPerSecond;
|
||||
import static edu.wpi.first.units.Units.RadiansPerSecond;
|
||||
import static edu.wpi.first.units.Units.RotationsPerSecond;
|
||||
|
||||
import java.util.Optional;
|
||||
|
||||
import com.ctre.phoenix6.hardware.Pigeon2;
|
||||
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
|
||||
import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.generated.TunerConstants;
|
||||
import frc.robot.subsystems.CommandSwerveDrivetrain;
|
||||
import frc.robot.subsystems.LimeLight3;
|
||||
import frc.robot.subsystems.Limelight3G;
|
||||
|
||||
/* 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 GrimperMur extends Command {
|
||||
LimeLight3 limeLight3;
|
||||
CommandSwerveDrivetrain drivetrain;
|
||||
double[] BotPose = new double[6];
|
||||
double botx;
|
||||
double boty;
|
||||
double x;
|
||||
double y;
|
||||
double angle;
|
||||
double pigeonAngle;
|
||||
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
|
||||
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond);
|
||||
Optional<Alliance> alliance = DriverStation.getAlliance();
|
||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
|
||||
.withDriveRequestType(DriveRequestType.OpenLoopVoltage);
|
||||
/** Creates a new GrimperMur. */
|
||||
public GrimperMur(LimeLight3 limeLight3, CommandSwerveDrivetrain drivetrain) {
|
||||
this.drivetrain = drivetrain;
|
||||
this.limeLight3 = limeLight3;
|
||||
addRequirements(limeLight3,drivetrain);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
alliance = DriverStation.getAlliance();
|
||||
// if(drivetrain.Equipe()){
|
||||
// angle+=180;
|
||||
// }
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(limeLight3.getV()){
|
||||
BotPose = limeLight3.getBotPoseBlue();
|
||||
botx = BotPose[0];
|
||||
boty = BotPose[1];
|
||||
if(angle < 0){
|
||||
angle = angle + 360;
|
||||
}
|
||||
if(alliance.get() == Alliance.Red){
|
||||
pigeonAngle = drivetrain.getPigeon2().getYaw().getValueAsDouble();
|
||||
System.out.println(pigeonAngle);
|
||||
y = 3.6;
|
||||
x = 15;
|
||||
angle = 180;
|
||||
if(pigeonAngle> 358 || pigeonAngle< 2){
|
||||
drivetrain.setControl(drive.withVelocityY(MathUtil.clamp((-(y-boty)*10), -2, 2)).withVelocityX(MathUtil.clamp((-(x-botx)*10),-2,2)).withRotationalRate(0));
|
||||
}
|
||||
else{
|
||||
if(pigeonAngle>180){
|
||||
drivetrain.setControl(drive.withVelocityY(0).withVelocityX(0).withRotationalRate(1));
|
||||
}
|
||||
else{
|
||||
drivetrain.setControl(drive.withVelocityY(0).withVelocityX(0).withRotationalRate(-1));
|
||||
}
|
||||
}
|
||||
}
|
||||
else{
|
||||
pigeonAngle = drivetrain.getPigeon2().getYaw().getValueAsDouble();
|
||||
System.out.println(pigeonAngle);
|
||||
y = 4.4;
|
||||
x = 1.6;
|
||||
angle = 0;
|
||||
if(pigeonAngle> 182 || pigeonAngle< 178){
|
||||
drivetrain.setControl(drive.withVelocityY(MathUtil.clamp(((y-boty)*10), -2, 2)).withVelocityX(MathUtil.clamp(((x-botx)*10),-2,2)).withRotationalRate(0));
|
||||
}
|
||||
else{
|
||||
if(pigeonAngle>0 && pigeonAngle<180){
|
||||
drivetrain.setControl(drive.withVelocityY(0).withVelocityX(0).withRotationalRate(-1));
|
||||
System.out.println("x");
|
||||
}
|
||||
else if(pigeonAngle>180){
|
||||
System.out.println("e");
|
||||
drivetrain.setControl(drive.withVelocityY(0).withVelocityX(0).withRotationalRate(1));
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else{
|
||||
drivetrain.setControl(drive.withVelocityX(0).withVelocityY(0).withRotationalRate(0));
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
drivetrain.setControl(drive.withVelocityX(0).withVelocityY(0).withRotationalRate(0));
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return (y-boty < 0.2 && y-boty >-0.2) && (x-botx < 0.06 && x-botx > -0.06);
|
||||
}
|
||||
}
|
||||
124
src/main/java/frc/robot/commands/ModeAuto/GrimperReservoir.java
Normal file
124
src/main/java/frc/robot/commands/ModeAuto/GrimperReservoir.java
Normal file
@@ -0,0 +1,124 @@
|
||||
// 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.ModeAuto;
|
||||
|
||||
import static edu.wpi.first.units.Units.MetersPerSecond;
|
||||
import static edu.wpi.first.units.Units.RadiansPerSecond;
|
||||
import static edu.wpi.first.units.Units.RotationsPerSecond;
|
||||
|
||||
import java.util.Optional;
|
||||
|
||||
import com.ctre.phoenix6.hardware.Pigeon2;
|
||||
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
|
||||
import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.generated.TunerConstants;
|
||||
import frc.robot.subsystems.CommandSwerveDrivetrain;
|
||||
import frc.robot.subsystems.Limelight3G;
|
||||
|
||||
/* 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 GrimperReservoir extends Command {
|
||||
Limelight3G limeLight3G;
|
||||
CommandSwerveDrivetrain drivetrain;
|
||||
double[] BotPose = new double[6];
|
||||
double botx;
|
||||
double boty;
|
||||
double x;
|
||||
double y;
|
||||
double angle;
|
||||
double pigeonAngle;
|
||||
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
|
||||
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond);
|
||||
Optional<Alliance> alliance;
|
||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
|
||||
.withDriveRequestType(DriveRequestType.OpenLoopVoltage);
|
||||
/** Creates a new GrimperMur. */
|
||||
public GrimperReservoir(Limelight3G limeLight3G, CommandSwerveDrivetrain drivetrain) {
|
||||
this.drivetrain = drivetrain;
|
||||
this.limeLight3G = limeLight3G;
|
||||
addRequirements(limeLight3G,drivetrain);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
alliance = DriverStation.getAlliance();
|
||||
// if(drivetrain.Equipe()){
|
||||
// drivetrain.getPigeon2().setYaw(drivetrain.getPigeon2().getYaw().getValueAsDouble()+180);
|
||||
// }
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(limeLight3G.getV()){
|
||||
BotPose = limeLight3G.getBotPoseBlue();
|
||||
botx = BotPose[0];
|
||||
boty = BotPose[1];
|
||||
if(angle < 0){
|
||||
angle = angle + 360;
|
||||
}
|
||||
if(alliance.get() == Alliance.Red){
|
||||
pigeonAngle = drivetrain.getPigeon2().getYaw().getValueAsDouble();
|
||||
System.out.println(pigeonAngle);
|
||||
y = 5.2;
|
||||
x = 15.6;
|
||||
angle = 180;
|
||||
if(pigeonAngle< 190 && pigeonAngle> 170){
|
||||
drivetrain.setControl(drive.withVelocityY(MathUtil.clamp((-(y-boty)*10), -2, 2)).withVelocityX(MathUtil.clamp((-(x-botx)*10),-2,2)));
|
||||
}
|
||||
else{
|
||||
if(pigeonAngle>180){
|
||||
drivetrain.setControl(drive.withRotationalRate(-1));
|
||||
}
|
||||
else{
|
||||
drivetrain.setControl(drive.withRotationalRate(1));
|
||||
}
|
||||
}
|
||||
}
|
||||
else{
|
||||
pigeonAngle = drivetrain.getPigeon2().getYaw().getValueAsDouble()+180;
|
||||
System.out.println(pigeonAngle);
|
||||
y = 2.6;
|
||||
x = 1.11;
|
||||
angle = 0;
|
||||
if(pigeonAngle> 358 || pigeonAngle< 2){
|
||||
drivetrain.setControl(drive.withVelocityY(MathUtil.clamp(((y-boty)*10), -2, 2)).withVelocityX(MathUtil.clamp(((x-botx)*10),-2,2)).withRotationalRate(0));
|
||||
}
|
||||
else{
|
||||
if(pigeonAngle>0 && pigeonAngle<180){
|
||||
drivetrain.setControl(drive.withRotationalRate(-1));
|
||||
System.out.println("x");
|
||||
}
|
||||
else if(pigeonAngle>180){
|
||||
System.out.println("e");
|
||||
drivetrain.setControl(drive.withRotationalRate(1));
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else{
|
||||
drivetrain.setControl(drive.withVelocityX(0).withVelocityY(0).withRotationalRate(0));
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
drivetrain.setControl(drive.withVelocityX(0).withVelocityY(0).withRotationalRate(0));
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return (y-boty < 0.2 && y-boty >-0.2) && (x-botx < 0.06 && x-botx > -0.06);
|
||||
}
|
||||
}
|
||||
93
src/main/java/frc/robot/commands/ModeAuto/LancerAuto.java
Normal file
93
src/main/java/frc/robot/commands/ModeAuto/LancerAuto.java
Normal file
@@ -0,0 +1,93 @@
|
||||
// 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.ModeAuto;
|
||||
|
||||
import java.util.Optional;
|
||||
|
||||
import edu.wpi.first.math.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.subsystems.Lanceur;
|
||||
import frc.robot.subsystems.Limelight3G;
|
||||
|
||||
/* 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 LancerAuto extends Command {
|
||||
Lanceur lanceur;
|
||||
Timer timer;
|
||||
private PIDController pidController;
|
||||
Limelight3G limelight3g;
|
||||
double botx = 0;
|
||||
double boty = 0;
|
||||
Optional<Alliance> alliance = DriverStation.getAlliance();
|
||||
|
||||
/** Creates a new LancerAuto. */
|
||||
public LancerAuto(Lanceur lanceur, Limelight3G limelight3g) {
|
||||
this.lanceur = lanceur;
|
||||
timer = new Timer();
|
||||
this.limelight3g = limelight3g;
|
||||
addRequirements(lanceur, limelight3g);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
pidController = new PIDController(0.0007, 0, 0, 0.001);
|
||||
timer.reset();
|
||||
alliance = DriverStation.getAlliance();
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
double[] BotPose = new double[6];
|
||||
if (limelight3g.getV()) {
|
||||
if (!alliance.isPresent()) {
|
||||
return;
|
||||
}
|
||||
if (alliance.get() == Alliance.Blue) {
|
||||
BotPose = limelight3g.getBotPoseBlue();
|
||||
} else {
|
||||
BotPose = limelight3g.getBotPoseRed();
|
||||
}
|
||||
|
||||
botx = BotPose[0];
|
||||
boty = BotPose[1];
|
||||
}
|
||||
double vitesse = 0.5;
|
||||
if (limelight3g.getV()) {
|
||||
vitesse = 410.57 * ((Math.sqrt(Math.pow(Math.abs(4.625594 - botx), 2) + Math.pow(Math.abs(4.034536 - boty), 2))))
|
||||
+ 2250;
|
||||
System.out.println("lancer");
|
||||
|
||||
double output = pidController.calculate(lanceur.Vitesse(), vitesse);
|
||||
lanceur.Lancer(output);
|
||||
if (lanceur.Vitesse() >= vitesse - 800) {
|
||||
timer.start();
|
||||
if (timer.get() > 1) {
|
||||
lanceur.Demeler(1);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
lanceur.Lancer(0);
|
||||
lanceur.Demeler(0);
|
||||
timer.reset();
|
||||
timer.stop();
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return timer.get() > 4;
|
||||
// return false;
|
||||
}
|
||||
}
|
||||
133
src/main/java/frc/robot/commands/ModeAuto/LimelighterAuto.java
Normal file
133
src/main/java/frc/robot/commands/ModeAuto/LimelighterAuto.java
Normal file
@@ -0,0 +1,133 @@
|
||||
// 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.ModeAuto;
|
||||
|
||||
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
|
||||
import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.generated.TunerConstants;
|
||||
import frc.robot.subsystems.CommandSwerveDrivetrain;
|
||||
import frc.robot.subsystems.Limelight3G;
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
|
||||
import java.util.Optional;
|
||||
|
||||
/* 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 LimelighterAuto extends Command {
|
||||
Limelight3G limelight3g;
|
||||
CommandSwerveDrivetrain drivetrain;
|
||||
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
|
||||
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond);
|
||||
double botx;
|
||||
double boty;
|
||||
double angle;
|
||||
double calcul;
|
||||
double x;
|
||||
Optional<Alliance> alliance = DriverStation.getAlliance();
|
||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
|
||||
.withDriveRequestType(DriveRequestType.OpenLoopVoltage);
|
||||
|
||||
/** Creates a new Limelighter. */
|
||||
public LimelighterAuto(Limelight3G limelight3g, CommandSwerveDrivetrain drivetrain) {
|
||||
this.limelight3g = limelight3g;
|
||||
this.drivetrain = drivetrain;
|
||||
addRequirements(drivetrain, limelight3g);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
alliance = DriverStation.getAlliance();
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
double[] BotPose = new double[6];
|
||||
System.out.println("e");
|
||||
if (limelight3g.getV()) {
|
||||
BotPose = limelight3g.getBotPoseBlue();
|
||||
if (!alliance.isPresent()) {
|
||||
return;
|
||||
}
|
||||
if (alliance.get() == Alliance.Blue) {
|
||||
x = 4.6;
|
||||
BotPose = limelight3g.getBotPoseBlue();
|
||||
}
|
||||
else {
|
||||
// x = 11.915394;
|
||||
x = 4.6;
|
||||
BotPose = limelight3g.getBotPoseRed();
|
||||
}
|
||||
botx = BotPose[0];
|
||||
boty = BotPose[1];
|
||||
angle = BotPose[5];
|
||||
calcul = limelight3g.Calcule(botx, x, boty, 4, angle);
|
||||
if(calcul > -5 && calcul < 5){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(0));
|
||||
}
|
||||
else if(calcul > 5){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(2));
|
||||
}
|
||||
else if(calcul < -5){
|
||||
drivetrain.setControl(drive.withRotationalRate(-2));
|
||||
}
|
||||
// botx = BotPose[1];
|
||||
// boty = BotPose[0];
|
||||
// angle = drivetrain.getPigeon2().getYaw().getValueAsDouble();
|
||||
// calcul = limelight3g.Calcule(botx, x, boty, 4, angle);
|
||||
// if(calcul < -5 && calcul > -180){
|
||||
// drivetrain.setControl(
|
||||
// drive.withRotationalRate(0.5*(2*Math.PI)));
|
||||
// }
|
||||
// else if(calcul > 5 && calcul < 180){
|
||||
// drivetrain.setControl(
|
||||
// drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||
// }
|
||||
// else if(calcul < -5){
|
||||
// drivetrain.setControl(
|
||||
// drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||
// }
|
||||
// else if(calcul <= -180){
|
||||
// drivetrain.setControl(
|
||||
// drive.withRotationalRate(0.5*(2*Math.PI)));
|
||||
// }
|
||||
// else{
|
||||
// drivetrain.setControl(
|
||||
// drive.withRotationalRate(0));
|
||||
// }
|
||||
// drivetrain.setControl(
|
||||
// drive.withVelocityX(0).withVelocityY(0).withRotationalRate(calcul));
|
||||
// System.out.println(angle);
|
||||
// if (calcul < 0.2 && calcul > -0.2) {
|
||||
// drivetrain.setControl(drive.withRotationalRate(0));
|
||||
// }
|
||||
}
|
||||
else{
|
||||
drivetrain.setControl(drive.withRotationalRate(0));
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
drivetrain.setControl(drive.withRotationalRate(0));
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return calcul > -5 && calcul < 5;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -15,9 +15,9 @@ import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.Limelight3G;
|
||||
import frc.robot.generated.TunerConstants;
|
||||
import frc.robot.subsystems.CommandSwerveDrivetrain;
|
||||
import frc.robot.subsystems.Limelight3G;
|
||||
|
||||
/* 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 RetourMilieuDroite extends Command {
|
||||
@@ -38,7 +38,7 @@ public class RetourMilieuDroite extends Command {
|
||||
public RetourMilieuDroite(CommandSwerveDrivetrain drivetrain, Limelight3G limelight3g) {
|
||||
this.drivetrain = drivetrain;
|
||||
this.limelight3g = limelight3g;
|
||||
addRequirements(drivetrain);
|
||||
addRequirements(drivetrain, limelight3g);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
|
||||
@@ -15,9 +15,9 @@ import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.Limelight3G;
|
||||
import frc.robot.generated.TunerConstants;
|
||||
import frc.robot.subsystems.CommandSwerveDrivetrain;
|
||||
import frc.robot.subsystems.Limelight3G;
|
||||
|
||||
/* 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 RetourMilieuGauche extends Command {
|
||||
@@ -38,7 +38,7 @@ public class RetourMilieuGauche extends Command {
|
||||
public RetourMilieuGauche(CommandSwerveDrivetrain drivetrain, Limelight3G limelight3g) {
|
||||
this.drivetrain = drivetrain;
|
||||
this.limelight3g = limelight3g;
|
||||
addRequirements(drivetrain);
|
||||
addRequirements(drivetrain, limelight3g);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
|
||||
@@ -37,7 +37,9 @@ public class TournerVersMur extends Command {
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {}
|
||||
public void initialize() {
|
||||
alliance = DriverStation.getAlliance();
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
|
||||
@@ -37,7 +37,9 @@ public class TournerVersReservoir extends Command {
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {}
|
||||
public void initialize() {
|
||||
alliance = DriverStation.getAlliance();
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
@@ -52,13 +54,18 @@ public class TournerVersReservoir extends Command {
|
||||
angle = 0;
|
||||
}
|
||||
}
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() > angle && drivetrain.getPigeon2().getYaw().getValueAsDouble() < angle + 10){
|
||||
drivetrain.setControl(drive.withRotationalRate(0));
|
||||
}
|
||||
else{
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >0 && drivetrain.getPigeon2().getYaw().getValueAsDouble() <180){
|
||||
drivetrain.setControl(drive.withRotationalRate(-force*180/Math.PI));
|
||||
drivetrain.setControl(drive.withRotationalRate(-force*2));
|
||||
}
|
||||
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >180){
|
||||
drivetrain.setControl(drive.withRotationalRate(force*180/Math.PI));
|
||||
drivetrain.setControl(drive.withRotationalRate(force*2));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
@@ -67,6 +74,6 @@ public class TournerVersReservoir extends Command {
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return drivetrain.getPigeon2().getYaw().getValueAsDouble() > angle && drivetrain.getPigeon2().getYaw().getValueAsDouble() < angle + 10;
|
||||
return drivetrain.getPigeon2().getYaw().getValueAsDouble() > angle && drivetrain.getPigeon2().getYaw().getValueAsDouble() < angle + 10;
|
||||
}
|
||||
}
|
||||
|
||||
43
src/main/java/frc/robot/commands/ModeOposer.java
Normal file
43
src/main/java/frc/robot/commands/ModeOposer.java
Normal file
@@ -0,0 +1,43 @@
|
||||
// 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.Lanceur;
|
||||
/* 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 ModeOposer extends Command {
|
||||
private Lanceur lanceur;
|
||||
/** Creates a new Lancer. */
|
||||
public ModeOposer(Lanceur lanceur) {
|
||||
this.lanceur = lanceur;
|
||||
addRequirements(lanceur);
|
||||
// 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() {
|
||||
lanceur.Lancer(-0.2);
|
||||
lanceur.Demeler(-0.2);
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
lanceur.Demeler(0);
|
||||
lanceur.Lancer(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
43
src/main/java/frc/robot/commands/ModeOposerBalayeuse.java
Normal file
43
src/main/java/frc/robot/commands/ModeOposerBalayeuse.java
Normal file
@@ -0,0 +1,43 @@
|
||||
// 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.Balayeuse;
|
||||
/* 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 ModeOposerBalayeuse extends Command {
|
||||
private Balayeuse balayeuse;
|
||||
/** Creates a new Lancer. */
|
||||
public ModeOposerBalayeuse(Balayeuse balayeuse) {
|
||||
this.balayeuse = balayeuse;
|
||||
addRequirements(balayeuse);
|
||||
// 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() {
|
||||
balayeuse.BalayerEnbas(0.5);
|
||||
balayeuse.BalayerPadle(0.2);
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
balayeuse.BalayerEnbas(0);
|
||||
balayeuse.BalayerPadle(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
@@ -5,32 +5,33 @@
|
||||
package frc.robot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.subsystems.Led;
|
||||
|
||||
import frc.robot.subsystems.Lanceur;
|
||||
/* 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 RainBowAnim extends Command {
|
||||
private Led led;
|
||||
/** Creates a new RainBowAnim. */
|
||||
public RainBowAnim(Led led) {
|
||||
this.led = led;
|
||||
addRequirements(led);
|
||||
public class ModeOposerDemeleur extends Command {
|
||||
private Lanceur lanceur;
|
||||
/** Creates a new Lancer. */
|
||||
public ModeOposerDemeleur(Lanceur lanceur) {
|
||||
this.lanceur = lanceur;
|
||||
addRequirements(lanceur);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
led.RainBow();
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {}
|
||||
public void execute() {
|
||||
lanceur.Demeler(-0.2);
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
led.RainBowStop();
|
||||
lanceur.Demeler(0);
|
||||
lanceur.Lancer(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
47
src/main/java/frc/robot/commands/MonterBalyeuse.java
Normal file
47
src/main/java/frc/robot/commands/MonterBalyeuse.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.Balayeuse;
|
||||
|
||||
/* 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 MonterBalyeuse extends Command {
|
||||
private Balayeuse balayeuse;
|
||||
/** Creates a new MonterBalyeuse. */
|
||||
public MonterBalyeuse(Balayeuse balayeuse) {
|
||||
this.balayeuse = balayeuse;
|
||||
addRequirements(balayeuse);
|
||||
// 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(!balayeuse.GetLimiSwtich()){
|
||||
balayeuse.Pivoter(0.5);
|
||||
}
|
||||
else{
|
||||
balayeuse.Reset();
|
||||
balayeuse.Pivoter(0);
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
balayeuse.Pivoter(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
51
src/main/java/frc/robot/commands/MonterGrimpeur.java
Normal file
51
src/main/java/frc/robot/commands/MonterGrimpeur.java
Normal file
@@ -0,0 +1,51 @@
|
||||
// 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.Grimpeur;
|
||||
|
||||
/* 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 MonterGrimpeur extends Command {
|
||||
private Grimpeur grimpeur;
|
||||
/** Creates a new MonterGrimpeur. */
|
||||
public MonterGrimpeur(Grimpeur grimpeur) {
|
||||
this.grimpeur = grimpeur;
|
||||
addRequirements(grimpeur);
|
||||
// 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(Math.abs(grimpeur.Position()) < grimpeur.PositionFinal()){
|
||||
grimpeur.GrimperGauche(0.5);
|
||||
grimpeur.GrimperDroit(0.5);
|
||||
System.out.println("monte");
|
||||
}
|
||||
else {
|
||||
grimpeur.GrimperGauche(0);
|
||||
grimpeur.GrimperDroit(0);
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
grimpeur.GrimperGauche(0);
|
||||
grimpeur.GrimperDroit(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return Math.abs(grimpeur.Position()) > grimpeur.PositionFinal();
|
||||
}
|
||||
}
|
||||
@@ -5,42 +5,61 @@
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import com.revrobotics.spark.SparkFlex;
|
||||
import com.revrobotics.spark.SparkMax;
|
||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||
|
||||
import edu.wpi.first.networktables.GenericEntry;
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Balayeuse extends SubsystemBase {
|
||||
ShuffleboardTab teb = Shuffleboard.getTab("teb");
|
||||
SparkFlex moteurBas = new SparkFlex(2, MotorType.kBrushless);
|
||||
SparkFlex moteurHaut = new SparkFlex(20, MotorType.kBrushless);
|
||||
|
||||
private final double vitesseMoteurBas = -0.5;
|
||||
private final double vitesseMoteurHaut = -0.2;
|
||||
|
||||
public Command balaye(double vitesseBas, double vitesseHaut) {
|
||||
return startEnd(
|
||||
() -> {
|
||||
moteurBas.set(vitesseBas);
|
||||
moteurHaut.set(vitesseHaut);
|
||||
}, () -> {
|
||||
moteurBas.set(0);
|
||||
moteurHaut.set(0);
|
||||
});
|
||||
SparkFlex Balaye1 = new SparkFlex(2, MotorType.kBrushless);
|
||||
SparkFlex Balaye2 = new SparkFlex(20, MotorType.kBrushless);
|
||||
SparkMax Pivot = new SparkMax(8, MotorType.kBrushless);
|
||||
DigitalInput limit = new DigitalInput(9);
|
||||
private GenericEntry EncodeurBalayeuse =
|
||||
teb.add("Position bas balayeuse", 1.8).getEntry();
|
||||
private GenericEntry AmpBaleyeuse =
|
||||
teb.add("Ampérage Baleyeuse", 40).getEntry();
|
||||
public void BalayerEnbas(double vitesse){
|
||||
Balaye1.set(vitesse);
|
||||
}
|
||||
|
||||
public Command aspirer() {
|
||||
return balaye(vitesseMoteurBas, vitesseMoteurHaut);
|
||||
public void BalayerPadle(double vitesse){
|
||||
Balaye2.set(vitesse);
|
||||
}
|
||||
|
||||
public Command ejecter() {
|
||||
return balaye(-vitesseMoteurBas, -vitesseMoteurHaut);
|
||||
public void Pivoter(double vitesse){
|
||||
Pivot.set(vitesse);
|
||||
}
|
||||
public double Distance(){
|
||||
return Pivot.getEncoder().getPosition();
|
||||
}
|
||||
public void Reset(){
|
||||
Pivot.getEncoder().setPosition(0.6);
|
||||
}
|
||||
public boolean GetLimiSwtich(){
|
||||
return !limit.get();
|
||||
}
|
||||
public double Amp(){
|
||||
return Balaye2.getOutputCurrent();
|
||||
}
|
||||
public double AmpMax(){
|
||||
return AmpBaleyeuse.getDouble(40);
|
||||
}
|
||||
public void Temps(){
|
||||
Timer timer = new Timer();
|
||||
timer.start();
|
||||
}
|
||||
public double EncodeurBalayeuse(){
|
||||
return EncodeurBalayeuse.getDouble(1.8);
|
||||
}
|
||||
|
||||
/** Creates a new Balayeuse. */
|
||||
public Balayeuse() {
|
||||
teb.addBoolean("limit balayeuse", this::GetLimiSwtich);
|
||||
teb.addDouble("encodeur balayeuse", this::Distance);
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -1,8 +1,6 @@
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import static edu.wpi.first.units.Units.Degrees;
|
||||
import static edu.wpi.first.units.Units.Second;
|
||||
import static edu.wpi.first.units.Units.Volts;
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
|
||||
import java.util.Optional;
|
||||
import java.util.function.Supplier;
|
||||
@@ -11,10 +9,8 @@ import com.ctre.phoenix6.SignalLogger;
|
||||
import com.ctre.phoenix6.Utils;
|
||||
import com.ctre.phoenix6.hardware.Pigeon2;
|
||||
import com.ctre.phoenix6.swerve.SwerveDrivetrainConstants;
|
||||
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
|
||||
import com.ctre.phoenix6.swerve.SwerveModuleConstants;
|
||||
import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||
import com.ctre.phoenix6.swerve.SwerveRequest.FieldCentricFacingAngle;
|
||||
import com.pathplanner.lib.auto.AutoBuilder;
|
||||
import com.pathplanner.lib.config.PIDConstants;
|
||||
import com.pathplanner.lib.config.RobotConfig;
|
||||
@@ -23,7 +19,6 @@ import com.pathplanner.lib.controllers.PPHolonomicDriveController;
|
||||
import edu.wpi.first.math.Matrix;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import edu.wpi.first.math.numbers.N3;
|
||||
@@ -34,7 +29,7 @@ import edu.wpi.first.wpilibj.RobotController;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
|
||||
import frc.robot.Coordinates;
|
||||
|
||||
import frc.robot.generated.TunerConstants.TunerSwerveDrivetrain;
|
||||
|
||||
/**
|
||||
@@ -60,108 +55,107 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
||||
private final SwerveRequest.SysIdSwerveTranslation m_translationCharacterization = new SwerveRequest.SysIdSwerveTranslation();
|
||||
private final SwerveRequest.SysIdSwerveSteerGains m_steerCharacterization = new SwerveRequest.SysIdSwerveSteerGains();
|
||||
private final SwerveRequest.SysIdSwerveRotation m_rotationCharacterization = new SwerveRequest.SysIdSwerveRotation();
|
||||
|
||||
/*
|
||||
* SysId routine for characterizing translation. This is used to find PID gains
|
||||
* for the drive motors.
|
||||
*/
|
||||
@SuppressWarnings("unused")
|
||||
/* SysId routine for characterizing translation. This is used to find PID gains for the drive motors. */
|
||||
private final SysIdRoutine m_sysIdRoutineTranslation = new SysIdRoutine(
|
||||
new SysIdRoutine.Config(
|
||||
null, // Use default ramp rate (1 V/s)
|
||||
Volts.of(4), // Reduce dynamic step voltage to 4 V to prevent brownout
|
||||
null, // Use default timeout (10 s)
|
||||
// Log state with SignalLogger class
|
||||
state -> SignalLogger.writeString("SysIdTranslation_State", state.toString())),
|
||||
new SysIdRoutine.Mechanism(
|
||||
output -> setControl(m_translationCharacterization.withVolts(output)),
|
||||
null,
|
||||
this));
|
||||
new SysIdRoutine.Config(
|
||||
null, // Use default ramp rate (1 V/s)
|
||||
Volts.of(4), // Reduce dynamic step voltage to 4 V to prevent brownout
|
||||
null, // Use default timeout (10 s)
|
||||
// Log state with SignalLogger class
|
||||
state -> SignalLogger.writeString("SysIdTranslation_State", state.toString())
|
||||
),
|
||||
new SysIdRoutine.Mechanism(
|
||||
output -> setControl(m_translationCharacterization.withVolts(output)),
|
||||
null,
|
||||
this
|
||||
)
|
||||
);
|
||||
|
||||
/*
|
||||
* SysId routine for characterizing steer. This is used to find PID gains for
|
||||
* the steer motors.
|
||||
*/
|
||||
@SuppressWarnings("unused")
|
||||
/* SysId routine for characterizing steer. This is used to find PID gains for the steer motors. */
|
||||
private final SysIdRoutine m_sysIdRoutineSteer = new SysIdRoutine(
|
||||
new SysIdRoutine.Config(
|
||||
null, // Use default ramp rate (1 V/s)
|
||||
Volts.of(7), // Use dynamic voltage of 7 V
|
||||
null, // Use default timeout (10 s)
|
||||
// Log state with SignalLogger class
|
||||
state -> SignalLogger.writeString("SysIdSteer_State", state.toString())),
|
||||
new SysIdRoutine.Mechanism(
|
||||
volts -> setControl(m_steerCharacterization.withVolts(volts)),
|
||||
null,
|
||||
this));
|
||||
new SysIdRoutine.Config(
|
||||
null, // Use default ramp rate (1 V/s)
|
||||
Volts.of(7), // Use dynamic voltage of 7 V
|
||||
null, // Use default timeout (10 s)
|
||||
// Log state with SignalLogger class
|
||||
state -> SignalLogger.writeString("SysIdSteer_State", state.toString())
|
||||
),
|
||||
new SysIdRoutine.Mechanism(
|
||||
volts -> setControl(m_steerCharacterization.withVolts(volts)),
|
||||
null,
|
||||
this
|
||||
)
|
||||
);
|
||||
|
||||
/*
|
||||
* SysId routine for characterizing rotation.
|
||||
* This is used to find PID gains for the FieldCentricFacingAngle
|
||||
* HeadingController.
|
||||
* See the documentation of SwerveRequest.SysIdSwerveRotation for info on
|
||||
* importing the log to SysId.
|
||||
* This is used to find PID gains for the FieldCentricFacingAngle HeadingController.
|
||||
* See the documentation of SwerveRequest.SysIdSwerveRotation for info on importing the log to SysId.
|
||||
*/
|
||||
@SuppressWarnings("unused")
|
||||
private final SysIdRoutine m_sysIdRoutineRotation = new SysIdRoutine(
|
||||
new SysIdRoutine.Config(
|
||||
/* This is in radians per second², but SysId only supports "volts per second" */
|
||||
Volts.of(Math.PI / 6).per(Second),
|
||||
/* This is in radians per second, but SysId only supports "volts" */
|
||||
Volts.of(Math.PI),
|
||||
null, // Use default timeout (10 s)
|
||||
// Log state with SignalLogger class
|
||||
state -> SignalLogger.writeString("SysIdRotation_State", state.toString())),
|
||||
new SysIdRoutine.Mechanism(
|
||||
output -> {
|
||||
/* output is actually radians per second, but SysId only supports "volts" */
|
||||
setControl(m_rotationCharacterization.withRotationalRate(output.in(Volts)));
|
||||
/* also log the requested output for SysId */
|
||||
SignalLogger.writeDouble("Rotational_Rate", output.in(Volts));
|
||||
},
|
||||
null,
|
||||
this));
|
||||
new SysIdRoutine.Config(
|
||||
/* This is in radians per second², but SysId only supports "volts per second" */
|
||||
Volts.of(Math.PI / 6).per(Second),
|
||||
/* This is in radians per second, but SysId only supports "volts" */
|
||||
Volts.of(Math.PI),
|
||||
null, // Use default timeout (10 s)
|
||||
// Log state with SignalLogger class
|
||||
state -> SignalLogger.writeString("SysIdRotation_State", state.toString())
|
||||
),
|
||||
new SysIdRoutine.Mechanism(
|
||||
output -> {
|
||||
/* output is actually radians per second, but SysId only supports "volts" */
|
||||
setControl(m_rotationCharacterization.withRotationalRate(output.in(Volts)));
|
||||
/* also log the requested output for SysId */
|
||||
SignalLogger.writeDouble("Rotational_Rate", output.in(Volts));
|
||||
},
|
||||
null,
|
||||
this
|
||||
)
|
||||
);
|
||||
|
||||
/* The SysId routine to test */
|
||||
private SysIdRoutine m_sysIdRoutineToApply = m_sysIdRoutineTranslation;
|
||||
|
||||
private final SwerveRequest.ApplyRobotSpeeds m_pathApplyRobotSpeeds = new SwerveRequest.ApplyRobotSpeeds();
|
||||
|
||||
private void configureAutoBuilder() {
|
||||
private void configureAutoBuilder() {
|
||||
try {
|
||||
RobotConfig config = RobotConfig.fromGUISettings();
|
||||
AutoBuilder.configure(
|
||||
() -> getState().Pose,
|
||||
this::resetPose,
|
||||
() -> getState().Speeds,
|
||||
(speeds, feedforwards) -> setControl(
|
||||
m_pathApplyRobotSpeeds.withSpeeds(ChassisSpeeds.discretize(speeds, 0.020))
|
||||
.withWheelForceFeedforwardsX(feedforwards.robotRelativeForcesXNewtons())
|
||||
.withWheelForceFeedforwardsY(feedforwards.robotRelativeForcesYNewtons())),
|
||||
new PPHolonomicDriveController(
|
||||
new PIDConstants(10, 0, 0),
|
||||
new PIDConstants(7, 0, 0)),
|
||||
config,
|
||||
() -> DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Red,
|
||||
this);
|
||||
() -> getState().Pose,
|
||||
this::resetPose,
|
||||
() -> getState().Speeds,
|
||||
(speeds, feedforwards) -> setControl(
|
||||
m_pathApplyRobotSpeeds.withSpeeds(ChassisSpeeds.discretize(speeds, 0.020))
|
||||
.withWheelForceFeedforwardsX(feedforwards.robotRelativeForcesXNewtons())
|
||||
.withWheelForceFeedforwardsY(feedforwards.robotRelativeForcesYNewtons())
|
||||
),
|
||||
new PPHolonomicDriveController(
|
||||
new PIDConstants(10, 0, 0),
|
||||
new PIDConstants(7, 0, 0)
|
||||
),
|
||||
config,
|
||||
() -> DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Red,
|
||||
this
|
||||
);
|
||||
} catch (Exception ex) {
|
||||
DriverStation.reportError("Failed to load PathPlanner config and configure AutoBuilder",
|
||||
ex.getStackTrace());
|
||||
DriverStation.reportError("Failed to load PathPlanner config and configure AutoBuilder", ex.getStackTrace());
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructs a CTRE SwerveDrivetrain using the specified constants.
|
||||
* <p>
|
||||
* This constructs the underlying hardware devices, so users should not
|
||||
* construct
|
||||
* the devices themselves. If they need the devices, they can access them
|
||||
* through
|
||||
* This constructs the underlying hardware devices, so users should not construct
|
||||
* the devices themselves. If they need the devices, they can access them through
|
||||
* getters in the classes.
|
||||
*
|
||||
* @param drivetrainConstants Drivetrain-wide constants for the swerve drive
|
||||
* @param modules Constants for each specific module
|
||||
* @param drivetrainConstants Drivetrain-wide constants for the swerve drive
|
||||
* @param modules Constants for each specific module
|
||||
*/
|
||||
public CommandSwerveDrivetrain(
|
||||
SwerveDrivetrainConstants drivetrainConstants,
|
||||
SwerveModuleConstants<?, ?, ?>... modules) {
|
||||
SwerveDrivetrainConstants drivetrainConstants,
|
||||
SwerveModuleConstants<?, ?, ?>... modules
|
||||
) {
|
||||
super(drivetrainConstants, modules);
|
||||
if (Utils.isSimulation()) {
|
||||
startSimThread();
|
||||
@@ -172,10 +166,8 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
||||
/**
|
||||
* Constructs a CTRE SwerveDrivetrain using the specified constants.
|
||||
* <p>
|
||||
* This constructs the underlying hardware devices, so users should not
|
||||
* construct
|
||||
* the devices themselves. If they need the devices, they can access them
|
||||
* through
|
||||
* This constructs the underlying hardware devices, so users should not construct
|
||||
* the devices themselves. If they need the devices, they can access them through
|
||||
* getters in the classes.
|
||||
*
|
||||
* @param drivetrainConstants Drivetrain-wide constants for the swerve drive
|
||||
@@ -185,9 +177,10 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
||||
* @param modules Constants for each specific module
|
||||
*/
|
||||
public CommandSwerveDrivetrain(
|
||||
SwerveDrivetrainConstants drivetrainConstants,
|
||||
double odometryUpdateFrequency,
|
||||
SwerveModuleConstants<?, ?, ?>... modules) {
|
||||
SwerveDrivetrainConstants drivetrainConstants,
|
||||
double odometryUpdateFrequency,
|
||||
SwerveModuleConstants<?, ?, ?>... modules
|
||||
) {
|
||||
super(drivetrainConstants, odometryUpdateFrequency, modules);
|
||||
if (Utils.isSimulation()) {
|
||||
startSimThread();
|
||||
@@ -198,38 +191,30 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
||||
/**
|
||||
* Constructs a CTRE SwerveDrivetrain using the specified constants.
|
||||
* <p>
|
||||
* This constructs the underlying hardware devices, so users should not
|
||||
* construct
|
||||
* the devices themselves. If they need the devices, they can access them
|
||||
* through
|
||||
* This constructs the underlying hardware devices, so users should not construct
|
||||
* the devices themselves. If they need the devices, they can access them through
|
||||
* getters in the classes.
|
||||
*
|
||||
* @param drivetrainConstants Drivetrain-wide constants for the swerve
|
||||
* drive
|
||||
* @param drivetrainConstants Drivetrain-wide constants for the swerve drive
|
||||
* @param odometryUpdateFrequency The frequency to run the odometry loop. If
|
||||
* unspecified or set to 0 Hz, this is 250 Hz
|
||||
* on
|
||||
* unspecified or set to 0 Hz, this is 250 Hz on
|
||||
* CAN FD, and 100 Hz on CAN 2.0.
|
||||
* @param odometryStandardDeviation The standard deviation for odometry
|
||||
* calculation
|
||||
* in the form [x, y, theta]ᵀ, with units in
|
||||
* meters
|
||||
* @param odometryStandardDeviation The standard deviation for odometry calculation
|
||||
* in the form [x, y, theta]ᵀ, with units in meters
|
||||
* and radians
|
||||
* @param visionStandardDeviation The standard deviation for vision
|
||||
* calculation
|
||||
* in the form [x, y, theta]ᵀ, with units in
|
||||
* meters
|
||||
* @param visionStandardDeviation The standard deviation for vision calculation
|
||||
* in the form [x, y, theta]ᵀ, with units in meters
|
||||
* and radians
|
||||
* @param modules Constants for each specific module
|
||||
*/
|
||||
public CommandSwerveDrivetrain(
|
||||
SwerveDrivetrainConstants drivetrainConstants,
|
||||
double odometryUpdateFrequency,
|
||||
Matrix<N3, N1> odometryStandardDeviation,
|
||||
Matrix<N3, N1> visionStandardDeviation,
|
||||
SwerveModuleConstants<?, ?, ?>... modules) {
|
||||
super(drivetrainConstants, odometryUpdateFrequency, odometryStandardDeviation, visionStandardDeviation,
|
||||
modules);
|
||||
SwerveDrivetrainConstants drivetrainConstants,
|
||||
double odometryUpdateFrequency,
|
||||
Matrix<N3, N1> odometryStandardDeviation,
|
||||
Matrix<N3, N1> visionStandardDeviation,
|
||||
SwerveModuleConstants<?, ?, ?>... modules
|
||||
) {
|
||||
super(drivetrainConstants, odometryUpdateFrequency, odometryStandardDeviation, visionStandardDeviation, modules);
|
||||
if (Utils.isSimulation()) {
|
||||
startSimThread();
|
||||
}
|
||||
@@ -237,8 +222,7 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns a command that applies the specified control request to this swerve
|
||||
* drivetrain.
|
||||
* Returns a command that applies the specified control request to this swerve drivetrain.
|
||||
*
|
||||
* @param request Function returning the request to apply
|
||||
* @return Command to run
|
||||
@@ -246,26 +230,43 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
||||
public Command applyRequest(Supplier<SwerveRequest> request) {
|
||||
return run(() -> this.setControl(request.get()));
|
||||
}
|
||||
public Command sysIdQuasistatic(SysIdRoutine.Direction direction) {
|
||||
return m_sysIdRoutineToApply.quasistatic(direction);
|
||||
}
|
||||
|
||||
/**
|
||||
* Runs the SysId Dynamic test in the given direction for the routine
|
||||
* specified by {@link #m_sysIdRoutineToApply}.
|
||||
*
|
||||
* @param direction Direction of the SysId Dynamic test
|
||||
* @return Command to run
|
||||
*/
|
||||
public Command sysIdDynamic(SysIdRoutine.Direction direction) {
|
||||
return m_sysIdRoutineToApply.dynamic(direction);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
if(getPigeon2().getYaw().getValueAsDouble() > 360){
|
||||
getPigeon2().setYaw(getPigeon2().getYaw().getValueAsDouble()-360);
|
||||
}
|
||||
else if(getPigeon2().getYaw().getValueAsDouble() < 0){
|
||||
getPigeon2().setYaw(getPigeon2().getYaw().getValueAsDouble()+360);
|
||||
}
|
||||
/*
|
||||
* Periodically try to apply the operator perspective.
|
||||
* If we haven't applied the operator perspective before, then we should apply
|
||||
* it regardless of DS state.
|
||||
* This allows us to correct the perspective in case the robot code restarts
|
||||
* mid-match.
|
||||
* Otherwise, only check and apply the operator perspective if the DS is
|
||||
* disabled.
|
||||
* This ensures driving behavior doesn't change until an explicit disable event
|
||||
* occurs during testing.
|
||||
* If we haven't applied the operator perspective before, then we should apply it regardless of DS state.
|
||||
* This allows us to correct the perspective in case the robot code restarts mid-match.
|
||||
* Otherwise, only check and apply the operator perspective if the DS is disabled.
|
||||
* This ensures driving behavior doesn't change until an explicit disable event occurs during testing.
|
||||
*/
|
||||
if (!m_hasAppliedOperatorPerspective || DriverStation.isDisabled()) {
|
||||
DriverStation.getAlliance().ifPresent(allianceColor -> {
|
||||
setOperatorPerspectiveForward(
|
||||
allianceColor == Alliance.Red
|
||||
? kRedAlliancePerspectiveRotation
|
||||
: kBlueAlliancePerspectiveRotation);
|
||||
allianceColor == Alliance.Red
|
||||
? kRedAlliancePerspectiveRotation
|
||||
: kBlueAlliancePerspectiveRotation
|
||||
);
|
||||
m_hasAppliedOperatorPerspective = true;
|
||||
});
|
||||
}
|
||||
@@ -287,14 +288,11 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
||||
}
|
||||
|
||||
/**
|
||||
* Adds a vision measurement to the Kalman Filter. This will correct the
|
||||
* odometry pose estimate
|
||||
* Adds a vision measurement to the Kalman Filter. This will correct the odometry pose estimate
|
||||
* while still accounting for measurement noise.
|
||||
*
|
||||
* @param visionRobotPoseMeters The pose of the robot as measured by the vision
|
||||
* camera.
|
||||
* @param timestampSeconds The timestamp of the vision measurement in
|
||||
* seconds.
|
||||
* @param visionRobotPoseMeters The pose of the robot as measured by the vision camera.
|
||||
* @param timestampSeconds The timestamp of the vision measurement in seconds.
|
||||
*/
|
||||
@Override
|
||||
public void addVisionMeasurement(Pose2d visionRobotPoseMeters, double timestampSeconds) {
|
||||
@@ -302,74 +300,35 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
||||
}
|
||||
|
||||
/**
|
||||
* Adds a vision measurement to the Kalman Filter. This will correct the
|
||||
* odometry pose estimate
|
||||
* Adds a vision measurement to the Kalman Filter. This will correct the odometry pose estimate
|
||||
* while still accounting for measurement noise.
|
||||
* <p>
|
||||
* Note that the vision measurement standard deviations passed into this method
|
||||
* will continue to apply to future measurements until a subsequent call to
|
||||
* {@link #setVisionMeasurementStdDevs(Matrix)} or this method.
|
||||
*
|
||||
* @param visionRobotPoseMeters The pose of the robot as measured by the
|
||||
* vision camera.
|
||||
* @param timestampSeconds The timestamp of the vision measurement in
|
||||
* seconds.
|
||||
* @param visionMeasurementStdDevs Standard deviations of the vision pose
|
||||
* measurement
|
||||
* in the form [x, y, theta]ᵀ, with units in
|
||||
* meters and radians.
|
||||
* @param visionRobotPoseMeters The pose of the robot as measured by the vision camera.
|
||||
* @param timestampSeconds The timestamp of the vision measurement in seconds.
|
||||
* @param visionMeasurementStdDevs Standard deviations of the vision pose measurement
|
||||
* in the form [x, y, theta]ᵀ, with units in meters and radians.
|
||||
*/
|
||||
@Override
|
||||
public void addVisionMeasurement(
|
||||
Pose2d visionRobotPoseMeters,
|
||||
double timestampSeconds,
|
||||
Matrix<N3, N1> visionMeasurementStdDevs) {
|
||||
super.addVisionMeasurement(visionRobotPoseMeters, Utils.fpgaToCurrentTime(timestampSeconds),
|
||||
visionMeasurementStdDevs);
|
||||
Pose2d visionRobotPoseMeters,
|
||||
double timestampSeconds,
|
||||
Matrix<N3, N1> visionMeasurementStdDevs
|
||||
) {
|
||||
super.addVisionMeasurement(visionRobotPoseMeters, Utils.fpgaToCurrentTime(timestampSeconds), visionMeasurementStdDevs);
|
||||
}
|
||||
|
||||
/**
|
||||
* Return the pose at a given timestamp, if the buffer is not empty.
|
||||
*
|
||||
* @param timestampSeconds The timestamp of the pose in seconds.
|
||||
* @return The pose at the given timestamp (or Optional.empty() if the buffer is
|
||||
* empty).
|
||||
* @return The pose at the given timestamp (or Optional.empty() if the buffer is empty).
|
||||
*/
|
||||
@Override
|
||||
public Optional<Pose2d> samplePoseAt(double timestampSeconds) {
|
||||
return super.samplePoseAt(Utils.fpgaToCurrentTime(timestampSeconds));
|
||||
}
|
||||
|
||||
private SwerveRequest.FieldCentricFacingAngle fieldCentricFacingAngle = new FieldCentricFacingAngle()
|
||||
.withDriveRequestType(DriveRequestType.OpenLoopVoltage).withHeadingPID(7, 0, 0);
|
||||
|
||||
public Command viserReservoir(Supplier<Double> velocityX, Supplier<Double> velocityY) {
|
||||
return runEnd(() -> {
|
||||
Translation2d diff = Coordinates.diffFromHub(getState().Pose.getTranslation());
|
||||
Rotation2d angle = diff.getAngle();
|
||||
setControl(fieldCentricFacingAngle
|
||||
.withTargetDirection(angle)
|
||||
.withVelocityX(velocityX.get())
|
||||
.withVelocityY(velocityY.get()));
|
||||
}, () -> setControl(fieldCentricFacingAngle.withVelocityX(0).withVelocityY(0)));
|
||||
}
|
||||
|
||||
public Command allerGrimper(Supplier<Translation2d> diffSupplier) {
|
||||
return runEnd(() -> {
|
||||
Translation2d diff = diffSupplier.get();
|
||||
Rotation2d angle = diff.getAngle().rotateBy(new Rotation2d(Degrees.of(-90)));
|
||||
setControl(fieldCentricFacingAngle
|
||||
.withTargetDirection(angle)
|
||||
.withVelocityX(diff.getX())
|
||||
.withVelocityY(diff.getY()));
|
||||
}, () -> setControl(fieldCentricFacingAngle.withVelocityX(0).withVelocityY(0)));
|
||||
}
|
||||
|
||||
public Command allerGrimpeMur() {
|
||||
return allerGrimper(() -> Coordinates.diffFromGrimpeMur(getState().Pose.getTranslation()));
|
||||
}
|
||||
|
||||
public Command allerGrimpeDepot() {
|
||||
return allerGrimper(() -> Coordinates.diffFromGrimpeDepot(getState().Pose.getTranslation()));
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1,33 +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 com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||
import com.revrobotics.spark.SparkMax;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Demeleur extends SubsystemBase {
|
||||
|
||||
SparkMax moteur = new SparkMax(19, MotorType.kBrushless);
|
||||
|
||||
/** Creates a new Demeleur. */
|
||||
public Demeleur() {
|
||||
}
|
||||
|
||||
public Command run() {
|
||||
return startEnd(() -> moteur.set(1), () -> moteur.set(0));
|
||||
}
|
||||
|
||||
public Command inverse() {
|
||||
return startEnd(() -> moteur.set(-0.2), () -> moteur.set(0));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
}
|
||||
}
|
||||
@@ -4,76 +4,63 @@
|
||||
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import com.revrobotics.PersistMode;
|
||||
import com.revrobotics.RelativeEncoder;
|
||||
import com.revrobotics.ResetMode;
|
||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||
import com.revrobotics.spark.SparkMax;
|
||||
import com.revrobotics.spark.config.SoftLimitConfig;
|
||||
import com.revrobotics.spark.config.SparkBaseConfig;
|
||||
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
|
||||
import com.revrobotics.spark.config.SparkMaxConfig;
|
||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||
|
||||
import edu.wpi.first.networktables.GenericEntry;
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Grimpeur extends SubsystemBase {
|
||||
ShuffleboardTab teb = Shuffleboard.getTab("teb");
|
||||
SparkMax moteur1 = new SparkMax(3, MotorType.kBrushless);
|
||||
SparkMax moteur2 = new SparkMax(12, MotorType.kBrushless);
|
||||
RelativeEncoder encoder1 = moteur1.getEncoder();
|
||||
RelativeEncoder encoder2 = moteur2.getEncoder();
|
||||
|
||||
private double vitesseSortir = 0.5;
|
||||
private double vitesseEntrer = -0.4;
|
||||
|
||||
private GenericEntry ntEncodeurGrimpeur = teb.add("Position haut grimpeur", 101).getEntry();
|
||||
|
||||
private double maxEncodeur = ntEncodeurGrimpeur.getDouble(101);
|
||||
SparkMax grimpeur1 = new SparkMax(3, MotorType.kBrushless);
|
||||
SparkMax grimpeur2 = new SparkMax(12, MotorType.kBrushless);
|
||||
|
||||
// SparkMaxConfig slaveConfig = new SparkMaxConfig();
|
||||
DigitalInput limit = new DigitalInput(0);
|
||||
private GenericEntry EncodeurGrimpeur = teb.add("Position haut grimpeur", 100).getEntry();
|
||||
|
||||
// public void Grimper(double vitesse){
|
||||
// grimpeur1.configure(slaveConfig, ResetMode.kNoResetSafeParameters,
|
||||
// PersistMode.kPersistParameters);
|
||||
// grimpeur2.configure(slaveConfig.follow(grimpeur1),
|
||||
// ResetMode.kNoResetSafeParameters, PersistMode.kPersistParameters);
|
||||
// grimpeur1.set(vitesse);
|
||||
// }
|
||||
public void GrimperGauche(double vitesse) {
|
||||
grimpeur1.set(vitesse);
|
||||
}
|
||||
|
||||
public void GrimperDroit(double vitesse) {
|
||||
grimpeur2.set(vitesse);
|
||||
}
|
||||
|
||||
public double Position() {
|
||||
return grimpeur1.getEncoder().getPosition();
|
||||
}
|
||||
|
||||
public void Reset() {
|
||||
grimpeur1.getEncoder().setPosition(0);
|
||||
}
|
||||
|
||||
public boolean Limit() {
|
||||
return limit.get();
|
||||
}
|
||||
|
||||
public double PositionFinal() {
|
||||
return EncodeurGrimpeur.getDouble(100);
|
||||
}
|
||||
|
||||
/** Creates a new Grimpeur. */
|
||||
public Grimpeur() {
|
||||
teb.addDouble("encodeur grimpeur", encoder1::getPosition);
|
||||
teb.addBoolean("limit grimpeur", limit::get);
|
||||
configMoteurs();
|
||||
}
|
||||
|
||||
private void configMoteurs() {
|
||||
SparkBaseConfig configMoteur = new SparkMaxConfig().apply(
|
||||
new SoftLimitConfig().forwardSoftLimit(maxEncodeur).forwardSoftLimitEnabled(true)
|
||||
.reverseSoftLimit(0).reverseSoftLimitEnabled(true))
|
||||
.openLoopRampRate(0.1)
|
||||
.idleMode(IdleMode.kBrake);
|
||||
moteur1.configure(configMoteur, ResetMode.kNoResetSafeParameters, PersistMode.kPersistParameters);
|
||||
moteur2.configure(configMoteur.follow(moteur1), ResetMode.kNoResetSafeParameters, PersistMode.kPersistParameters);
|
||||
}
|
||||
|
||||
public Command sortir() {
|
||||
return startEnd(() -> moteur1.set(vitesseSortir), () -> moteur1.set(0))
|
||||
.until(() -> moteur1.getForwardSoftLimit().isReached() || moteur2.getForwardSoftLimit().isReached());
|
||||
}
|
||||
|
||||
public Command rentrer() {
|
||||
return startEnd(() -> moteur1.set(vitesseEntrer), () -> moteur1.set(0))
|
||||
.until(() -> moteur1.getReverseSoftLimit().isReached() || moteur2.getReverseSoftLimit().isReached());
|
||||
teb.addDouble("encodeur grimpeur", this::Position);
|
||||
teb.addBoolean("limit grimpeur", this::Limit);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
if (limit.get()) {
|
||||
encoder1.setPosition(0);
|
||||
encoder2.setPosition(0);
|
||||
}
|
||||
|
||||
double newEncoderMax = ntEncodeurGrimpeur.getDouble(maxEncodeur);
|
||||
if (newEncoderMax != maxEncodeur) {
|
||||
maxEncodeur = newEncoderMax;
|
||||
configMoteurs();
|
||||
}
|
||||
// This method will be called once per scheduler run
|
||||
}
|
||||
}
|
||||
|
||||
149
src/main/java/frc/robot/subsystems/LEDSubsystem.java
Normal file
149
src/main/java/frc/robot/subsystems/LEDSubsystem.java
Normal file
@@ -0,0 +1,149 @@
|
||||
// /* Generated by Phoenix Tuner X */
|
||||
// package frc.robot.subsystems;
|
||||
|
||||
// import edu.wpi.first.networktables.GenericEntry;
|
||||
// import edu.wpi.first.wpilibj.DriverStation;
|
||||
// import edu.wpi.first.wpilibj.Timer;
|
||||
// import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
|
||||
// import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
// import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
// import edu.wpi.first.wpilibj2.command.Command;
|
||||
// import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
// import com.ctre.phoenix6.CANBus;
|
||||
// import com.ctre.phoenix6.controls.SolidColor;
|
||||
// import com.ctre.phoenix6.hardware.CANdle;
|
||||
// import com.ctre.phoenix6.signals.RGBWColor;
|
||||
|
||||
// /**
|
||||
// * Subsystem that controls an addressable LED strip using a CANdle.
|
||||
// */
|
||||
// public class LEDSubsystem extends SubsystemBase {
|
||||
// Timer _timer;
|
||||
// boolean q = true;
|
||||
// ShuffleboardTab teb = Shuffleboard.getTab("teb");
|
||||
// private GenericEntry equipe =
|
||||
// teb.add("equipe commence (bleu = ouvert, rouge = fermé)", true).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
||||
// private final CANBus kCANBus = new CANBus("rio");
|
||||
// private final CANdle m_candle = new CANdle(17, kCANBus);
|
||||
// public void Bleu(){
|
||||
// m_candle.setControl(new SolidColor(0, 80).withColor(new RGBWColor(255, 0, 0, 0)));
|
||||
// }
|
||||
// public void Rouge(){
|
||||
// m_candle.setControl(new SolidColor(0, 80).withColor(new RGBWColor(0, 0, 255, 0)));
|
||||
// }
|
||||
// public void Vert(){
|
||||
// m_candle.setControl(new SolidColor(0, 80).withColor(new RGBWColor(0, 255, 0, 0)));
|
||||
// }
|
||||
// public void Noir(){
|
||||
|
||||
// m_candle.setControl(new SolidColor(0, 80).withColor(new RGBWColor(0, 0, 0, 0)));
|
||||
// }
|
||||
// public void Flash(boolean couleur){
|
||||
// Timer timer = new Timer();
|
||||
// if(timer.get() <0.5){
|
||||
// if(couleur){
|
||||
// Bleu();
|
||||
// }
|
||||
// else{
|
||||
// Rouge();
|
||||
// }
|
||||
// }
|
||||
// else{
|
||||
// Noir();
|
||||
// timer.reset();
|
||||
// }
|
||||
// }
|
||||
// public LEDSubsystem() {
|
||||
// setDefaultCommand(updateLEDs());
|
||||
// _timer = new Timer();
|
||||
// _timer.start();
|
||||
// }
|
||||
// public boolean Equipe(){
|
||||
// return equipe.getBoolean(false);
|
||||
// }
|
||||
// /**
|
||||
// * Updates the animations and LEDs of the CANdle.
|
||||
// *
|
||||
// * @return Command to run
|
||||
// */
|
||||
// public Command updateLEDs() {
|
||||
// return run(() -> {
|
||||
// // if(q){
|
||||
// // _timer.reset();
|
||||
// // q = false;
|
||||
// // }
|
||||
// double temps = _timer.get();
|
||||
// System.out.println(temps);
|
||||
// if(Equipe()){
|
||||
// if(temps > 30){
|
||||
// Vert();
|
||||
// }
|
||||
// else if(temps > 52){
|
||||
|
||||
// Bleu();
|
||||
// }
|
||||
// else if(temps > 55){
|
||||
// Flash(true);
|
||||
// }
|
||||
// else if(temps > 67){
|
||||
// Rouge();
|
||||
// }
|
||||
// else if(temps > 70){
|
||||
// Flash(false);
|
||||
// }
|
||||
// else if(temps > 103){
|
||||
// Bleu();
|
||||
// }
|
||||
// else if(temps > 105){
|
||||
// Flash(true);
|
||||
// }
|
||||
// else if(temps > 127){
|
||||
// Rouge();
|
||||
// }
|
||||
// else if(temps > 130){
|
||||
// Flash(false);
|
||||
// }
|
||||
// else if(temps < 140){
|
||||
// Vert();
|
||||
// }
|
||||
// }
|
||||
// else{
|
||||
// if(temps > 110){
|
||||
// Vert();
|
||||
// }
|
||||
// else if(temps > 88){
|
||||
|
||||
// Rouge();
|
||||
// }
|
||||
// else if(temps > 85){
|
||||
// Flash(false);
|
||||
// }
|
||||
// else if(temps > 63){
|
||||
// Bleu();
|
||||
// }
|
||||
// else if(temps > 60){
|
||||
// Flash(true);
|
||||
// }
|
||||
// else if(temps > 33){
|
||||
// Rouge();
|
||||
// }
|
||||
// else if(temps > 30){
|
||||
// Flash(false);
|
||||
// }
|
||||
// else if(temps > 13){
|
||||
// Bleu();
|
||||
// }
|
||||
// else if(temps > 10){
|
||||
// Flash(true);
|
||||
// }
|
||||
// else if(temps < 10){
|
||||
// Vert();
|
||||
// }
|
||||
// }
|
||||
// // _timer.stop();
|
||||
|
||||
// });
|
||||
// }
|
||||
// }
|
||||
|
||||
@@ -4,71 +4,48 @@
|
||||
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import java.util.function.Supplier;
|
||||
|
||||
import com.revrobotics.PersistMode;
|
||||
import com.revrobotics.RelativeEncoder;
|
||||
import com.revrobotics.ResetMode;
|
||||
import com.revrobotics.spark.SparkBase.ControlType;
|
||||
import com.revrobotics.spark.SparkFlex;
|
||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||
import com.revrobotics.spark.config.ClosedLoopConfig;
|
||||
import com.revrobotics.spark.config.SparkBaseConfig;
|
||||
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
|
||||
import com.revrobotics.spark.config.SparkMaxConfig;
|
||||
import com.revrobotics.spark.SparkMax;
|
||||
|
||||
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.Command;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Lanceur extends SubsystemBase {
|
||||
ShuffleboardTab teb = Shuffleboard.getTab("teb");
|
||||
|
||||
SparkFlex moteur1 = new SparkFlex(15, MotorType.kBrushless);
|
||||
SparkFlex moteur2 = new SparkFlex(18, MotorType.kBrushless);
|
||||
SparkMax Demeleur = new SparkMax(19, MotorType.kBrushless);
|
||||
GenericEntry vitesse =
|
||||
teb.add("vitesse lanceur",4000).getEntry();
|
||||
GenericEntry AmpLanceur =
|
||||
teb.add("ampérage lanceur",30).getEntry();
|
||||
|
||||
RelativeEncoder encoder = moteur1.getEncoder();
|
||||
|
||||
GenericEntry vitesse = teb.add("vitesse lanceur", 4000).getEntry();
|
||||
GenericEntry AmpLanceur = teb.add("ampérage lanceur", 30).getEntry();
|
||||
|
||||
public void Lancer(double vitesse){
|
||||
moteur1.set(vitesse);
|
||||
moteur2.set(vitesse);
|
||||
}
|
||||
public void Demeler(double vitesse){
|
||||
Demeleur.set(vitesse);
|
||||
}
|
||||
public double Vitesse(){
|
||||
return moteur1.getEncoder().getVelocity();
|
||||
}
|
||||
public double Amp(){
|
||||
return moteur1.getOutputCurrent();
|
||||
}
|
||||
public double AmpBas(){
|
||||
return AmpLanceur.getDouble(30);
|
||||
}
|
||||
public double vitesseDemander(){
|
||||
return vitesse.getDouble(4000);
|
||||
}
|
||||
/** Creates a new Lanceur. */
|
||||
public Lanceur() {
|
||||
teb.addDouble("amperage lanceur", moteur1::getOutputCurrent);
|
||||
teb.addDouble("vitesse actuelle", encoder::getVelocity);
|
||||
configMoteurs();
|
||||
}
|
||||
|
||||
private void configMoteurs() {
|
||||
SparkBaseConfig configMoteur = new SparkMaxConfig().apply(
|
||||
new ClosedLoopConfig().pid(0.0007, 0, 0))
|
||||
.openLoopRampRate(0.1)
|
||||
.idleMode(IdleMode.kCoast);
|
||||
moteur1.configure(configMoteur, ResetMode.kNoResetSafeParameters, PersistMode.kPersistParameters);
|
||||
moteur2.configure(configMoteur.follow(moteur1), ResetMode.kNoResetSafeParameters, PersistMode.kPersistParameters);
|
||||
}
|
||||
|
||||
public Command lancer(Supplier<Double> vitesse) {
|
||||
return runEnd(() -> moteur1.getClosedLoopController().setSetpoint(vitesse.get(), ControlType.kVelocity),
|
||||
() -> moteur1.set(0));
|
||||
}
|
||||
|
||||
public Command inverse() {
|
||||
return startEnd(() -> moteur1.set(-0.2), () -> moteur1.set(0));
|
||||
}
|
||||
|
||||
public double getVitesse() {
|
||||
return encoder.getVelocity();
|
||||
}
|
||||
|
||||
public boolean setPointAtteint() {
|
||||
return getVitesse() >= moteur1.getClosedLoopController().getSetpoint() * 0.95;
|
||||
}
|
||||
|
||||
public double ntBasseVitesse() {
|
||||
return vitesse.getDouble(4000);
|
||||
teb.addDouble("amperage lanceur", this::Amp);
|
||||
teb.addDouble("vitesse actuelle",this::Vitesse);
|
||||
}
|
||||
|
||||
@Override
|
||||
@@ -76,3 +53,4 @@ public class Lanceur extends SubsystemBase {
|
||||
// This method will be called once per scheduler run
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -1,145 +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 com.ctre.phoenix.led.CANdle;
|
||||
import com.ctre.phoenix.led.RainbowAnimation;
|
||||
|
||||
import edu.wpi.first.networktables.GenericEntry;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Led extends SubsystemBase {
|
||||
ShuffleboardTab teb = Shuffleboard.getTab("teb");
|
||||
private GenericEntry equipe =
|
||||
teb.add("equipe commence (bleu = ouvert, rouge = fermé)", true).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
||||
@SuppressWarnings("removal")
|
||||
CANdle CANDle = new CANdle(17);
|
||||
@SuppressWarnings("removal")
|
||||
RainbowAnimation rainbowAnim = new RainbowAnimation();
|
||||
@SuppressWarnings("removal")
|
||||
public void bleu(){
|
||||
CANDle.setLEDs(0, 0, 255,0,0,8);
|
||||
CANDle.setLEDs(0, 0, 255,0,16,8);
|
||||
CANDle.setLEDs(0, 0, 255,0,32,8);
|
||||
// CANDle.setLEDs(0, 0, 255,0,56,8);
|
||||
// CANDle.setLEDs(0, 0, 255,0,72,8);
|
||||
// CANDle.setLEDs(0, 0, 255,0,88,8);
|
||||
// CANDle.setLEDs(0, 0, 255,0,104,8);
|
||||
// CANDle.setLEDs(0, 0, 255,0,120,8);
|
||||
// CANDle.setLEDs(0, 0, 255,0,136,8);
|
||||
|
||||
}
|
||||
@SuppressWarnings("removal")
|
||||
public void Vert1(){
|
||||
CANDle.setLEDs(0, 255, 0,0,0,8);
|
||||
CANDle.setLEDs(0, 255, 0,0,16,8);
|
||||
CANDle.setLEDs(0, 255, 0,0,32,8);
|
||||
// CANDle.setLEDs(0, 255, 0,0,56,8);
|
||||
// CANDle.setLEDs(0, 255, 0,0,72,8);
|
||||
// CANDle.setLEDs(0, 255, 0,0,88,8);
|
||||
// CANDle.setLEDs(0, 255, 0,0,104,8);
|
||||
// CANDle.setLEDs(0, 255, 0,0,120,8);
|
||||
// CANDle.setLEDs(0, 255, 0,0,136,8);
|
||||
}
|
||||
@SuppressWarnings("removal")
|
||||
public void Rouge(){
|
||||
CANDle.setLEDs(255, 0, 0,0,0,8);
|
||||
CANDle.setLEDs(255, 0, 0,0,16,8);
|
||||
CANDle.setLEDs(255, 0, 0,0,32,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,48,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,64,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,80,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,96,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,112,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,128,8);
|
||||
}
|
||||
@SuppressWarnings("removal")
|
||||
public void Jaune2(){
|
||||
CANDle.setLEDs(255, 255, 0,0,8,8);
|
||||
CANDle.setLEDs(255, 255, 0,0,24,8);
|
||||
CANDle.setLEDs(255, 255, 0,0,40,8);
|
||||
// CANDle.setLEDs(255, 255, 0,0,56,8);
|
||||
// CANDle.setLEDs(255, 255, 0,0,72,8);
|
||||
// CANDle.setLEDs(255, 255, 0,0,88,8);
|
||||
// CANDle.setLEDs(255, 255, 0,0,104,8);
|
||||
// CANDle.setLEDs(255, 255, 0,0,120,8);
|
||||
// CANDle.setLEDs(255, 255, 0,0,136,8);
|
||||
}
|
||||
@SuppressWarnings("removal")
|
||||
public void Rouge2(){
|
||||
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);
|
||||
// CANDle.setLEDs(255, 0, 0,0,72,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,88,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,104,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,120,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,136,8);
|
||||
}
|
||||
@SuppressWarnings("removal")
|
||||
public void RainBow(){
|
||||
CANDle.animate(rainbowAnim);
|
||||
}
|
||||
@SuppressWarnings("removal")
|
||||
public void RainBowStop(){
|
||||
CANDle.animate(null);
|
||||
}
|
||||
public boolean Equipe(){
|
||||
return equipe.getBoolean(true);
|
||||
}
|
||||
/** Creates a new Led. */
|
||||
public Led() {}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
|
||||
double temps = DriverStation.getMatchTime();
|
||||
if(temps > 20 && temps < 30){
|
||||
Vert1();
|
||||
}
|
||||
if(Equipe()){
|
||||
if(temps > 30 && temps < 55){
|
||||
bleu();
|
||||
}
|
||||
else if(temps > 30 && temps < 80){
|
||||
Rouge();
|
||||
}
|
||||
else if(temps > 80 && temps < 105){
|
||||
bleu();
|
||||
}
|
||||
else if(temps > 105 && temps < 130){
|
||||
Rouge();
|
||||
}
|
||||
else{
|
||||
RainBow();
|
||||
}
|
||||
}
|
||||
else{
|
||||
if(temps > 30 && temps < 55){
|
||||
Rouge();
|
||||
}
|
||||
else if(temps > 30 && temps < 80){
|
||||
bleu();
|
||||
}
|
||||
else if(temps > 80 && temps < 105){
|
||||
Rouge();
|
||||
}
|
||||
else if(temps > 105 && temps < 130){
|
||||
bleu();
|
||||
}
|
||||
else{
|
||||
RainBow();
|
||||
}
|
||||
}
|
||||
// This method will be called once per scheduler run
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
74
src/main/java/frc/robot/subsystems/LimeLight3.java
Normal file
74
src/main/java/frc/robot/subsystems/LimeLight3.java
Normal file
@@ -0,0 +1,74 @@
|
||||
// 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.net.PortForwarder;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.LimelightHelpers;
|
||||
|
||||
public class LimeLight3 extends SubsystemBase {
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-balaie");
|
||||
NetworkTableEntry pipeline = table.getEntry("pipeline");
|
||||
/** Creates a new LimeLight3. */
|
||||
public LimeLight3() {
|
||||
for(int port = 5800; port <=5807; port++){
|
||||
PortForwarder.add(port, "limelight.local", port);
|
||||
}
|
||||
}
|
||||
public double[] getBotPoseBlue(){
|
||||
NetworkTable limelightTable = NetworkTableInstance.getDefault().getTable("limelight-balaie");
|
||||
NetworkTableEntry BotPoseEntry = limelightTable.getEntry("botpose_wpiblue");
|
||||
double[] BotPose = BotPoseEntry.getDoubleArray(new double[7]);
|
||||
return BotPose;
|
||||
}
|
||||
public double[] getBotPoseRed(){
|
||||
NetworkTable limelightTable = NetworkTableInstance.getDefault().getTable("limelight-balaie");
|
||||
NetworkTableEntry BotPoseEntry = limelightTable.getEntry("botpose_wpired");
|
||||
double[] BotPose = BotPoseEntry.getDoubleArray(new double[7]);
|
||||
return BotPose;
|
||||
}
|
||||
public double getTx(){
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-balaie");
|
||||
NetworkTableEntry tx = table.getEntry("tx");
|
||||
return tx.getDouble(0.0);
|
||||
}
|
||||
public double getTId(){
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-balaie");
|
||||
NetworkTableEntry tid = table.getEntry("tid");
|
||||
return tid.getDouble(0.0);
|
||||
}
|
||||
public double getTA(){
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-balaie");
|
||||
NetworkTableEntry ta = table.getEntry("ta");
|
||||
return ta.getDouble(0.0);
|
||||
}
|
||||
public boolean getV(){
|
||||
return LimelightHelpers.getTV("limelight-balaie");
|
||||
}
|
||||
public void AprilTag(){
|
||||
pipeline.setNumber(0);
|
||||
}
|
||||
public void Forme(){
|
||||
pipeline.setNumber(1);
|
||||
}
|
||||
public double Calcule(double x1, double x2, double y1, double y2, double angle)
|
||||
{
|
||||
if (x1 > 4)
|
||||
{
|
||||
return (Math.abs(Math.atan2(x2 - x1, y2 - y1)) * (180 / Math.PI) - angle)/90;
|
||||
}
|
||||
else
|
||||
{
|
||||
return (Math.abs(Math.atan2(x2 - x1, y2 - y1)) * (180 / Math.PI) + angle) * -1/90;
|
||||
}
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
}
|
||||
}
|
||||
82
src/main/java/frc/robot/subsystems/Limelight3G.java
Normal file
82
src/main/java/frc/robot/subsystems/Limelight3G.java
Normal file
@@ -0,0 +1,82 @@
|
||||
// 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.net.PortForwarder;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.LimelightHelpers;
|
||||
|
||||
public class Limelight3G extends SubsystemBase {
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-tag");
|
||||
NetworkTableEntry pipeline = table.getEntry("pipeline");
|
||||
/** Creates a new LimeLight3. */
|
||||
public Limelight3G() {
|
||||
for(int port = 5800; port <=5807; port++){
|
||||
PortForwarder.add(port, "limelight.local", port);
|
||||
}
|
||||
}
|
||||
public double[] getBotPoseBlue(){
|
||||
NetworkTable limelightTable = NetworkTableInstance.getDefault().getTable("limelight-tag");
|
||||
NetworkTableEntry BotPoseEntry = limelightTable.getEntry("botpose_wpiblue");
|
||||
double[] BotPose = BotPoseEntry.getDoubleArray(new double[7]);
|
||||
return BotPose;
|
||||
}
|
||||
public double[] getBotPoseRed(){
|
||||
NetworkTable limelightTable = NetworkTableInstance.getDefault().getTable("limelight-tag");
|
||||
NetworkTableEntry BotPoseEntry = limelightTable.getEntry("botpose_wpired");
|
||||
double[] BotPose = BotPoseEntry.getDoubleArray(new double[7]);
|
||||
return BotPose;
|
||||
}
|
||||
public double getTx(){
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-tag");
|
||||
NetworkTableEntry tx = table.getEntry("tx");
|
||||
return tx.getDouble(0.0);
|
||||
}
|
||||
public double getTId(){
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-tag");
|
||||
NetworkTableEntry tid = table.getEntry("tid");
|
||||
return tid.getDouble(0.0);
|
||||
}
|
||||
public double getTA(){
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-tag");
|
||||
NetworkTableEntry ta = table.getEntry("ta");
|
||||
return ta.getDouble(0.0);
|
||||
}
|
||||
public boolean getV(){
|
||||
return LimelightHelpers.getTV("limelight-tag");
|
||||
}
|
||||
public double Calcule(double x1, double x2, double y1, double y2, double angle)
|
||||
{
|
||||
// if(x1 > x2){
|
||||
// if(y1 > y2){
|
||||
// return Math.atan(90-((x2 - x1) / (y2 - y1))) * (180 / Math.PI) - angle;
|
||||
// }
|
||||
// else{
|
||||
// return Math.atan((x2 - x1) / (y2 - y1)) * (180 / Math.PI)+90 - angle;
|
||||
// }
|
||||
// }
|
||||
// else{
|
||||
// if(y1 > y2){
|
||||
// return Math.atan((x2 - x1) / (y2 - y1))* (180 / Math.PI)+270 - angle;
|
||||
// }
|
||||
// else{
|
||||
// return Math.atan(90-((x2 - x1) / (y2 - y1))) * (180 / Math.PI)+180 - angle;
|
||||
// }
|
||||
// }
|
||||
if(y1 > y2){
|
||||
return Math.toDegrees(Math.atan((x2 - x1) /(y2 - y1))) - angle;
|
||||
}
|
||||
else{
|
||||
return Math.toDegrees(-Math.atan((x2 - x1) / (y2 - y1))) - angle;
|
||||
}
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
}
|
||||
}
|
||||
@@ -1,82 +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 com.revrobotics.PersistMode;
|
||||
import com.revrobotics.RelativeEncoder;
|
||||
import com.revrobotics.ResetMode;
|
||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||
import com.revrobotics.spark.SparkMax;
|
||||
import com.revrobotics.spark.config.SoftLimitConfig;
|
||||
import com.revrobotics.spark.config.SparkBaseConfig;
|
||||
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
|
||||
import com.revrobotics.spark.config.SparkMaxConfig;
|
||||
|
||||
import edu.wpi.first.networktables.GenericEntry;
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class PivotBalayeuse extends SubsystemBase {
|
||||
|
||||
ShuffleboardTab teb = Shuffleboard.getTab("teb");
|
||||
|
||||
SparkMax moteur = new SparkMax(8, MotorType.kBrushless);
|
||||
RelativeEncoder encoder = moteur.getEncoder();
|
||||
DigitalInput limit = new DigitalInput(9);
|
||||
|
||||
private GenericEntry ntEncodeurBalayeuse = teb.add("Position bas balayeuse", 1.8).getEntry();
|
||||
|
||||
private double maxEncodeur = ntEncodeurBalayeuse.getDouble(1.8);
|
||||
|
||||
private double vitesseMonter = 0.5;
|
||||
private double vitesseDescendre = -0.5;
|
||||
|
||||
/** Creates a new PivotBalayeuse. */
|
||||
public PivotBalayeuse() {
|
||||
configMoteurs();
|
||||
}
|
||||
|
||||
private void configMoteurs() {
|
||||
SparkBaseConfig configMoteur = new SparkMaxConfig().apply(
|
||||
new SoftLimitConfig().forwardSoftLimit(maxEncodeur).forwardSoftLimitEnabled(true)
|
||||
.reverseSoftLimit(0.6).reverseSoftLimitEnabled(true))
|
||||
.openLoopRampRate(0.1)
|
||||
.idleMode(IdleMode.kBrake);
|
||||
moteur.configure(configMoteur, ResetMode.kNoResetSafeParameters, PersistMode.kPersistParameters);
|
||||
}
|
||||
|
||||
public Command monter() {
|
||||
return startEnd(() -> moteur.set(vitesseMonter), () -> moteur.set(0))
|
||||
.until(() -> moteur.getForwardSoftLimit().isReached());
|
||||
}
|
||||
|
||||
public Command descendre() {
|
||||
return startEnd(() -> moteur.set(vitesseDescendre), () -> moteur.set(0))
|
||||
.until(() -> moteur.getReverseSoftLimit().isReached());
|
||||
}
|
||||
|
||||
public double EncodeurBalayeuse() {
|
||||
return ntEncodeurBalayeuse.getDouble(1.8);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
teb.addBoolean("limit balayeuse", limit::get);
|
||||
teb.addDouble("encodeur balayeuse", encoder::getPosition);
|
||||
|
||||
if (!limit.get()) {
|
||||
encoder.setPosition(0.6);
|
||||
}
|
||||
|
||||
double newEncoderMax = ntEncodeurBalayeuse.getDouble(maxEncodeur);
|
||||
if (newEncoderMax != maxEncodeur) {
|
||||
maxEncodeur = newEncoderMax;
|
||||
configMoteurs();
|
||||
}
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user