Code composante fini
This commit is contained in:
@@ -6,9 +6,7 @@ package frc.robot.subsystems;
|
||||
|
||||
import com.revrobotics.spark.SparkMax;
|
||||
import com.revrobotics.spark.config.SparkMaxConfig;
|
||||
import com.revrobotics.spark.SparkBase.PersistMode;
|
||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.Spark;
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
@@ -19,8 +17,8 @@ public class Grimpeur extends SubsystemBase {
|
||||
DigitalInput limit = new DigitalInput(1);
|
||||
public void Grimper(double vitesse){
|
||||
grimpeur1.set(vitesse);
|
||||
slaveConfig.follow(grimpeur1, false);
|
||||
grimpeur2.configure(slaveConfig,null,null);
|
||||
grimpeur2.set(vitesse);
|
||||
|
||||
}
|
||||
public double Position(){
|
||||
return grimpeur1.getEncoder().getPosition();
|
||||
|
||||
@@ -6,7 +6,6 @@ package frc.robot.subsystems;
|
||||
|
||||
import com.revrobotics.spark.SparkFlex;
|
||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||
import com.revrobotics.spark.config.SparkMaxConfig;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
@@ -14,11 +13,9 @@ public class Lanceur extends SubsystemBase {
|
||||
SparkFlex moteur1 = new SparkFlex(2, MotorType.kBrushless);
|
||||
SparkFlex moteur2 = new SparkFlex(3, MotorType.kBrushless);
|
||||
SparkFlex Demeleur = new SparkFlex(4, MotorType.kBrushless);
|
||||
SparkMaxConfig slaveConfig = new SparkMaxConfig();
|
||||
public void Lancer(double vitesse){
|
||||
moteur1.set(vitesse);
|
||||
slaveConfig.follow(moteur1, true);
|
||||
moteur2.configure(slaveConfig,null,null);
|
||||
moteur2.set(-vitesse);
|
||||
}
|
||||
public void Demeler(double vitesse){
|
||||
Demeleur.set(vitesse);
|
||||
|
||||
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-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[] getBotPoseBlue(){
|
||||
NetworkTable limelightTable = NetworkTableInstance.getDefault().getTable("limelight-balon");
|
||||
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-balon");
|
||||
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-balon");
|
||||
NetworkTableEntry tx = table.getEntry("tx");
|
||||
return tx.getDouble(0.0);
|
||||
}
|
||||
public double getTId(){
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-balon");
|
||||
NetworkTableEntry tid = table.getEntry("tid");
|
||||
return tid.getDouble(0.0);
|
||||
}
|
||||
public double getTA(){
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-balon");
|
||||
NetworkTableEntry ta = table.getEntry("ta");
|
||||
return ta.getDouble(0.0);
|
||||
}
|
||||
public boolean getV(){
|
||||
return LimelightHelpers.getTV("limelight-balon");
|
||||
}
|
||||
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
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user