Skip to content

Commit d487e1c

Browse files
authored
Fix deprecation warnings in PhotonLib examples (#1699)
The following deprecation warnings have been fixed: - `SwerveModuleState.optimize(desiredState, currentRotation);`, which is now an instance method - `AprilTagFields.kDefaultField.loadAprilTagLayoutField();`, which is now `AprilTagFieldLayout.loadField(AprilTagFields.kDefaultField);` WIP: - [x] C++ - [x] Python
1 parent 159b848 commit d487e1c

File tree

12 files changed

+48
-27
lines changed

12 files changed

+48
-27
lines changed
Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
python3 -m pip config unset global.find-links

photon-lib/py/enableUsingDevBuilds.sh

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
python3 -m pip config set global.find-links dist

photonlib-java-examples/aimandrange/src/main/java/frc/robot/Constants.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@ public static class Vision {
4848

4949
// The layout of the AprilTags on the field
5050
public static final AprilTagFieldLayout kTagLayout =
51-
AprilTagFields.kDefaultField.loadAprilTagLayoutField();
51+
AprilTagFieldLayout.loadField(AprilTagFields.kDefaultField);
5252

5353
// The standard deviations of our vision estimated poses, which affect correction rate
5454
// (Fake values. Experiment and determine estimation noise on an actual robot.)

photonlib-java-examples/aimandrange/src/main/java/frc/robot/subsystems/drivetrain/SwerveModule.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -108,7 +108,7 @@ public void setDesiredState(
108108
SwerveModuleState desiredState, boolean openLoop, boolean steerInPlace) {
109109
Rotation2d currentRotation = getAbsoluteHeading();
110110
// Avoid turning more than 90 degrees by inverting speed on large angle changes
111-
desiredState = SwerveModuleState.optimize(desiredState, currentRotation);
111+
desiredState.optimize(currentRotation);
112112

113113
this.desiredState = desiredState;
114114
}

photonlib-java-examples/aimattarget/src/main/java/frc/robot/Constants.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@ public static class Vision {
4848

4949
// The layout of the AprilTags on the field
5050
public static final AprilTagFieldLayout kTagLayout =
51-
AprilTagFields.kDefaultField.loadAprilTagLayoutField();
51+
AprilTagFieldLayout.loadField(AprilTagFields.kDefaultField);
5252

5353
// The standard deviations of our vision estimated poses, which affect correction rate
5454
// (Fake values. Experiment and determine estimation noise on an actual robot.)

photonlib-java-examples/aimattarget/src/main/java/frc/robot/subsystems/drivetrain/SwerveModule.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -108,7 +108,7 @@ public void setDesiredState(
108108
SwerveModuleState desiredState, boolean openLoop, boolean steerInPlace) {
109109
Rotation2d currentRotation = getAbsoluteHeading();
110110
// Avoid turning more than 90 degrees by inverting speed on large angle changes
111-
desiredState = SwerveModuleState.optimize(desiredState, currentRotation);
111+
desiredState.optimize(currentRotation);
112112

113113
this.desiredState = desiredState;
114114
}

photonlib-java-examples/poseest/src/main/java/frc/robot/Constants.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ public static class Vision {
4646

4747
// The layout of the AprilTags on the field
4848
public static final AprilTagFieldLayout kTagLayout =
49-
AprilTagFields.kDefaultField.loadAprilTagLayoutField();
49+
AprilTagFieldLayout.loadField(AprilTagFields.kDefaultField);
5050

5151
// The standard deviations of our vision estimated poses, which affect correction rate
5252
// (Fake values. Experiment and determine estimation noise on an actual robot.)

photonlib-java-examples/poseest/src/main/java/frc/robot/subsystems/drivetrain/SwerveModule.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -108,7 +108,7 @@ public void setDesiredState(
108108
SwerveModuleState desiredState, boolean openLoop, boolean steerInPlace) {
109109
Rotation2d currentRotation = getAbsoluteHeading();
110110
// Avoid turning more than 90 degrees by inverting speed on large angle changes
111-
desiredState = SwerveModuleState.optimize(desiredState, currentRotation);
111+
desiredState.optimize(currentRotation);
112112

113113
this.desiredState = desiredState;
114114
}

photonlib-python-examples/aimandrange/swervemodule.py

Lines changed: 5 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -142,25 +142,23 @@ def setDesiredState(
142142
encoderRotation = wpimath.geometry.Rotation2d(self.turningEncoder.getDistance())
143143

144144
# Optimize the reference state to avoid spinning further than 90 degrees
145-
state = wpimath.kinematics.SwerveModuleState.optimize(
146-
self.desiredState, encoderRotation
147-
)
145+
desiredState.optimize(encoderRotation)
148146

149147
# Scale speed by cosine of angle error. This scales down movement perpendicular to the desired
150148
# direction of travel that can occur when modules change directions. This results in smoother
151149
# driving.
152-
state.speed *= (state.angle - encoderRotation).cos()
150+
desiredState.speed *= (desiredState.angle - encoderRotation).cos()
153151

154152
# Calculate the drive output from the drive PID controller.
155153
driveOutput = self.drivePIDController.calculate(
156-
self.driveEncoder.getRate(), state.speed
154+
self.driveEncoder.getRate(), desiredState.speed
157155
)
158156

159-
driveFeedforward = self.driveFeedforward.calculate(state.speed)
157+
driveFeedforward = self.driveFeedforward.calculate(desiredState.speed)
160158

161159
# Calculate the turning motor output from the turning PID controller.
162160
turnOutput = self.turningPIDController.calculate(
163-
self.turningEncoder.getDistance(), state.angle.radians()
161+
self.turningEncoder.getDistance(), desiredState.angle.radians()
164162
)
165163

166164
turnFeedforward = self.turnFeedforward.calculate(

photonlib-python-examples/aimattarget/swervemodule.py

Lines changed: 5 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -142,25 +142,23 @@ def setDesiredState(
142142
encoderRotation = wpimath.geometry.Rotation2d(self.turningEncoder.getDistance())
143143

144144
# Optimize the reference state to avoid spinning further than 90 degrees
145-
state = wpimath.kinematics.SwerveModuleState.optimize(
146-
self.desiredState, encoderRotation
147-
)
145+
desiredState.optimize(encoderRotation)
148146

149147
# Scale speed by cosine of angle error. This scales down movement perpendicular to the desired
150148
# direction of travel that can occur when modules change directions. This results in smoother
151149
# driving.
152-
state.speed *= (state.angle - encoderRotation).cos()
150+
desiredState.speed *= (desiredState.angle - encoderRotation).cos()
153151

154152
# Calculate the drive output from the drive PID controller.
155153
driveOutput = self.drivePIDController.calculate(
156-
self.driveEncoder.getRate(), state.speed
154+
self.driveEncoder.getRate(), desiredState.speed
157155
)
158156

159-
driveFeedforward = self.driveFeedforward.calculate(state.speed)
157+
driveFeedforward = self.driveFeedforward.calculate(desiredState.speed)
160158

161159
# Calculate the turning motor output from the turning PID controller.
162160
turnOutput = self.turningPIDController.calculate(
163-
self.turningEncoder.getDistance(), state.angle.radians()
161+
self.turningEncoder.getDistance(), desiredState.angle.radians()
164162
)
165163

166164
turnFeedforward = self.turnFeedforward.calculate(

0 commit comments

Comments
 (0)