Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@
import edu.wpi.first.wpilibj.AddressableLED;
import edu.wpi.first.wpilibj.AddressableLEDBuffer;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.LimeLight;
import frc.robot.subsystems.LimelightSubsystem;

public class LEDSubsystem extends SubsystemBase {
Expand All @@ -22,7 +21,7 @@ public class LEDSubsystem extends SubsystemBase {
AddressableLEDBuffer m_ledBuffer;

public LEDSubsystem() {
// PWM port 9
// PWM port 9
m_led = new AddressableLED(9);

m_ledBuffer = new AddressableLEDBuffer(60);
Expand All @@ -34,7 +33,7 @@ public LEDSubsystem() {

public void LED() {
for (var i = 0; i < m_ledBuffer.getLength(); i++) {
// Sets the specified LED to the HSV values for red
// Sets the specified LED to the HSV values for red
m_ledBuffer.setHSV(i, 180, 98, 59);
}
m_led.setData(m_ledBuffer);
Expand All @@ -61,28 +60,31 @@ private void turretAlignmentLEDs(){
}
}

// private void frontLEDs(){
// int i;
// //boolean forwardDrive = DriveSubsystem.m_driveForward;
// while(forwardDrive){
// m_ledBuffer.setHSV(i, 190 + (i * (80/m_ledBuffer.getLength())), 100, 50); //Set farthest 2 LEDs
// m_led.setData(m_ledBuffer);
// i = i + 1;
// if(i > m_ledBuffer.getLength())
// {
// i = 0;
// }
// }
// m_ledBuffer.setHSV(i, 270 - (i * (80/m_ledBuffer.getLength())), 100, 50); //Set farthest 2 LEDs
// m_led.setData(m_ledBuffer);
// i = i + 1;
private void frontDrivingLEDs(){
int i = 0;
boolean forwardDrive = true; //Change to m_forwardDrive
while(forwardDrive){
m_ledBuffer.setHSV(i, 190 + (i * (80/m_ledBuffer.getLength())), 100, 100); //Set farthest 2 LEDs
m_led.setData(m_ledBuffer);
i ++;
if(i > m_ledBuffer.getLength())
{
i = 0;
}
}
m_ledBuffer.setHSV(i, 270 - (i * (80/m_ledBuffer.getLength())), 100, 100); //Set farthest 2 LEDs
m_led.setData(m_ledBuffer);
i ++;

if(i > m_ledBuffer.getLength())
{
i = 0;
}
}
}

//we need an LED to describe when the shooter and/or feeder is on

// if(i > m_ledBuffer.getLength())
// {
// i = 0;
// }
// }
}
/*
private fullFireSpeed(){

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@ public class LimelightSubsystem extends SubsystemBase {
public static double xOffset;
public static double point3Angle;
public static boolean limelightTargetingStatic = true;
public double limelightMountAngle = 7.75;

public LimelightSubsystem() {
table = NetworkTableInstance.getDefault().getTable("limelight");
Expand All @@ -57,17 +58,18 @@ public void updateLimeLightValues() {
}
public void getDistance() {
//Angle (in degrees) the limelight is mounted at
final double limeLightDefAngle = 16.3; //NEW VALUE NEEDED
final double limeLightDefAngle = .2 + limelightMountAngle + 2.4; //NEW VALUE NEEDED
//Add the mount angle to the yangle gotten
yAngleDegrees = yAngleDegrees + limeLightDefAngle;
//Convert the new yangle into radians for the tangent
yAngleRadians = Math.toRadians(yAngleDegrees);
//Get the tangent of the new yangle
tyTangent = Math.tan(yAngleRadians);
//Divide the tangent by the magic number gotten from a sample at 166.6in from target straight on
dist = 70.5 / tyTangent; //NEW NUMBER MAY NEED TO BE GOTTEN WITH NEW ROBOT
dist = 57.25 / tyTangent; //NEW NUMBER MAY NEED TO BE GOTTEN WITH NEW ROBOT
//plug the number into the desmos graph
dist = dist * 1.096 - 16.0466; //Desmos correction graph REQUIRES TESTING WITH NEW ROBOT
dist = dist - 4.5; //Distance from camera lens to center of ball output
}

public static void toggleAimAssist() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -157,9 +157,8 @@ else if(((!m_leftLimit.get() && (azimuthSpeed>0)) || (!m_rightLimit.get() &&(azi
}

public boolean setAzimuthMotorAutomatic(double azimuthSpeed){
m_limeLight.gettxValue();

if((-.75 < xOffset)||(xOffset < .75))
double xOffset = LimelightSubsystem.gettxValue();
if((-.75 < xOffset)&&(xOffset < .75))
{
azimuthSpeed = 0;
}
Expand Down