Skip to content

Commit

Permalink
Fixed wildcard imports & changed name of configPID
Browse files Browse the repository at this point in the history
  • Loading branch information
lakelandspark committed Jul 2, 2024
1 parent bfa486c commit b8028c5
Show file tree
Hide file tree
Showing 26 changed files with 31 additions and 59 deletions.
Binary file added .gradle/8.4/checksums/checksums.lock
Binary file not shown.
Binary file added .gradle/8.4/checksums/md5-checksums.bin
Binary file not shown.
Binary file added .gradle/8.4/checksums/sha1-checksums.bin
Binary file not shown.
Binary file not shown.
Empty file.
Binary file not shown.
Binary file added .gradle/8.4/executionHistory/executionHistory.lock
Binary file not shown.
Binary file added .gradle/8.4/fileChanges/last-build.bin
Binary file not shown.
Binary file added .gradle/8.4/fileHashes/fileHashes.bin
Binary file not shown.
Binary file added .gradle/8.4/fileHashes/fileHashes.lock
Binary file not shown.
Binary file added .gradle/8.4/fileHashes/resourceHashesCache.bin
Binary file not shown.
Empty file added .gradle/8.4/gc.properties
Empty file.
Binary file added .gradle/buildOutputCleanup/buildOutputCleanup.lock
Binary file not shown.
2 changes: 2 additions & 0 deletions .gradle/buildOutputCleanup/cache.properties
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
#Wed Jun 19 14:31:53 EDT 2024
gradle.version=8.4
Binary file added .gradle/buildOutputCleanup/outputFiles.bin
Binary file not shown.
Binary file added .gradle/file-system.probe
Binary file not shown.
Empty file added .gradle/vcs-1/gc.properties
Empty file.
1 change: 0 additions & 1 deletion src/main/kotlin/com/team4099/robot2023/RobotContainer.kt
Original file line number Diff line number Diff line change
Expand Up @@ -240,7 +240,6 @@ object RobotContainer {
ControlBoard.passingShot.whileTrue(superstructure.passingShotCommand())
ControlBoard.underStagePassingShot.whileTrue(superstructure.underStageCommand())
ControlBoard.testWrist.whileTrue(superstructure.testWristCommand())
//ControlBoard.testDriveVelocity.whileTrue(superstructure.testDriveVelocityCommand())

/*
ControlBoard.targetAmp.whileTrue(
Expand Down
9 changes: 5 additions & 4 deletions src/main/kotlin/com/team4099/robot2023/config/ControlBoard.kt
Original file line number Diff line number Diff line change
Expand Up @@ -70,16 +70,17 @@ object ControlBoard {
val ejectGamePiece = Trigger { driver.rightTriggerAxis > 0.5 }

val testWrist = Trigger { driver.aButton }



val characterizeWrist = Trigger { driver.rightShoulderButton }

val climbAlignFar = Trigger { driver.dPadUp }
val climbAlignLeft = Trigger { driver.dPadLeft }
val climbAlignRight = Trigger { driver.dPadRight }

val targetSpeaker = Trigger { driver.xButton } // TODO: switch back to climbAlignLeft
// TODO: Check if this variable is necessary
// val climbAutoAlign = Trigger { driver.bButton }

val targetSpeaker = Trigger { driver.xButton }
// TODO: switch back to climbAlignLeft
val lockWheels = Trigger { driver.startButton }

// week0 controls
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,10 +51,6 @@ object DrivetrainConstants {

const val GYRO_RATE_COEFFICIENT = 0.0 // TODO: Change this value

val TEST_X_VELOCITY = 10.0.meters.perSecond
val TEST_Y_VELOCITY = 10.0.meters.perSecond
val TEST_OMEGA = 5.0.radians.perSecond

val SLOW_AUTO_VEL = 2.meters.perSecond
val SLOW_AUTO_ACCEL = 2.0.meters.perSecond.perSecond

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,38 +31,27 @@ import org.team4099.lib.geometry.Rotation3d
import org.team4099.lib.geometry.Transform2d
import org.team4099.lib.geometry.Translation2d
import org.team4099.lib.kinematics.ChassisSpeeds
import org.team4099.lib.units.*
import org.team4099.lib.units.base.inMeters
import org.team4099.lib.units.base.inMilliseconds
import org.team4099.lib.units.base.inSeconds
import org.team4099.lib.units.base.meters
import org.team4099.lib.units.derived.*
import org.team4099.lib.units.inMetersPerSecond
import org.team4099.lib.units.inRadiansPerSecond
import org.team4099.lib.units.perSecond
import org.team4099.lib.units.inDegreesPerSecond
import org.team4099.lib.units.AngularVelocity
import org.team4099.lib.units.derived.radians
import org.team4099.lib.units.derived.degrees
import org.team4099.lib.units.derived.volts
import org.team4099.lib.units.derived.inDegrees
import org.team4099.lib.units.derived.inRotation2ds
import org.team4099.lib.units.derived.Angle
import org.team4099.lib.units.derived.inRadians
import java.util.concurrent.locks.Lock
import java.util.concurrent.locks.ReentrantLock
import com.team4099.robot2023.subsystems.superstructure.Request.DrivetrainRequest as DrivetrainRequest

class Drivetrain(private val gyroIO: GyroIO, swerveModuleIOs: DrivetrainIO) : SubsystemBase() {
object TunableDriveStates {
val testXVelocity =
LoggedTunableValue(
"Drivetrain/testXVelocity",
DrivetrainConstants.TEST_X_VELOCITY,
Pair( { it.inMetersPerSecond }, { it.meters.perSecond })
)
val testYVelocity =
LoggedTunableValue(
"Drivetrain/testYVelocity",
DrivetrainConstants.TEST_Y_VELOCITY,
Pair( { it.inMetersPerSecond }, { it.meters.perSecond })
)
val testOmega =
LoggedTunableValue(
"Drivetrain/testOmega",
DrivetrainConstants.TEST_OMEGA,
Pair( { it.inRadiansPerSecond }, { it.radians.perSecond })
)
}

private val gyroNotConnectedAlert =
Alert(
"Gyro is not connected, field relative driving will be significantly worse.",
Expand Down Expand Up @@ -92,8 +81,10 @@ class Drivetrain(private val gyroIO: GyroIO, swerveModuleIOs: DrivetrainIO) : Su
var targetPose: Pose2d = Pose2d(0.0.meters, 0.0.meters, 0.0.radians)

var fieldVelocity = Velocity2d()
private set

var robotVelocity = Velocity2d()
private set

private var omegaVelocity = 0.0.radians.perSecond

Expand Down Expand Up @@ -300,7 +291,7 @@ class Drivetrain(private val gyroIO: GyroIO, swerveModuleIOs: DrivetrainIO) : Su
VisionConstants.POSE_TOPIC_NAME,
doubleArrayOf(odomTRobot.x.inMeters, odomTRobot.y.inMeters, odomTRobot.rotation.inRadians)
)
CustomLogger.recordOutput("FieldRelativePose/robotPose", fieldTRobot.pose2d)
CustomLogger.recordOutput("FieldFrameEstimator/robotPose", fieldTRobot.pose2d)

CustomLogger.recordOutput("Drivetrain/ModuleStates", *measuredStates.toTypedArray())
CustomLogger.recordOutput("Drivetrain/setPointStates", *setPointStates.toTypedArray())
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ class SwerveModule(val io: SwerveModuleIO) {
modulePosition.angle = inputs.steerPosition.inRotation2ds

if (steerkD.hasChanged() || steerkP.hasChanged() || steerkI.hasChanged()) {
io.configSteerPID(steerkP.get(), steerkI.get(), steerkD.get())
io.configureSteerPID(steerkP.get(), steerkI.get(), steerkD.get())
}

if (drivekD.hasChanged() ||
Expand All @@ -175,7 +175,7 @@ class SwerveModule(val io: SwerveModuleIO) {
drivekA.hasChanged() ||
drivekV.hasChanged()
) {
io.configDrivePID(drivekP.get(), drivekI.get(), drivekD.get(), drivekV.get(), drivekA.get())
io.configureDrivePID(drivekP.get(), drivekI.get(), drivekD.get(), drivekV.get(), drivekA.get())
}
if (steerMaxVelo.hasChanged() || steerMaxAccel.hasChanged()) {
io.configSteerMotionMagic(steerMaxVelo.get(), steerMaxAccel.get())
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -152,13 +152,13 @@ interface SwerveModuleIO {

fun setSteeringSetpoint(angle: Angle) {}

fun configSteerPID(
fun configureSteerPID(
kP: ProportionalGain<Radian, Volt>,
kI: IntegralGain<Radian, Volt>,
kD: DerivativeGain<Radian, Volt>
) {}

fun configDrivePID(
fun configureDrivePID(
kP: ProportionalGain<Velocity<Meter>, Volt>,
kI: IntegralGain<Velocity<Meter>, Volt>,
kD: DerivativeGain<Velocity<Meter>, Volt>,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -254,7 +254,7 @@ class SwerveModuleIOSim(override val label: String) : SwerveModuleIO {
turnAbsolutePosition = 0.0.radians
}

override fun configDrivePID(
override fun configureDrivePID(
kP: ProportionalGain<Velocity<Meter>, Volt>,
kI: IntegralGain<Velocity<Meter>, Volt>,
kD: DerivativeGain<Velocity<Meter>, Volt>,
Expand All @@ -264,7 +264,7 @@ class SwerveModuleIOSim(override val label: String) : SwerveModuleIO {
driveFeedback.setPID(kP, kI, kD)
}

override fun configSteerPID(
override fun configureSteerPID(
kP: ProportionalGain<Radian, Volt>,
kI: IntegralGain<Radian, Volt>,
kD: DerivativeGain<Radian, Volt>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -261,6 +261,7 @@ class SwerveModuleIOTalon(
// }
// .toList() as
// List<Angle>

drivePositionQueue.clear()
steeringPositionQueue.clear()

Expand Down Expand Up @@ -358,7 +359,7 @@ class SwerveModuleIOTalon(
steeringPositionQueue.clear()
}

override fun configDrivePID(
override fun configureDrivePID(
kP: ProportionalGain<Velocity<Meter>, Volt>,
kI: IntegralGain<Velocity<Meter>, Volt>,
kD: DerivativeGain<Velocity<Meter>, Volt>,
Expand All @@ -376,7 +377,7 @@ class SwerveModuleIOTalon(
driveFalcon.configurator.apply(PIDConfig)
}

override fun configSteerPID(
override fun configureSteerPID(
kP: ProportionalGain<Radian, Volt>,
kI: IntegralGain<Radian, Volt>,
kD: DerivativeGain<Radian, Volt>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1168,24 +1168,6 @@ class Superstructure(
return returnCommand
}

fun testDriveVelocityCommand(): Command {
val returnCommand = runOnce {
currentRequest= Request.SuperstructureRequest.Tuning()
drivetrain.currentRequest =
Request.DrivetrainRequest.OpenLoop(
Drivetrain.TunableDriveStates.testOmega.get(),
Velocity2d(
Drivetrain.TunableDriveStates.testXVelocity.get(),
Drivetrain.TunableDriveStates.testYVelocity.get()
)
)
}
returnCommand.name = "TestDriveVelocityCommand"
return returnCommand
}

// TODO: Test Drivetrain Steer Command

companion object {
enum class SuperstructureStates {
UNINITIALIZED,
Expand Down

0 comments on commit b8028c5

Please sign in to comment.