Skip to content

Commit 80bfd28

Browse files
style: apply ktlint formatting [bot]
1 parent c044306 commit 80bfd28

4 files changed

Lines changed: 44 additions & 29 deletions

File tree

TeamCode/src/main/kotlin/pioneer/Constants.kt

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -99,7 +99,6 @@ object Follower {
9999
/** The maximum drive velocity in cm per second. */
100100
const val MAX_DRIVE_VELOCITY = 100.0
101101

102-
103102
/** The maximum drive acceleration in cm per second squared. */
104103
const val MAX_DRIVE_ACCELERATION = 50.0
105104

@@ -114,17 +113,23 @@ object Follower {
114113

115114
// X-axis PID coefficients for the trajectory follower
116115
@JvmField var X_KP = 0.0
116+
117117
@JvmField var X_KI = 0.0
118+
118119
@JvmField var X_KD = 0.0
119120

120121
// Y-axis PID coefficients for the trajectory follower
121122
@JvmField var Y_KP = 0.0
123+
122124
@JvmField var Y_KI = 0.0
125+
123126
@JvmField var Y_KD = 0.0
124127

125128
// Theta PID coefficients for the trajectory follower
126129
@JvmField var THETA_KP = 0.0
130+
127131
@JvmField var THETA_KI = 0.0
132+
128133
@JvmField var THETA_KD = 0.0
129134
}
130135

TeamCode/src/main/kotlin/pioneer/helpers/MathUtils.kt

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -43,12 +43,16 @@ object MathUtils {
4343
* @param heading Angle in radians to rotate the vector
4444
* @return Pair of rotated (x, y) components
4545
*/
46-
fun rotateVector(x: Double, y: Double, heading: Double): Pair<Double, Double> {
46+
fun rotateVector(
47+
x: Double,
48+
y: Double,
49+
heading: Double,
50+
): Pair<Double, Double> {
4751
val cos = cos(heading)
4852
val sin = sin(heading)
4953
return Pair(
5054
x * cos - y * sin,
51-
x * sin + y * cos
55+
x * sin + y * cos,
5256
)
5357
}
5458
}

TeamCode/src/main/kotlin/pioneer/pathing/follower/Follower.kt

Lines changed: 31 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -102,15 +102,15 @@ class Follower(
102102
ay = targetState.a * tangent.y + targetState.v.pow(2) * curvature * tangent.x,
103103
theta = headingTarget.x,
104104
omega = headingTarget.v,
105-
alpha = headingTarget.a
105+
alpha = headingTarget.a,
106106
)
107107

108108
// Calculate the error and convert to robot-centric coordinates
109109
val error =
110110
Pose(
111111
x = targetPose.x - localizer.pose.x,
112112
y = targetPose.y - localizer.pose.y,
113-
theta = MathUtils.normalizeRadians(headingTarget.x - localizer.pose.theta)
113+
theta = MathUtils.normalizeRadians(headingTarget.x - localizer.pose.theta),
114114
)
115115

116116
// Calculate the PID outputs
@@ -120,17 +120,19 @@ class Follower(
120120

121121
// Apply corrections to velocity directly
122122
// Rotate to convert to robot-centric coordinates
123-
val (vxRobot, vyRobot) = MathUtils.rotateVector(
124-
x = targetPose.vx + xCorrection,
125-
y = targetPose.vy + yCorrection,
126-
heading = -localizer.pose.theta
127-
)
123+
val (vxRobot, vyRobot) =
124+
MathUtils.rotateVector(
125+
x = targetPose.vx + xCorrection,
126+
y = targetPose.vy + yCorrection,
127+
heading = -localizer.pose.theta,
128+
)
128129

129-
val correctedPose = targetPose.copy(
130-
vx = vxRobot,
131-
vy = vyRobot,
132-
omega = targetPose.omega + turnCorrection
133-
)
130+
val correctedPose =
131+
targetPose.copy(
132+
vx = vxRobot,
133+
vy = vyRobot,
134+
omega = targetPose.omega + turnCorrection,
135+
)
134136

135137
mecanumBase.setDriveVA(correctedPose)
136138
}
@@ -140,7 +142,7 @@ class Follower(
140142
elapsedTime.reset()
141143
// Reset the PID controllers
142144
xPID.reset()
143-
yPID.reset()
145+
yPID.reset()
144146
headingPID.reset()
145147
}
146148

@@ -171,22 +173,25 @@ class Follower(
171173
FollowerConstants.MAX_DRIVE_ACCELERATION
172174
}
173175
return MotionProfileGenerator.generateMotionProfile(
174-
startState,
175-
endState,
176-
velocityConstraint,
177-
accelerationConstraint,
178-
)
176+
startState,
177+
endState,
178+
velocityConstraint,
179+
accelerationConstraint,
180+
)
179181
} else {
180182
return null
181183
}
182184
}
183185

184-
private fun calculateHeadingProfile(): MotionProfile? {
185-
return if (path != null) MotionProfileGenerator.generateMotionProfile(
186-
MotionState(localizer.pose.theta, 0.0, 0.0),
187-
MotionState(path!!.endPose.theta, 0.0, 0.0),
188-
{ FollowerConstants.MAX_ANGULAR_VELOCITY },
189-
{ FollowerConstants.MAX_ANGULAR_ACCELERATION },
190-
) else null
191-
}
186+
private fun calculateHeadingProfile(): MotionProfile? =
187+
if (path != null) {
188+
MotionProfileGenerator.generateMotionProfile(
189+
MotionState(localizer.pose.theta, 0.0, 0.0),
190+
MotionState(path!!.endPose.theta, 0.0, 0.0),
191+
{ FollowerConstants.MAX_ANGULAR_VELOCITY },
192+
{ FollowerConstants.MAX_ANGULAR_ACCELERATION },
193+
)
194+
} else {
195+
null
196+
}
192197
}

TeamCode/src/main/kotlin/pioneer/pathing/paths/LinearPath.kt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@ class LinearPath(
1313
) : Path {
1414
// Constructor overloads
1515
constructor(startX: Double, startY: Double, endX: Double, endY: Double) : this(Pose(startX, startY), Pose(endX, endY))
16+
1617
override fun getLength(): Double = startPose.distanceTo(endPose)
1718

1819
override fun getLengthSoFar(t: Double): Double = getLength() * t

0 commit comments

Comments
 (0)