Skip to content

Commit 5c71425

Browse files
committed
It works
1 parent cb60105 commit 5c71425

File tree

2 files changed

+14
-10
lines changed

2 files changed

+14
-10
lines changed

src/main/java/frc/robot/RobotContainer.kt

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@ package frc.robot
22

33
import LauncherSubsystem
44
import com.pathplanner.lib.auto.NamedCommands
5+
import com.pathplanner.lib.util.GeometryUtil
56
import edu.wpi.first.math.MathUtil
67
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard
78
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab
@@ -161,12 +162,17 @@ object RobotContainer {
161162
controller.rightBumper().toggleOnTrue(manualClimb)
162163
controller.rightStick().onTrue(InstantCommand(SwerveSubsystem::toggleFieldOriented))
163164
controller.button(Constants.OperatorConstants.BACK_BUTTON)
164-
.onTrue(PrintCommand("Toggle Between Absolute and Angular Velocity")) // TODO: Implement Toggle
165+
.onTrue(Commands.runOnce(
166+
{
167+
SwerveSubsystem.resetOdometry(GeometryUtil.flipFieldPose(SwerveSubsystem.getPose()))
168+
}
169+
)) // TODO: Implement Toggle
165170
controller.button(Constants.OperatorConstants.START_BUTTON)
166171
.onTrue(Commands.runOnce({
167172
SwerveSubsystem.resetOdometry(Constants.FIELD_LOCATIONS.SUBWOOFER_POSE)
168173
})) // TODO: Implement Intake Command Override
169174

175+
170176
LauncherSubsystem.noteTrigger.and(controller.a()).onTrue(launchCommand) // TODO: Implement Priming
171177

172178

src/main/java/frc/robot/commands/pivot/QuickPivotCommand.kt

Lines changed: 7 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -34,14 +34,17 @@ class QuickPivotCommand(target: Double, auto: Boolean, autoAim: Boolean) : Comma
3434
}
3535

3636
override fun initialize() {
37-
3837
if(autoAim) {
3938
pose = SwerveSubsystem.getPose()
4039
if (DriverStation.getAlliance() == Optional.of(DriverStation.Alliance.Red)) {
41-
speakerPose = GeometryUtil.flipFieldPose(speakerPose)
40+
speakerPose = GeometryUtil.flipFieldPose(Constants.FIELD_LOCATIONS.SUBWOOFER_POSE)
41+
} else {
42+
speakerPose = Constants.FIELD_LOCATIONS.SUBWOOFER_POSE
4243
}
4344

4445
xDistanceMeters = Math.abs(speakerPose.x - pose.x)
46+
println(xDistanceMeters)
47+
println(target)
4548

4649
target = calculateAngle(xDistanceMeters.meters)
4750
}
@@ -67,12 +70,7 @@ class QuickPivotCommand(target: Double, auto: Boolean, autoAim: Boolean) : Comma
6770
}
6871

6972
override fun end(interrupted: Boolean) {
70-
if (!this.auto) {
71-
val hold = HoldTargetCommand(target)
72-
hold.schedule()
73-
} else {
74-
pivotSubsystem.holdArm(target)
75-
println("Auto Pivot Stopped")
76-
}
73+
pivotSubsystem.holdArm(target)
74+
println("Auto Pivot Stopped")
7775
}
7876
}

0 commit comments

Comments
 (0)