Skip to content

Commit

Permalink
chore(refactor): the code seems not to build with util named how it i…
Browse files Browse the repository at this point in the history
…s, let's fix that
  • Loading branch information
TheGamer1002 committed Oct 25, 2024
1 parent 76cea3c commit 532537d
Show file tree
Hide file tree
Showing 7 changed files with 21 additions and 16 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Robot.kt
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ import edu.wpi.first.wpilibj.DriverStation
import edu.wpi.first.wpilibj.PowerDistribution
import edu.wpi.first.wpilibj2.command.Command
import edu.wpi.first.wpilibj2.command.CommandScheduler
import frc.robot.util.LocalADStarAK
import frc.robot.Util.LocalADStarAK
import org.littletonrobotics.junction.LogFileUtil
import org.littletonrobotics.junction.LoggedRobot
import org.littletonrobotics.junction.Logger
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.robot.util
package frc.robot.Util

import com.pathplanner.lib.path.GoalEndState
import com.pathplanner.lib.path.PathConstraints
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.robot.util
package frc.robot.Util

import com.ctre.phoenix6.SignalLogger
import com.ctre.phoenix6.hardware.ParentDevice
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.robot.util
package frc.robot.Util

import edu.wpi.first.math.geometry.Pose2d
import edu.wpi.first.math.geometry.Translation2d
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.robot.util
package frc.robot.Util

import com.ctre.phoenix6.StatusCode
import com.ctre.phoenix6.controls.MotionMagicVoltage
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,8 @@ 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.generated.TunerConstants
import frc.robot.util.ModifiedSignalLogger
import frc.robot.util.SwerveVoltageRequest
import frc.robot.Util.ModifiedSignalLogger
import frc.robot.Util.SwerveVoltageRequest
import org.littletonrobotics.junction.AutoLogOutput
import java.util.*
import java.util.function.Supplier
Expand Down
23 changes: 14 additions & 9 deletions src/main/java/frc/robot/subsystems/vision/VisionSubsystem.kt
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,11 @@ package frc.robot.subsystems.vision
import edu.wpi.first.apriltag.AprilTagFields
import edu.wpi.first.math.geometry.*
import edu.wpi.first.wpilibj.DriverStation.Alliance
import edu.wpi.first.wpilibj.RobotBase
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard
import edu.wpi.first.wpilibj2.command.SubsystemBase
import frc.robot.subsystems.drive.CommandSwerveDrivetrain
import frc.robot.util.RectanglePoseArea
import frc.robot.Util.RectanglePoseArea
import org.photonvision.EstimatedRobotPose
import org.photonvision.PhotonCamera
import org.photonvision.PhotonPoseEstimator
Expand All @@ -27,6 +28,7 @@ class VisionSubsystem(var drivetrain: CommandSwerveDrivetrain) : SubsystemBase()
private var aprilTagFieldLayout = AprilTagFields.k2024Crescendo.loadAprilTagLayoutField()
private var rightPhotonPoseEstimator = PhotonPoseEstimator(aprilTagFieldLayout, PhotonPoseEstimator.PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, rightCam, botToRightCamera)
private var leftPhotonPoseEstimator = PhotonPoseEstimator(aprilTagFieldLayout, PhotonPoseEstimator.PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, leftCam, botToLeftCamera)
private val isSim = RobotBase.isSimulation()

/** Creates a new Limelight. */
init {
Expand All @@ -50,18 +52,21 @@ class VisionSubsystem(var drivetrain: CommandSwerveDrivetrain) : SubsystemBase()
}

override fun periodic() {
val right = updateRight()
val left = updateLeft()
if (right != null) {
drivetrain.addVisionMeasurement(right.estimatedPose.toPose2d(), right.timestampSeconds)
}
if (left != null) {
drivetrain.addVisionMeasurement(left.estimatedPose.toPose2d(), left.timestampSeconds)
if(!isSim) {
val right = updateRight()
val left = updateLeft()
if (right != null) {
drivetrain.addVisionMeasurement(right.estimatedPose.toPose2d(), right.timestampSeconds)
}
if (left != null) {
drivetrain.addVisionMeasurement(left.estimatedPose.toPose2d(), left.timestampSeconds)
}
}
}

fun getNoteCamAngle(): Double {
return noteCam.getLatestResult().getBestTarget().yaw
if (!isSim) return noteCam.getLatestResult().getBestTarget().yaw
else return 0.0
}

companion object {
Expand Down

0 comments on commit 532537d

Please sign in to comment.