Skip to content

Commit

Permalink
Made instantiation of the 0 velocity vector static
Browse files Browse the repository at this point in the history
  • Loading branch information
yamamara committed Jul 2, 2024
1 parent 927a15a commit 4a77797
Show file tree
Hide file tree
Showing 10 changed files with 12 additions and 11 deletions.
Binary file modified .gradle/8.4/executionHistory/executionHistory.bin
Binary file not shown.
Binary file modified .gradle/8.4/executionHistory/executionHistory.lock
Binary file not shown.
Binary file modified .gradle/8.4/fileHashes/fileHashes.bin
Binary file not shown.
Binary file modified .gradle/8.4/fileHashes/fileHashes.lock
Binary file not shown.
Binary file modified .gradle/8.4/fileHashes/resourceHashesCache.bin
Binary file not shown.
Binary file modified .gradle/buildOutputCleanup/buildOutputCleanup.lock
Binary file not shown.
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,8 @@ class DriveBrakeModeCommand(val drivetrain: Drivetrain) : Command() {
}

override fun execute() {
drivetrain.currentRequest = DrivetrainRequest.OpenLoop(0.0.radians.perSecond, Velocity2d())
drivetrain.currentRequest =
DrivetrainRequest.OpenLoop(0.0.radians.perSecond, Velocity2d.ZERO_VELOCITY_VECTOR)
drivetrain.swerveModules.forEach() { it.setDriveBrakeMode(true) }
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ private constructor(
val flipForAlliances: Boolean = true,
val endPathOnceAtReference: Boolean = true,
val leaveOutYAdjustment: Boolean = false,
val endVelocity: Velocity2d = Velocity2d(),
val endVelocity: Velocity2d = Velocity2d.ZERO_VELOCITY_VECTOR,
var stateFrame: FrameType = FrameType.ODOMETRY,
var pathFrame: FrameType = FrameType.FIELD,
) : Command() {
Expand Down Expand Up @@ -427,7 +427,8 @@ private constructor(
// Execute one last time to end up in the final state of the trajectory
// Since we weren't interrupted, we know curTime > endTime
execute()
drivetrain.currentRequest = DrivetrainRequest.OpenLoop(0.0.radians.perSecond, Velocity2d())
drivetrain.currentRequest =
DrivetrainRequest.OpenLoop(0.0.radians.perSecond, Velocity2d.ZERO_VELOCITY_VECTOR)
}
}

Expand All @@ -443,7 +444,7 @@ private constructor(
flipForAlliances: Boolean = true,
endPathOnceAtReference: Boolean = true,
leaveOutYAdjustment: Boolean = false,
endVelocity: Velocity2d = Velocity2d(),
endVelocity: Velocity2d = Velocity2d.ZERO_VELOCITY_VECTOR,
stateFrame: FrameType = FrameType.ODOMETRY,
): DrivePathCommand<OdometryWaypoint> =
DrivePathCommand(
Expand All @@ -467,7 +468,7 @@ private constructor(
flipForAlliances: Boolean = true,
endPathOnceAtReference: Boolean = true,
leaveOutYAdjustment: Boolean = false,
endVelocity: Velocity2d = Velocity2d(),
endVelocity: Velocity2d = Velocity2d.ZERO_VELOCITY_VECTOR,
stateFrame: FrameType = FrameType.ODOMETRY,
): DrivePathCommand<FieldWaypoint> =
DrivePathCommand(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ class Drivetrain(private val gyroIO: GyroIO, val swerveModules: List<SwerveModul

private var angularVelocityTarget = 0.degrees.perSecond

private var targetedDriveVector = Velocity2d()
private var targetedDriveVector = Velocity2d.ZERO_VELOCITY_VECTOR

private var isFieldOriented = true

Expand All @@ -81,10 +81,10 @@ class Drivetrain(private val gyroIO: GyroIO, val swerveModules: List<SwerveModul

var targetPose: Pose2d = Pose2d(0.0.meters, 0.0.meters, 0.0.radians)

var fieldVelocity = Velocity2d()
var fieldVelocity = Velocity2d.ZERO_VELOCITY_VECTOR
private set

var robotVelocity = Velocity2d()
var robotVelocity = Velocity2d.ZERO_VELOCITY_VECTOR
private set

private var omegaVelocity = 0.0.radians.perSecond
Expand Down
5 changes: 2 additions & 3 deletions src/main/kotlin/com/team4099/robot2023/util/Velocity2d.kt
Original file line number Diff line number Diff line change
Expand Up @@ -12,16 +12,15 @@ import org.team4099.lib.units.perSecond
import kotlin.math.hypot

data class Velocity2d(val x: LinearVelocity, val y: LinearVelocity) {

constructor() : this(0.0.meters.perSecond, 0.0.meters.perSecond)

val velocity2dWPIlib = Translation2d(x.inMetersPerSecond, y.inMetersPerSecond)

val magnitude = hypot(x.inMetersPerSecond, y.inMetersPerSecond).meters.perSecond

val heading: Angle = velocity2dWPIlib.angle.angle

companion object {
val ZERO_VELOCITY_VECTOR = Velocity2d(0.0.meters.perSecond, 0.0.meters.perSecond)

fun fromVelocityVectorToVelocity2d(speed: LinearVelocity, heading: Angle): Velocity2d {
return Velocity2d(speed * heading.cos, speed * heading.sin)
}
Expand Down

0 comments on commit 4a77797

Please sign in to comment.