diff --git a/src/main/java/frc/robot/Robot.kt b/src/main/java/frc/robot/Robot.kt index b799b8a..91d3f4a 100755 --- a/src/main/java/frc/robot/Robot.kt +++ b/src/main/java/frc/robot/Robot.kt @@ -18,14 +18,12 @@ import org.littletonrobotics.junction.networktables.NT4Publisher import org.littletonrobotics.junction.wpilog.WPILOGReader import org.littletonrobotics.junction.wpilog.WPILOGWriter - class Robot : LoggedRobot() { private var m_autonomousCommand: Command? = null private var m_robotContainer: RobotContainer? = null override fun robotInit() { - Pathfinding.setPathfinder(LocalADStarAK()) Logger.recordMetadata("ProjectName", "FRC2024-offseason") // Set a metadata value @@ -42,24 +40,22 @@ class Robot : LoggedRobot() { WPILOGWriter( LogFileUtil.addPathSuffix( logPath, - "_sim" - ) - ) + "_sim", + ), + ), ) // Save outputs to a new log } - // Logger.disableDeterministicTimestamps() // See "Deterministic Timestamps" in the "Understanding Data Flow" page Logger.start() // Start logging! No more data receivers, replay sources, or metadata values may be added. m_robotContainer = RobotContainer() m_robotContainer!!.drivetrain.daqThread.setThreadPriority(99) - DriverStation.silenceJoystickConnectionWarning(true) SignalLogger.start() - PathfindingCommand.warmupCommand().schedule(); + PathfindingCommand.warmupCommand().schedule() } override fun robotPeriodic() { diff --git a/src/main/java/frc/robot/RobotContainer.kt b/src/main/java/frc/robot/RobotContainer.kt index 4eb6af0..7ec0ef0 100755 --- a/src/main/java/frc/robot/RobotContainer.kt +++ b/src/main/java/frc/robot/RobotContainer.kt @@ -19,10 +19,10 @@ import edu.wpi.first.wpilibj2.command.Commands import edu.wpi.first.wpilibj2.command.button.CommandXboxController import edu.wpi.first.wpilibj2.command.button.Trigger import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine -import frc.robot.subsystems.vision.VisionSubsystem import frc.robot.generated.TunerConstants import frc.robot.subsystems.ArmSubsystem import frc.robot.subsystems.drive.CommandSwerveDrivetrain +import frc.robot.subsystems.vision.VisionSubsystem import org.littletonrobotics.junction.networktables.LoggedDashboardChooser import java.util.function.Supplier import kotlin.math.atan2 @@ -48,7 +48,6 @@ class RobotContainer { val armSubsystem: ArmSubsystem = ArmSubsystem val visionSubsystem: VisionSubsystem = VisionSubsystem(drivetrain) - // Slew Rate Limiters to limit acceleration of joystick inputs private val xLimiter: SlewRateLimiter = SlewRateLimiter(2.0) private val yLimiter: SlewRateLimiter = SlewRateLimiter(0.5) @@ -89,10 +88,10 @@ class RobotContainer { point.withModuleDirection( Rotation2d( -drv.leftY, - -drv.leftX - ) + -drv.leftX, + ), ) - } + }, ) // reset the field-centric heading on start button press @@ -103,16 +102,15 @@ class RobotContainer { Commands.runOnce({ MaxSpeed = TunerConstants.kSpeedAt12VoltsMps * TurtleSpeed }) - .andThen({ AngularRate = TurtleAngularRate }) + .andThen({ AngularRate = TurtleAngularRate }), ) drv.leftBumper().onFalse( Commands.runOnce({ MaxSpeed = TunerConstants.kSpeedAt12VoltsMps * speedChooser.get() }) - .andThen({ AngularRate = MaxAngularRate }) + .andThen({ AngularRate = MaxAngularRate }), ) - if (Utils.isSimulation()) { drivetrain.seedFieldRelative(Pose2d(Translation2d(), Rotation2d.fromDegrees(0.0))) } @@ -139,10 +137,8 @@ class RobotContainer { // Drivetrain needs to be placed against a sturdy wall and test stopped immediately upon wheel slip drv.back().and(drv.pov(0)).whileTrue(drivetrain.runDriveSlipTest()) - drv.rightBumper().whileTrue(drivetrain.rotateToAngleDiff(visionSubsystem.getNoteCamAngle())) /* TODO make sure this works and probably also see if we can't get it to also move the robot forward a bit to center it w/ the arm */ - } init { @@ -174,7 +170,7 @@ class RobotContainer { } val autoCommand: Command? - get() =/* First put the drivetrain into auto run mode, then run the auto */ + get() = /* First put the drivetrain into auto run mode, then run the auto */ autoChooser.get() private fun newControlStyle() { @@ -222,6 +218,4 @@ class RobotContainer { private fun conditionX(joystick: Double, deadband: Double): Double { return xLimiter.calculate(MathUtil.applyDeadband(joystick, deadband)) } - - } diff --git a/src/main/java/frc/robot/subsystems/ArmSubsystem.kt b/src/main/java/frc/robot/subsystems/ArmSubsystem.kt index 4c7c1bd..c33e303 100644 --- a/src/main/java/frc/robot/subsystems/ArmSubsystem.kt +++ b/src/main/java/frc/robot/subsystems/ArmSubsystem.kt @@ -6,12 +6,6 @@ import com.ctre.phoenix.motorcontrol.can.TalonSRX import com.ctre.phoenix.motorcontrol.can.TalonSRXConfiguration import edu.wpi.first.math.controller.ArmFeedforward import edu.wpi.first.math.controller.PIDController -import edu.wpi.first.wpilibj.shuffleboard.ComplexWidget -import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard -import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab -import edu.wpi.first.wpilibj.smartdashboard.Mechanism2d -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard - import edu.wpi.first.wpilibj2.command.Command import edu.wpi.first.wpilibj2.command.Subsystem @@ -21,8 +15,6 @@ object ArmSubsystem : Subsystem { var config = TalonSRXConfiguration() var ff: ArmFeedforward - - init { // Initialize the arm subsystem motor = TalonSRX(31) diff --git a/src/main/java/frc/robot/subsystems/drive/CommandSwerveDrivetrain.kt b/src/main/java/frc/robot/subsystems/drive/CommandSwerveDrivetrain.kt index ec0e1b6..70c2b06 100755 --- a/src/main/java/frc/robot/subsystems/drive/CommandSwerveDrivetrain.kt +++ b/src/main/java/frc/robot/subsystems/drive/CommandSwerveDrivetrain.kt @@ -90,16 +90,14 @@ class CommandSwerveDrivetrain : SwerveDrivetrain, Subsystem { } private fun configurePathPlanner() { - - AutoBuilder.configureHolonomic( - { this.state.Pose }, // Supplier of current robot pose - this::seedFieldRelative, // Consumer for seeding pose against auto + { this.state.Pose }, // Supplier of current robot pose + this::seedFieldRelative, // Consumer for seeding pose against auto { this.currentRobotChassisSpeeds }, - { speeds -> this.setControl(autoRequest.withSpeeds(speeds)) }, // Consumer of ChassisSpeeds to drive the robot + { speeds -> this.setControl(autoRequest.withSpeeds(speeds)) }, // Consumer of ChassisSpeeds to drive the robot holonomicPathFollowerConfig(), getAlliance(), - this + this, ) // Subsystem for requirements } @@ -108,7 +106,7 @@ class CommandSwerveDrivetrain : SwerveDrivetrain, Subsystem { PIDConstants(10.0, 0.0, 0.0), TunerConstants.kSpeedAt12VoltsMps, driveBaseRadius, - ReplanningConfig() + ReplanningConfig(), ) fun applyRequest(requestSupplier: Supplier): Command { @@ -172,9 +170,11 @@ class CommandSwerveDrivetrain : SwerveDrivetrain, Subsystem { } private fun getHolonomicDriveController() = PPHolonomicDriveController( - PIDConstants(10.0, 0.0, 0.0), PIDConstants(10.0, 0.0, 0.0), + PIDConstants(10.0, 0.0, 0.0), + PIDConstants(10.0, 0.0, 0.0), // max module speed is 9.46 m/s, convert to ft/s - FeetPerSecond.of(9.46).`in`(MetersPerSecond), driveBaseRadius + FeetPerSecond.of(9.46).`in`(MetersPerSecond), + driveBaseRadius, ) @@ -191,7 +191,8 @@ class CommandSwerveDrivetrain : SwerveDrivetrain, Subsystem { private fun getReplanningConfig() = ReplanningConfig(true, true) - override fun simulationPeriodic() {/* Assume 20ms update rate, get battery voltage from WPILib */ + override fun simulationPeriodic() { + /* Assume 20ms update rate, get battery voltage from WPILib */ updateSimState(0.02, RobotController.getBatteryVoltage()) } @@ -202,33 +203,39 @@ class CommandSwerveDrivetrain : SwerveDrivetrain, Subsystem { private val driveVoltageRequest: SwerveVoltageRequest = SwerveVoltageRequest(true) private val m_driveSysIdRoutine: SysIdRoutine = SysIdRoutine( - SysIdRoutine.Config(null, null, null, ModifiedSignalLogger.logState()), SysIdRoutine.Mechanism( + SysIdRoutine.Config(null, null, null, ModifiedSignalLogger.logState()), + SysIdRoutine.Mechanism( { volts: Measure -> setControl( driveVoltageRequest.withVoltage( volts.`in`( - Volts - ) - ) + Volts, + ), + ), ) - }, null, this - ) + }, + null, + this, + ), ) private val steerVoltageRequest: SwerveVoltageRequest = SwerveVoltageRequest(false) private val m_steerSysIdRoutine: SysIdRoutine = SysIdRoutine( - SysIdRoutine.Config(null, null, null, ModifiedSignalLogger.logState()), SysIdRoutine.Mechanism( + SysIdRoutine.Config(null, null, null, ModifiedSignalLogger.logState()), + SysIdRoutine.Mechanism( { volts: Measure -> setControl( steerVoltageRequest.withVoltage( volts.`in`( - Volts - ) - ) + Volts, + ), + ), ) - }, null, this - ) + }, + null, + this, + ), ) override fun periodic() { /* Periodically try to apply the operator perspective */ @@ -239,10 +246,11 @@ class CommandSwerveDrivetrain : SwerveDrivetrain, Subsystem { if (!hasAppliedOperatorPerspective || DriverStation.isDisabled()) { DriverStation.getAlliance().ifPresent { allianceColor: Alliance -> this.setOperatorPerspectiveForward( - if (allianceColor == Alliance.Red) + if (allianceColor == Alliance.Red) { redAlliancePerspectiveRotation - else + } else { blueAlliancePerspectiveRotation + }, ) hasAppliedOperatorPerspective = true } @@ -251,18 +259,24 @@ class CommandSwerveDrivetrain : SwerveDrivetrain, Subsystem { private val m_slipSysIdRoutine: SysIdRoutine = SysIdRoutine( SysIdRoutine.Config( - Volts.of(0.25).per(Seconds.of(1.0)), null, null, ModifiedSignalLogger.logState() - ), SysIdRoutine.Mechanism( + Volts.of(0.25).per(Seconds.of(1.0)), + null, + null, + ModifiedSignalLogger.logState(), + ), + SysIdRoutine.Mechanism( { volts: Measure -> setControl( driveVoltageRequest.withVoltage( volts.`in`( - Volts - ) - ) + Volts, + ), + ), ) - }, null, this - ) + }, + null, + this, + ), ) fun runDriveQuasiTest(direction: SysIdRoutine.Direction?): Command { diff --git a/src/main/java/frc/robot/subsystems/vision/VisionSubsystem.kt b/src/main/java/frc/robot/subsystems/vision/VisionSubsystem.kt index e2f6850..71f3a0b 100755 --- a/src/main/java/frc/robot/subsystems/vision/VisionSubsystem.kt +++ b/src/main/java/frc/robot/subsystems/vision/VisionSubsystem.kt @@ -32,10 +32,8 @@ class VisionSubsystem(var drivetrain: CommandSwerveDrivetrain) : SubsystemBase() init { SmartDashboard.putNumber("Field Error", fieldError.toDouble()) SmartDashboard.putNumber("Limelight Error", distanceError.toDouble()) - } - fun updateLeft(): EstimatedRobotPose? { return leftPhotonPoseEstimator.update().getOrNull() } @@ -43,7 +41,6 @@ class VisionSubsystem(var drivetrain: CommandSwerveDrivetrain) : SubsystemBase() return rightPhotonPoseEstimator.update().getOrNull() } - fun useLimelight(enable: Boolean) { this.enable = enable } @@ -70,4 +67,4 @@ class VisionSubsystem(var drivetrain: CommandSwerveDrivetrain) : SubsystemBase() companion object { private val field = RectanglePoseArea(Translation2d(0.0, 0.0), Translation2d(16.54, 8.02)) } -} \ No newline at end of file +} diff --git a/src/main/java/frc/robot/util/CommandXboxPS5Controller.kt b/src/main/java/frc/robot/util/CommandXboxPS5Controller.kt index f4e1e84..c6dfcb4 100755 --- a/src/main/java/frc/robot/util/CommandXboxPS5Controller.kt +++ b/src/main/java/frc/robot/util/CommandXboxPS5Controller.kt @@ -65,20 +65,24 @@ class CommandXboxPS5Controller(port: Int) : CommandGenericHID(port) { fun leftBumper(loop: EventLoop? = CommandScheduler.getInstance().defaultButtonLoop): Trigger { return if (xbox!!) { m_hidx!!.leftBumper(loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } else { m_hidp!!.L1(loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } } @@ -99,20 +103,24 @@ class CommandXboxPS5Controller(port: Int) : CommandGenericHID(port) { fun rightBumper(loop: EventLoop? = CommandScheduler.getInstance().defaultButtonLoop): Trigger { return if (xbox!!) { m_hidx!!.rightBumper(loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } else { m_hidp!!.R1(loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } } @@ -134,20 +142,24 @@ class CommandXboxPS5Controller(port: Int) : CommandGenericHID(port) { fun leftStick(loop: EventLoop? = CommandScheduler.getInstance().defaultButtonLoop): Trigger { return if (xbox!!) { m_hidx!!.leftStick(loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } else { m_hidp!!.L3(loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } } @@ -169,20 +181,24 @@ class CommandXboxPS5Controller(port: Int) : CommandGenericHID(port) { fun rightStick(loop: EventLoop? = CommandScheduler.getInstance().defaultButtonLoop): Trigger { return if (xbox!!) { m_hidx!!.rightStick(loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } else { m_hidp!!.R3(loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } } @@ -203,20 +219,24 @@ class CommandXboxPS5Controller(port: Int) : CommandGenericHID(port) { fun a(loop: EventLoop? = CommandScheduler.getInstance().defaultButtonLoop): Trigger { return if (xbox!!) { m_hidx!!.a(loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } else { m_hidp!!.cross(loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } } @@ -237,20 +257,24 @@ class CommandXboxPS5Controller(port: Int) : CommandGenericHID(port) { fun b(loop: EventLoop? = CommandScheduler.getInstance().defaultButtonLoop): Trigger { return if (xbox!!) { m_hidx!!.b(loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } else { m_hidp!!.circle(loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } } @@ -271,20 +295,24 @@ class CommandXboxPS5Controller(port: Int) : CommandGenericHID(port) { fun x(loop: EventLoop? = CommandScheduler.getInstance().defaultButtonLoop): Trigger { return if (xbox!!) { m_hidx!!.x(loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } else { m_hidp!!.square(loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } } @@ -305,20 +333,24 @@ class CommandXboxPS5Controller(port: Int) : CommandGenericHID(port) { fun y(loop: EventLoop? = CommandScheduler.getInstance().defaultButtonLoop): Trigger { return if (xbox!!) { m_hidx!!.y(loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } else { m_hidp!!.triangle(loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } } @@ -339,20 +371,24 @@ class CommandXboxPS5Controller(port: Int) : CommandGenericHID(port) { fun start(loop: EventLoop? = CommandScheduler.getInstance().defaultButtonLoop): Trigger { return if (xbox!!) { m_hidx!!.start(loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } else { m_hidp!!.options(loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } } @@ -373,20 +409,24 @@ class CommandXboxPS5Controller(port: Int) : CommandGenericHID(port) { fun back(loop: EventLoop? = CommandScheduler.getInstance().defaultButtonLoop): Trigger { return if (xbox!!) { m_hidx!!.back(loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } else { m_hidp!!.create(loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } } @@ -419,24 +459,27 @@ class CommandXboxPS5Controller(port: Int) : CommandGenericHID(port) { @JvmOverloads fun leftTrigger( threshold: Double = 0.5, - loop: EventLoop = CommandScheduler.getInstance().defaultButtonLoop + loop: EventLoop = CommandScheduler.getInstance().defaultButtonLoop, ): Trigger { return if (xbox!!) { m_hidx!!.leftTrigger(threshold, loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } else { BooleanEvent(loop) { m_hidp!!.l2Axis > threshold }.castTo( BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> Trigger( loop, - condition + condition, ) - }) + }, + ) } } @@ -469,24 +512,27 @@ class CommandXboxPS5Controller(port: Int) : CommandGenericHID(port) { @JvmOverloads fun rightTrigger( threshold: Double = 0.5, - loop: EventLoop = CommandScheduler.getInstance().defaultButtonLoop + loop: EventLoop = CommandScheduler.getInstance().defaultButtonLoop, ): Trigger { return if (xbox!!) { m_hidx!!.rightTrigger(threshold, loop) - .castTo(BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> - Trigger( - loop, - condition - ) - }) + .castTo( + BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> + Trigger( + loop, + condition, + ) + }, + ) } else { BooleanEvent(loop) { m_hidp!!.r2Axis > threshold }.castTo( BiFunction { loop: EventLoop?, condition: BooleanSupplier? -> Trigger( loop, - condition + condition, ) - }) + }, + ) } } diff --git a/src/main/java/frc/robot/util/LocalADStarAK.kt b/src/main/java/frc/robot/util/LocalADStarAK.kt index d12c7cd..3a67337 100644 --- a/src/main/java/frc/robot/util/LocalADStarAK.kt +++ b/src/main/java/frc/robot/util/LocalADStarAK.kt @@ -84,7 +84,8 @@ class LocalADStarAK : Pathfinder { * position of the path to properly avoid obstacles */ override fun setDynamicObstacles( - obs: List>, currentRobotPos: Translation2d, + obs: List>, + currentRobotPos: Translation2d, ) { if (!Logger.hasReplaySource()) { io.adStar.setDynamicObstacles(obs, currentRobotPos) @@ -139,4 +140,4 @@ class LocalADStarAK : Pathfinder { } } } -} \ No newline at end of file +}