Skip to content

Commit

Permalink
Fix final errors in Drivetrain logic to get file ready for review
Browse files Browse the repository at this point in the history
  • Loading branch information
SirBeans committed Jun 22, 2024
1 parent cd079c5 commit deef8c4
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -243,7 +243,7 @@ class Drivetrain(val gyroIO: GyroIO, swerveModuleIOs: DrivetrainIO) : SubsystemB
swerveModules.forEach { it.updateInputs() }
// odometryLock.unlock()

Logger.processInputs("Gyro", gyroInputs)
CustomLogger.processInputs("Gyro", gyroInputs)

gyroNotConnectedAlert.set(!gyroInputs.gyroConnected)

Expand Down Expand Up @@ -364,12 +364,12 @@ class Drivetrain(val gyroIO: GyroIO, swerveModuleIOs: DrivetrainIO) : SubsystemB
}
DrivetrainState.OPEN_LOOP -> {
// Outputs
setOpenLoop(angularVelocityTarget, targetedDriveVector., isFieldOriented)
setOpenLoop(angularVelocityTarget, targetedDriveVector, isFieldOriented)
CustomLogger.recordOutput(
"Drivetrain/TargetVelocityXInMPS", targetedDriveVector.first.inMetersPerSecond
"Drivetrain/TargetVelocityXInMPS", targetedDriveVector.x.inMetersPerSecond
)
CustomLogger.recordOutput(
"Drivetrain/TargetVelocityYInMPS", targetedDriveVector.second.inMetersPerSecond
"Drivetrain/TargetVelocityYInMPS", targetedDriveVector.y.inMetersPerSecond
)
// Transitions
nextState = fromRequestToState(currentRequest)
Expand Down Expand Up @@ -439,7 +439,7 @@ class Drivetrain(val gyroIO: GyroIO, swerveModuleIOs: DrivetrainIO) : SubsystemB
ChassisSpeeds.fromFieldRelativeSpeeds(
driveVectorRespectiveToAlliance.x,
driveVectorRespectiveToAlliance.y,
angularVelocity
angularVelocity,
odomTRobot.rotation
)
} else {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
package com.team4099.robot2023.subsystems.superstructure

import com.team4099.robot2023.config.constants.WristConstants
import com.team4099.robot2023.util.Velocity2d
import edu.wpi.first.math.kinematics.ChassisSpeeds
import org.team4099.lib.units.AngularVelocity
import org.team4099.lib.units.LinearVelocity
Expand Down Expand Up @@ -58,7 +59,7 @@ sealed interface Request {
sealed interface DrivetrainRequest : Request {
class OpenLoop(
val angularVelocity: AngularVelocity,
val driveVector: Pair<LinearVelocity, LinearVelocity>,
val driveVector: Velocity2d,
val fieldOriented: Boolean = true
) : DrivetrainRequest

Expand Down

0 comments on commit deef8c4

Please sign in to comment.