Skip to content

Commit

Permalink
Revert "refactored alliance choosing"
Browse files Browse the repository at this point in the history
This reverts commit cf5db22.
  • Loading branch information
jpothen8 committed Mar 2, 2024
1 parent 6c5faba commit ffb56fa
Show file tree
Hide file tree
Showing 7 changed files with 56 additions and 44 deletions.
8 changes: 3 additions & 5 deletions src/main/kotlin/frc/team449/control/auto/ChoreoTrajectory.kt
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,7 @@ import edu.wpi.first.math.geometry.Pose2d
import edu.wpi.first.math.geometry.Rotation2d
import edu.wpi.first.math.numbers.N2
import edu.wpi.first.math.numbers.N3
import edu.wpi.first.wpilibj.DriverStation.Alliance
import edu.wpi.first.wpilibj.Filesystem
import frc.team449.robot2024.auto.AutoUtil
import org.json.simple.JSONArray
import org.json.simple.JSONObject
import org.json.simple.parser.JSONParser
Expand Down Expand Up @@ -69,8 +67,7 @@ class ChoreoTrajectory(
* @param filename Filename of .chor document file. By default, it will check in the deploy/choreo folder
*/
fun createTrajectory(
filename: String,
alliance: Alliance = Alliance.Blue
filename: String
): MutableList<ChoreoTrajectory> {
val path = Filesystem.getDeployDirectory().absolutePath.plus("/choreo/$filename.chor")
val document = (JSONParser().parse(FileReader(File(path).absolutePath)) as JSONObject)["paths"] as HashMap<*, *>
Expand All @@ -96,7 +93,8 @@ class ChoreoTrajectory(
)
)
}
return if (alliance == Alliance.Red) AutoUtil.transformForRed(trajList) else trajList

return trajList
}

private fun deadband(value: Double, deadband: Double = 1e-6): Double {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
package frc.team449.robot2024.auto.routines

import edu.wpi.first.wpilibj.DriverStation.Alliance
import frc.team449.control.auto.ChoreoRoutine
import frc.team449.control.auto.ChoreoRoutineStructure
import frc.team449.control.auto.ChoreoTrajectory
Expand All @@ -9,7 +8,7 @@ import frc.team449.robot2024.auto.AutoUtil

class Experimental3PieceMid(
robot: Robot,
alliance: Alliance
isRed: Boolean
) : ChoreoRoutineStructure {

override val routine =
Expand All @@ -28,8 +27,12 @@ class Experimental3PieceMid(
debug = false
)

override val trajectory: MutableList<ChoreoTrajectory> = ChoreoTrajectory.createTrajectory(
"3_Piece_Mid",
alliance
)
override val trajectory: MutableList<ChoreoTrajectory> =
if (isRed) {
AutoUtil.transformForRed(
ChoreoTrajectory.createTrajectory("3_Piece_Mid")
)
} else {
ChoreoTrajectory.createTrajectory("3_Piece_Mid")
}
}
15 changes: 9 additions & 6 deletions src/main/kotlin/frc/team449/robot2024/auto/routines/FivePiece.kt
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
package frc.team449.robot2024.auto.routines

import edu.wpi.first.wpilibj.DriverStation.Alliance
import frc.team449.control.auto.ChoreoRoutine
import frc.team449.control.auto.ChoreoRoutineStructure
import frc.team449.control.auto.ChoreoTrajectory
Expand All @@ -9,7 +8,7 @@ import frc.team449.robot2024.auto.AutoUtil

class FivePiece(
robot: Robot,
alliance: Alliance
isRed: Boolean
) : ChoreoRoutineStructure {
override val routine =
ChoreoRoutine(
Expand All @@ -31,8 +30,12 @@ class FivePiece(
debug = false
)

override val trajectory: MutableList<ChoreoTrajectory> = ChoreoTrajectory.createTrajectory(
"4_Piece_Shoot_Anywhere",
alliance
)
override val trajectory: MutableList<ChoreoTrajectory> =
if (isRed) {
AutoUtil.transformForRed(
ChoreoTrajectory.createTrajectory("4_Piece_Shoot_Anywhere")
)
} else {
ChoreoTrajectory.createTrajectory("4_Piece_Shoot_Anywhere")
}
}
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
package frc.team449.robot2024.auto.routines

import edu.wpi.first.wpilibj.DriverStation.Alliance
import frc.team449.control.auto.ChoreoRoutine
import frc.team449.control.auto.ChoreoRoutineStructure
import frc.team449.control.auto.ChoreoTrajectory
Expand All @@ -9,7 +8,7 @@ import frc.team449.robot2024.auto.AutoUtil

class FivePieceSubwoofer(
robot: Robot,
alliance: Alliance
isRed: Boolean
) : ChoreoRoutineStructure {
override val routine =
ChoreoRoutine(
Expand All @@ -36,8 +35,12 @@ class FivePieceSubwoofer(
timeout = 0.0
)

override val trajectory: MutableList<ChoreoTrajectory> = ChoreoTrajectory.createTrajectory(
"5_Piece_Sub",
alliance
)
override val trajectory: MutableList<ChoreoTrajectory> =
if (isRed) {
AutoUtil.transformForRed(
ChoreoTrajectory.createTrajectory("5_Piece_Sub")
)
} else {
ChoreoTrajectory.createTrajectory("5_Piece_Sub")
}
}
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
package frc.team449.robot2024.auto.routines

import edu.wpi.first.wpilibj.DriverStation.Alliance
import frc.team449.control.auto.ChoreoRoutine
import frc.team449.control.auto.ChoreoRoutineStructure
import frc.team449.control.auto.ChoreoTrajectory
Expand All @@ -9,7 +8,7 @@ import frc.team449.robot2024.auto.AutoUtil

class FourPieceSubwooferAmp(
robot: Robot,
alliance: Alliance
isRed: Boolean
) : ChoreoRoutineStructure {
override val routine =
ChoreoRoutine(
Expand All @@ -34,8 +33,12 @@ class FourPieceSubwooferAmp(
debug = false
)

override val trajectory: MutableList<ChoreoTrajectory> = ChoreoTrajectory.createTrajectory(
"4_Piece_Subwoofer_AmpSide",
alliance
)
override val trajectory: MutableList<ChoreoTrajectory> =
if (isRed) {
AutoUtil.transformForRed(
ChoreoTrajectory.createTrajectory("4_Piece_Subwoofer_AmpSide")
)
} else {
ChoreoTrajectory.createTrajectory("4_Piece_Subwoofer_AmpSide")
}
}
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
package frc.team449.robot2024.auto.routines

import edu.wpi.first.wpilibj.DriverStation.Alliance
import frc.team449.control.auto.ChoreoRoutine
import frc.team449.control.auto.ChoreoRoutineStructure
import frc.team449.control.auto.ChoreoTrajectory
Expand All @@ -9,7 +8,7 @@ import frc.team449.robot2024.auto.AutoUtil

class FourPieceSubwooferStage(
robot: Robot,
alliance: Alliance
isRed: Boolean
) : ChoreoRoutineStructure {
override val routine =
ChoreoRoutine(
Expand All @@ -34,8 +33,12 @@ class FourPieceSubwooferStage(
debug = false
)

override val trajectory: MutableList<ChoreoTrajectory> = ChoreoTrajectory.createTrajectory(
"4_Piece_Subwoofer_StageSide",
alliance
)
override val trajectory: MutableList<ChoreoTrajectory> =
if (isRed) {
AutoUtil.transformForRed(
ChoreoTrajectory.createTrajectory("4_Piece_Subwoofer_StageSide")
)
} else {
ChoreoTrajectory.createTrajectory("4_Piece_Subwoofer_StageSide")
}
}
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
package frc.team449.robot2024.auto.routines

import edu.wpi.first.wpilibj.DriverStation
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser
import edu.wpi.first.wpilibj2.command.Command
import frc.team449.robot2024.Robot
Expand All @@ -10,14 +9,14 @@ class RoutineChooser(private val robot: Robot) : SendableChooser<String>() {
fun routineMap(): HashMap<String, Command> {
return hashMapOf(
"DoNothing" to DoNothing(robot).createCommand(),
"Red4PieceAmp" to FourPieceSubwooferAmp(robot, DriverStation.Alliance.Red).createCommand(),
"Blue4PieceAmp" to FourPieceSubwooferAmp(robot, DriverStation.Alliance.Blue).createCommand(),
"Red4PieceStage" to FourPieceSubwooferStage(robot, DriverStation.Alliance.Red).createCommand(),
"Blue4PieceStage" to FourPieceSubwooferStage(robot, DriverStation.Alliance.Blue).createCommand(),
"Red3PieceMid" to Experimental3PieceMid(robot, DriverStation.Alliance.Red).createCommand(),
"Blue3PieceMid" to Experimental3PieceMid(robot, DriverStation.Alliance.Blue).createCommand(),
"RedSubwoofer5Piece" to FivePieceSubwoofer(robot, DriverStation.Alliance.Red).createCommand(),
"BlueSubwoofer5Piece" to FivePieceSubwoofer(robot, DriverStation.Alliance.Blue).createCommand(),
"Red4PieceAmp" to FourPieceSubwooferAmp(robot, true).createCommand(),
"Blue4PieceAmp" to FourPieceSubwooferAmp(robot, false).createCommand(),
"Red4PieceStage" to FourPieceSubwooferStage(robot, true).createCommand(),
"Blue4PieceStage" to FourPieceSubwooferStage(robot, false).createCommand(),
"Red3PieceMid" to Experimental3PieceMid(robot, true).createCommand(),
"Blue3PieceMid" to Experimental3PieceMid(robot, false).createCommand(),
"RedSubwoofer5Piece" to FivePieceSubwoofer(robot, true).createCommand(),
"BlueSubwoofer5Piece" to FivePieceSubwoofer(robot, false).createCommand(),
)
}

Expand Down

0 comments on commit ffb56fa

Please sign in to comment.