Skip to content

Commit

Permalink
cleaned up weird merge commit stuff
Browse files Browse the repository at this point in the history
  • Loading branch information
falOn-Dev committed Dec 10, 2023
1 parent 2812112 commit 5341a28
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 19 deletions.
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/commands/vision/TrackTargetCommand.kt
Original file line number Diff line number Diff line change
Expand Up @@ -29,11 +29,11 @@ class TrackTargetCommand : CommandBase() {
override fun initialize() {}

override fun execute() {
rotation = pidController.calculate(limelightSubsystem.xOffset, 0.0)
rotation = pidController.calculate(limelightSubsystem.getXOffset(), 0.0)



if((abs(limelightSubsystem.xOffset) < 2 && limelightSubsystem.area < 3.5) && limelightSubsystem.targetVisible){
if((abs(limelightSubsystem.getXOffset()) < 2 && limelightSubsystem.getArea() < 3.5) && limelightSubsystem.isTargetVisible()){
translation = Translation2d(0.3, -SingletonXboxController.leftX)
} else {
translation = Translation2d(0.0, -SingletonXboxController.leftX)
Expand Down
17 changes: 0 additions & 17 deletions src/main/java/frc/robot/subsystems/LimelightSubsystem.kt
Original file line number Diff line number Diff line change
Expand Up @@ -18,23 +18,13 @@ object LimelightSubsystem : SubsystemBase() {

// NetworkTable object for getting data from the Limelight
private var table: NetworkTable

<<<<<<< HEAD
var xOffset: Double = 0.0
var yOffset: Double = 0.0
var area: Double = 0.0
var skew: Double = 0.0
var targetVisible: Boolean = false

private var visionTab: ShuffleboardTab
=======
// Variables for storing data from the Limelight
private var xOffset: Double = 0.0
private var yOffset: Double = 0.0
private var area: Double = 0.0
private var skew: Double = 0.0
private var targetVisible: Boolean = false
>>>>>>> a460a03e86fd31443af08ddf3721adb2fac133d4

init {
// Get the default NetworkTable for the Limelight
Expand All @@ -47,7 +37,6 @@ object LimelightSubsystem : SubsystemBase() {
tv = table.getEntry("tv")
ts = table.getEntry("ts")

<<<<<<< HEAD
visionTab = Shuffleboard.getTab("Vision")

visionTab.addDouble("X Offset") { xOffset }
Expand All @@ -56,10 +45,8 @@ object LimelightSubsystem : SubsystemBase() {
visionTab.addDouble("Skew") { skew }
visionTab.addBoolean("Target Visible") { targetVisible }

=======
// Create a Shuffleboard tab for the Limelight
val visionTab: ShuffleboardTab = Shuffleboard.getTab("Vision")
>>>>>>> a460a03e86fd31443af08ddf3721adb2fac133d4


}
Expand All @@ -70,9 +57,6 @@ object LimelightSubsystem : SubsystemBase() {
yOffset = ty.getDouble(0.0)
area = ta.getDouble(0.0)
skew = ts.getDouble(0.0)
<<<<<<< HEAD
targetVisible = tv.getDouble(0.0) > 0
=======
targetVisible = tv.getDouble(0.0) == 1.0
}

Expand All @@ -95,6 +79,5 @@ object LimelightSubsystem : SubsystemBase() {

fun isTargetVisible(): Boolean {
return targetVisible
>>>>>>> a460a03e86fd31443af08ddf3721adb2fac133d4
}
}

0 comments on commit 5341a28

Please sign in to comment.