Compare commits
6 Commits
grimpe
...
2b94ebcc95
Author | SHA1 | Date | |
---|---|---|---|
2b94ebcc95 | |||
9796800b4e | |||
cf97a05e6f | |||
688315bcd0 | |||
bd180e9153 | |||
bff426ef0f |
@ -1,97 +0,0 @@
|
|||||||
{
|
|
||||||
"System Joysticks": {
|
|
||||||
"window": {
|
|
||||||
"enabled": false
|
|
||||||
}
|
|
||||||
},
|
|
||||||
"keyboardJoysticks": [
|
|
||||||
{
|
|
||||||
"axisConfig": [
|
|
||||||
{
|
|
||||||
"decKey": 65,
|
|
||||||
"incKey": 68
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"decKey": 87,
|
|
||||||
"incKey": 83
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"decKey": 69,
|
|
||||||
"decayRate": 0.0,
|
|
||||||
"incKey": 82,
|
|
||||||
"keyRate": 0.009999999776482582
|
|
||||||
}
|
|
||||||
],
|
|
||||||
"axisCount": 3,
|
|
||||||
"buttonCount": 4,
|
|
||||||
"buttonKeys": [
|
|
||||||
90,
|
|
||||||
88,
|
|
||||||
67,
|
|
||||||
86
|
|
||||||
],
|
|
||||||
"povConfig": [
|
|
||||||
{
|
|
||||||
"key0": 328,
|
|
||||||
"key135": 323,
|
|
||||||
"key180": 322,
|
|
||||||
"key225": 321,
|
|
||||||
"key270": 324,
|
|
||||||
"key315": 327,
|
|
||||||
"key45": 329,
|
|
||||||
"key90": 326
|
|
||||||
}
|
|
||||||
],
|
|
||||||
"povCount": 1
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"axisConfig": [
|
|
||||||
{
|
|
||||||
"decKey": 74,
|
|
||||||
"incKey": 76
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"decKey": 73,
|
|
||||||
"incKey": 75
|
|
||||||
}
|
|
||||||
],
|
|
||||||
"axisCount": 2,
|
|
||||||
"buttonCount": 4,
|
|
||||||
"buttonKeys": [
|
|
||||||
77,
|
|
||||||
44,
|
|
||||||
46,
|
|
||||||
47
|
|
||||||
],
|
|
||||||
"povCount": 0
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"axisConfig": [
|
|
||||||
{
|
|
||||||
"decKey": 263,
|
|
||||||
"incKey": 262
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"decKey": 265,
|
|
||||||
"incKey": 264
|
|
||||||
}
|
|
||||||
],
|
|
||||||
"axisCount": 2,
|
|
||||||
"buttonCount": 6,
|
|
||||||
"buttonKeys": [
|
|
||||||
260,
|
|
||||||
268,
|
|
||||||
266,
|
|
||||||
261,
|
|
||||||
269,
|
|
||||||
267
|
|
||||||
],
|
|
||||||
"povCount": 0
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"axisCount": 0,
|
|
||||||
"buttonCount": 0,
|
|
||||||
"povCount": 0
|
|
||||||
}
|
|
||||||
]
|
|
||||||
}
|
|
1645
src/main/java/frc/robot/LimelightHelpers.java
Normal file
1645
src/main/java/frc/robot/LimelightHelpers.java
Normal file
File diff suppressed because it is too large
Load Diff
@ -4,40 +4,18 @@
|
|||||||
|
|
||||||
package frc.robot;
|
package frc.robot;
|
||||||
|
|
||||||
import edu.wpi.first.math.MathUtil;
|
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
import edu.wpi.first.wpilibj2.command.Commands;
|
import edu.wpi.first.wpilibj2.command.Commands;
|
||||||
import edu.wpi.first.wpilibj2.command.RunCommand;
|
|
||||||
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
||||||
import frc.robot.commands.GrimperHaut;
|
|
||||||
import frc.robot.commands.GrimpeurBas;
|
|
||||||
import frc.robot.commands.GrimpeurManuel;
|
|
||||||
import frc.robot.commands.ResetGrimpeur;
|
|
||||||
import frc.robot.subsystems.Bougie;
|
|
||||||
import frc.robot.subsystems.Grimpeur;
|
|
||||||
|
|
||||||
public class RobotContainer {
|
public class RobotContainer {
|
||||||
CommandXboxController manette1 = new CommandXboxController(0);
|
CommandXboxController manette1 = new CommandXboxController(0);
|
||||||
CommandXboxController manette2 = new CommandXboxController(1);
|
CommandXboxController manette2 = new CommandXboxController(0);
|
||||||
Grimpeur grimpeur = new Grimpeur();
|
|
||||||
Bougie bougie = new Bougie();
|
|
||||||
GrimpeurManuel grimpeurManuel = new GrimpeurManuel(grimpeur, manette2::getLeftY);
|
|
||||||
public RobotContainer() {
|
public RobotContainer() {
|
||||||
grimpeur.setDefaultCommand(new RunCommand(()->{
|
|
||||||
if(grimpeur.stop()){
|
|
||||||
grimpeur.grimpe(0);
|
|
||||||
}
|
|
||||||
else{
|
|
||||||
grimpeur.grimpe(MathUtil.applyDeadband(manette2.getLeftY(), 0.2));
|
|
||||||
}}, grimpeur));
|
|
||||||
configureBindings();
|
configureBindings();
|
||||||
}
|
}
|
||||||
|
|
||||||
private void configureBindings() {
|
private void configureBindings() {}
|
||||||
manette2.leftBumper().whileTrue(new GrimperHaut(grimpeur,bougie));
|
|
||||||
manette2.rightBumper().whileTrue(new GrimpeurBas(grimpeur));
|
|
||||||
manette2.a().whileTrue(new ResetGrimpeur(grimpeur));
|
|
||||||
}
|
|
||||||
|
|
||||||
public Command getAutonomousCommand() {
|
public Command getAutonomousCommand() {
|
||||||
return Commands.print("No autonomous command configured");
|
return Commands.print("No autonomous command configured");
|
||||||
|
@ -5,40 +5,39 @@
|
|||||||
package frc.robot.commands;
|
package frc.robot.commands;
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
import frc.robot.subsystems.Grimpeur;
|
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 */
|
/* 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 GrimpeurBas extends Command {
|
public class AprilTag3 extends Command {
|
||||||
private Grimpeur grimpeur;
|
private Limelight3 limelight3;
|
||||||
/** Creates a new GrimpeurBas. */
|
/** Creates a new AprilTag3G. */
|
||||||
public GrimpeurBas(Grimpeur grimpeur) {
|
public AprilTag3(Limelight3 limelight3) {
|
||||||
this.grimpeur = grimpeur;
|
this.limelight3 = limelight3;
|
||||||
addRequirements(grimpeur);
|
addRequirements(limelight3);
|
||||||
// Use addRequirements() here to declare subsystem dependencies.
|
// Use addRequirements() here to declare subsystem dependencies.
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called when the command is initially scheduled.
|
// Called when the command is initially scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void initialize() {}
|
public void initialize() {
|
||||||
|
limelight3.Apriltag();
|
||||||
|
}
|
||||||
|
|
||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void execute() {
|
public void execute() {
|
||||||
if(grimpeur.encodeur()>=-38.5 && grimpeur.encodeur()<=-39.19){
|
if(limelight3.getV() == true){
|
||||||
grimpeur.grimpe(0);
|
|
||||||
}
|
}
|
||||||
else if(grimpeur.encodeur()>=-38.5){
|
else{
|
||||||
grimpeur.grimpe(-0.5);
|
|
||||||
}
|
}
|
||||||
else{grimpeur.grimpe(0.5);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
// Called once the command ends or is interrupted.
|
||||||
@Override
|
@Override
|
||||||
public void end(boolean interrupted) {
|
public void end(boolean interrupted) {}
|
||||||
grimpeur.grimpe(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
||||||
@Override
|
@Override
|
@ -5,15 +5,15 @@
|
|||||||
package frc.robot.commands;
|
package frc.robot.commands;
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
import frc.robot.subsystems.Bougie;
|
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 */
|
/* 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 RainBow extends Command {
|
public class AprilTag3G extends Command {
|
||||||
/** Creates a new RainBow. */
|
private Limelight3G limelight3g;
|
||||||
private Bougie bougie;
|
/** Creates a new AprilTag3G. */
|
||||||
public RainBow(Bougie bougie) {
|
public AprilTag3G(Limelight3G limelight3g) {
|
||||||
this.bougie = bougie;
|
this.limelight3g = limelight3g;
|
||||||
addRequirements(bougie);
|
addRequirements(limelight3g);
|
||||||
// Use addRequirements() here to declare subsystem dependencies.
|
// Use addRequirements() here to declare subsystem dependencies.
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -24,13 +24,18 @@ public class RainBow extends Command {
|
|||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void execute() {
|
public void execute() {
|
||||||
bougie.RainBow();
|
if(limelight3g.getV() == true){
|
||||||
|
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
// Called once the command ends or is interrupted.
|
||||||
@Override
|
@Override
|
||||||
public void end(boolean interrupted) {
|
public void end(boolean interrupted) {
|
||||||
bougie.RainBowStop();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
@ -5,26 +5,34 @@
|
|||||||
package frc.robot.commands;
|
package frc.robot.commands;
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
import frc.robot.subsystems.Grimpeur;
|
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 */
|
/* 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 ResetGrimpeur extends Command {
|
public class Forme3 extends Command {
|
||||||
private Grimpeur grimpeur;
|
private Limelight3 limelight3;
|
||||||
/** Creates a new ResetGrimpeur. */
|
/** Creates a new Forme3. */
|
||||||
public ResetGrimpeur(Grimpeur grimpeur) {
|
public Forme3(Limelight3 limelight3) {
|
||||||
this.grimpeur = grimpeur;
|
this.limelight3 = limelight3;
|
||||||
addRequirements(grimpeur);
|
addRequirements(limelight3);
|
||||||
// Use addRequirements() here to declare subsystem dependencies.
|
// Use addRequirements() here to declare subsystem dependencies.
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called when the command is initially scheduled.
|
// Called when the command is initially scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void initialize() {}
|
public void initialize() {
|
||||||
|
limelight3.Forme();
|
||||||
|
}
|
||||||
|
|
||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void execute() {
|
public void execute() {
|
||||||
grimpeur.reset();
|
if(limelight3.getV() == true){
|
||||||
|
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
// Called once the command ends or is interrupted.
|
@ -1,56 +0,0 @@
|
|||||||
// Copyright (c) FIRST and other WPILib contributors.
|
|
||||||
// Open Source Software; you can modify and/or share it under the terms of
|
|
||||||
// the WPILib BSD license file in the root directory of this project.
|
|
||||||
|
|
||||||
package frc.robot.commands;
|
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
|
||||||
import frc.robot.subsystems.Bougie;
|
|
||||||
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 GrimperHaut extends Command {
|
|
||||||
private Grimpeur grimpeur;
|
|
||||||
private Bougie bougie;
|
|
||||||
/** Creates a new Grimper. */
|
|
||||||
public GrimperHaut(Grimpeur grimpeur, Bougie bougie) {
|
|
||||||
this.grimpeur = grimpeur;
|
|
||||||
this.bougie = bougie;
|
|
||||||
addRequirements(grimpeur,bougie);
|
|
||||||
// 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.stop()==true){
|
|
||||||
grimpeur.grimpe(0);
|
|
||||||
grimpeur.reset();
|
|
||||||
bougie.RainBow();
|
|
||||||
}
|
|
||||||
else{
|
|
||||||
grimpeur.grimpe(0.5);
|
|
||||||
bougie.RainBowStop();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
|
||||||
@Override
|
|
||||||
public void end(boolean interrupted) {
|
|
||||||
grimpeur.grimpe(0);
|
|
||||||
if(grimpeur.stop()){
|
|
||||||
bougie.RainBow();
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
// Returns true when the command should end.
|
|
||||||
@Override
|
|
||||||
public boolean isFinished() {
|
|
||||||
return grimpeur.stop()==true;
|
|
||||||
}
|
|
||||||
}
|
|
@ -1,51 +0,0 @@
|
|||||||
// Copyright (c) FIRST and other WPILib contributors.
|
|
||||||
// Open Source Software; you can modify and/or share it under the terms of
|
|
||||||
// the WPILib BSD license file in the root directory of this project.
|
|
||||||
|
|
||||||
package frc.robot.commands;
|
|
||||||
|
|
||||||
import java.util.function.DoubleSupplier;
|
|
||||||
|
|
||||||
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 GrimpeurManuel extends Command {
|
|
||||||
private Grimpeur grimpeur;
|
|
||||||
private DoubleSupplier x;
|
|
||||||
/** Creates a new GrimpeurManuel. */
|
|
||||||
public GrimpeurManuel(Grimpeur grimpeur,DoubleSupplier x) {
|
|
||||||
this.grimpeur = grimpeur;
|
|
||||||
this.x = x;
|
|
||||||
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.stop()){
|
|
||||||
grimpeur.grimpe(0);
|
|
||||||
}
|
|
||||||
else{
|
|
||||||
grimpeur.grimpe(x.getAsDouble());
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
|
||||||
@Override
|
|
||||||
public void end(boolean interrupted) {
|
|
||||||
grimpeur.grimpe(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Returns true when the command should end.
|
|
||||||
@Override
|
|
||||||
public boolean isFinished() {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
}
|
|
@ -1,38 +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.CANdleConfiguration;
|
|
||||||
import com.ctre.phoenix.led.RainbowAnimation;
|
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
|
||||||
|
|
||||||
public class Bougie extends SubsystemBase {
|
|
||||||
CANdle candle = new CANdle(5);
|
|
||||||
CANdleConfiguration config = new CANdleConfiguration();
|
|
||||||
RainbowAnimation rainbowAnim = new RainbowAnimation(1, 0.5, 64);
|
|
||||||
/** Creates a new Bougie. */
|
|
||||||
public Bougie() {
|
|
||||||
config.brightnessScalar = 0.5;
|
|
||||||
candle.configAllSettings(config);
|
|
||||||
}
|
|
||||||
public void Rouge() {
|
|
||||||
candle.setLEDs(255, 0, 0);
|
|
||||||
}
|
|
||||||
public void Vert() {
|
|
||||||
candle.setLEDs(0, 255, 0);
|
|
||||||
}
|
|
||||||
public void Bleu() {
|
|
||||||
candle.setLEDs(0, 0, 255);
|
|
||||||
}
|
|
||||||
public void RainBow(){candle.animate(rainbowAnim);}
|
|
||||||
public void RainBowStop(){candle.animate(null);}
|
|
||||||
@Override
|
|
||||||
public void periodic() {
|
|
||||||
// This method will be called once per scheduler run
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
@ -4,35 +4,21 @@
|
|||||||
|
|
||||||
package frc.robot.subsystems;
|
package frc.robot.subsystems;
|
||||||
|
|
||||||
import com.revrobotics.spark.SparkMax;
|
|
||||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj.DigitalInput;
|
import edu.wpi.first.wpilibj.DigitalInput;
|
||||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
import edu.wpi.first.wpilibj.motorcontrol.Spark;
|
||||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
|
||||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||||
|
|
||||||
public class Grimpeur extends SubsystemBase {
|
public class Grimpeur extends SubsystemBase {
|
||||||
/** Creates a new Grimpeur. */
|
/** Creates a new Grimpeur. */
|
||||||
ShuffleboardTab teb = Shuffleboard.getTab("teb");
|
public Grimpeur() {}
|
||||||
public Grimpeur() {
|
final Spark grimpeur = new Spark(0);
|
||||||
teb.addBoolean("limit grimpeur", this::stop);
|
final DigitalInput limit1 = new DigitalInput(0);
|
||||||
teb.addDouble("encodeur grimpeur", this::encodeur);
|
|
||||||
}
|
|
||||||
final SparkMax grimpeur = new SparkMax(21,MotorType.kBrushless);
|
|
||||||
final DigitalInput limit1 = new DigitalInput(2);
|
|
||||||
public void grimpe(double vitesse){
|
public void grimpe(double vitesse){
|
||||||
grimpeur.set(vitesse);
|
grimpeur.set(vitesse);
|
||||||
}
|
}
|
||||||
public boolean stop(){
|
final void stop(){
|
||||||
return limit1.get();
|
limit1.get();
|
||||||
}
|
}
|
||||||
public double encodeur(){
|
|
||||||
return grimpeur.getEncoder().getPosition();
|
|
||||||
}
|
|
||||||
public void reset(){
|
|
||||||
grimpeur.getEncoder().setPosition(0);
|
|
||||||
}
|
|
||||||
@Override
|
@Override
|
||||||
public void periodic() {
|
public void periodic() {
|
||||||
// This method will be called once per scheduler run
|
// This method will be called once per scheduler run
|
||||||
|
39
src/main/java/frc/robot/subsystems/Limelight3.java
Normal file
39
src/main/java/frc/robot/subsystems/Limelight3.java
Normal file
@ -0,0 +1,39 @@
|
|||||||
|
// 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-balon");
|
||||||
|
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 getX(){
|
||||||
|
return LimelightHelpers.getTX("limelight-balon");
|
||||||
|
}
|
||||||
|
public boolean getV(){
|
||||||
|
return LimelightHelpers.getTV("limelight-balon");
|
||||||
|
}
|
||||||
|
public void Apriltag(){
|
||||||
|
pipeline.setNumber(1);
|
||||||
|
}
|
||||||
|
public void Forme(){
|
||||||
|
pipeline.setNumber(0);
|
||||||
|
}
|
||||||
|
@Override
|
||||||
|
public void periodic() {
|
||||||
|
// This method will be called once per scheduler run
|
||||||
|
}
|
||||||
|
}
|
28
src/main/java/frc/robot/subsystems/Limelight3G.java
Normal file
28
src/main/java/frc/robot/subsystems/Limelight3G.java
Normal file
@ -0,0 +1,28 @@
|
|||||||
|
// 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.wpilibj2.command.SubsystemBase;
|
||||||
|
import frc.robot.LimelightHelpers;
|
||||||
|
|
||||||
|
public class Limelight3G extends SubsystemBase {
|
||||||
|
/** Creates a new Limelight3. */
|
||||||
|
public Limelight3G() {
|
||||||
|
for(int port = 5800; port <=5807; port++){
|
||||||
|
PortForwarder.add(port, "limelight.local", port);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
public double getX(){
|
||||||
|
return LimelightHelpers.getTX("limelight-tag");
|
||||||
|
}
|
||||||
|
public boolean getV(){
|
||||||
|
return LimelightHelpers.getTV("limelight-tag");
|
||||||
|
}
|
||||||
|
@Override
|
||||||
|
public void periodic() {
|
||||||
|
// This method will be called once per scheduler run
|
||||||
|
}
|
||||||
|
}
|
Reference in New Issue
Block a user