mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-19 00:41:41 +00:00
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
This commit is contained in:
1
photon-lib/py/disableUsingDevBuilds.sh
Executable file
1
photon-lib/py/disableUsingDevBuilds.sh
Executable file
@@ -0,0 +1 @@
|
||||
python3 -m pip config unset global.find-links
|
||||
1
photon-lib/py/enableUsingDevBuilds.sh
Executable file
1
photon-lib/py/enableUsingDevBuilds.sh
Executable file
@@ -0,0 +1 @@
|
||||
python3 -m pip config set global.find-links dist
|
||||
@@ -48,7 +48,7 @@ public class Constants {
|
||||
|
||||
// The layout of the AprilTags on the field
|
||||
public static final AprilTagFieldLayout kTagLayout =
|
||||
AprilTagFields.kDefaultField.loadAprilTagLayoutField();
|
||||
AprilTagFieldLayout.loadField(AprilTagFields.kDefaultField);
|
||||
|
||||
// The standard deviations of our vision estimated poses, which affect correction rate
|
||||
// (Fake values. Experiment and determine estimation noise on an actual robot.)
|
||||
|
||||
@@ -108,7 +108,7 @@ public class SwerveModule {
|
||||
SwerveModuleState desiredState, boolean openLoop, boolean steerInPlace) {
|
||||
Rotation2d currentRotation = getAbsoluteHeading();
|
||||
// Avoid turning more than 90 degrees by inverting speed on large angle changes
|
||||
desiredState = SwerveModuleState.optimize(desiredState, currentRotation);
|
||||
desiredState.optimize(currentRotation);
|
||||
|
||||
this.desiredState = desiredState;
|
||||
}
|
||||
|
||||
@@ -48,7 +48,7 @@ public class Constants {
|
||||
|
||||
// The layout of the AprilTags on the field
|
||||
public static final AprilTagFieldLayout kTagLayout =
|
||||
AprilTagFields.kDefaultField.loadAprilTagLayoutField();
|
||||
AprilTagFieldLayout.loadField(AprilTagFields.kDefaultField);
|
||||
|
||||
// The standard deviations of our vision estimated poses, which affect correction rate
|
||||
// (Fake values. Experiment and determine estimation noise on an actual robot.)
|
||||
|
||||
@@ -108,7 +108,7 @@ public class SwerveModule {
|
||||
SwerveModuleState desiredState, boolean openLoop, boolean steerInPlace) {
|
||||
Rotation2d currentRotation = getAbsoluteHeading();
|
||||
// Avoid turning more than 90 degrees by inverting speed on large angle changes
|
||||
desiredState = SwerveModuleState.optimize(desiredState, currentRotation);
|
||||
desiredState.optimize(currentRotation);
|
||||
|
||||
this.desiredState = desiredState;
|
||||
}
|
||||
|
||||
@@ -46,7 +46,7 @@ public class Constants {
|
||||
|
||||
// The layout of the AprilTags on the field
|
||||
public static final AprilTagFieldLayout kTagLayout =
|
||||
AprilTagFields.kDefaultField.loadAprilTagLayoutField();
|
||||
AprilTagFieldLayout.loadField(AprilTagFields.kDefaultField);
|
||||
|
||||
// The standard deviations of our vision estimated poses, which affect correction rate
|
||||
// (Fake values. Experiment and determine estimation noise on an actual robot.)
|
||||
|
||||
@@ -108,7 +108,7 @@ public class SwerveModule {
|
||||
SwerveModuleState desiredState, boolean openLoop, boolean steerInPlace) {
|
||||
Rotation2d currentRotation = getAbsoluteHeading();
|
||||
// Avoid turning more than 90 degrees by inverting speed on large angle changes
|
||||
desiredState = SwerveModuleState.optimize(desiredState, currentRotation);
|
||||
desiredState.optimize(currentRotation);
|
||||
|
||||
this.desiredState = desiredState;
|
||||
}
|
||||
|
||||
@@ -142,25 +142,23 @@ class SwerveModule:
|
||||
encoderRotation = wpimath.geometry.Rotation2d(self.turningEncoder.getDistance())
|
||||
|
||||
# Optimize the reference state to avoid spinning further than 90 degrees
|
||||
state = wpimath.kinematics.SwerveModuleState.optimize(
|
||||
self.desiredState, encoderRotation
|
||||
)
|
||||
desiredState.optimize(encoderRotation)
|
||||
|
||||
# Scale speed by cosine of angle error. This scales down movement perpendicular to the desired
|
||||
# direction of travel that can occur when modules change directions. This results in smoother
|
||||
# driving.
|
||||
state.speed *= (state.angle - encoderRotation).cos()
|
||||
desiredState.speed *= (desiredState.angle - encoderRotation).cos()
|
||||
|
||||
# Calculate the drive output from the drive PID controller.
|
||||
driveOutput = self.drivePIDController.calculate(
|
||||
self.driveEncoder.getRate(), state.speed
|
||||
self.driveEncoder.getRate(), desiredState.speed
|
||||
)
|
||||
|
||||
driveFeedforward = self.driveFeedforward.calculate(state.speed)
|
||||
driveFeedforward = self.driveFeedforward.calculate(desiredState.speed)
|
||||
|
||||
# Calculate the turning motor output from the turning PID controller.
|
||||
turnOutput = self.turningPIDController.calculate(
|
||||
self.turningEncoder.getDistance(), state.angle.radians()
|
||||
self.turningEncoder.getDistance(), desiredState.angle.radians()
|
||||
)
|
||||
|
||||
turnFeedforward = self.turnFeedforward.calculate(
|
||||
|
||||
@@ -142,25 +142,23 @@ class SwerveModule:
|
||||
encoderRotation = wpimath.geometry.Rotation2d(self.turningEncoder.getDistance())
|
||||
|
||||
# Optimize the reference state to avoid spinning further than 90 degrees
|
||||
state = wpimath.kinematics.SwerveModuleState.optimize(
|
||||
self.desiredState, encoderRotation
|
||||
)
|
||||
desiredState.optimize(encoderRotation)
|
||||
|
||||
# Scale speed by cosine of angle error. This scales down movement perpendicular to the desired
|
||||
# direction of travel that can occur when modules change directions. This results in smoother
|
||||
# driving.
|
||||
state.speed *= (state.angle - encoderRotation).cos()
|
||||
desiredState.speed *= (desiredState.angle - encoderRotation).cos()
|
||||
|
||||
# Calculate the drive output from the drive PID controller.
|
||||
driveOutput = self.drivePIDController.calculate(
|
||||
self.driveEncoder.getRate(), state.speed
|
||||
self.driveEncoder.getRate(), desiredState.speed
|
||||
)
|
||||
|
||||
driveFeedforward = self.driveFeedforward.calculate(state.speed)
|
||||
driveFeedforward = self.driveFeedforward.calculate(desiredState.speed)
|
||||
|
||||
# Calculate the turning motor output from the turning PID controller.
|
||||
turnOutput = self.turningPIDController.calculate(
|
||||
self.turningEncoder.getDistance(), state.angle.radians()
|
||||
self.turningEncoder.getDistance(), desiredState.angle.radians()
|
||||
)
|
||||
|
||||
turnFeedforward = self.turnFeedforward.calculate(
|
||||
|
||||
@@ -141,25 +141,23 @@ class SwerveModule:
|
||||
encoderRotation = wpimath.geometry.Rotation2d(self.turningEncoder.getDistance())
|
||||
|
||||
# Optimize the reference state to avoid spinning further than 90 degrees
|
||||
state = wpimath.kinematics.SwerveModuleState.optimize(
|
||||
self.desiredState, encoderRotation
|
||||
)
|
||||
self.desiredState.optimize(encoderRotation)
|
||||
|
||||
# Scale speed by cosine of angle error. This scales down movement perpendicular to the desired
|
||||
# direction of travel that can occur when modules change directions. This results in smoother
|
||||
# driving.
|
||||
state.speed *= (state.angle - encoderRotation).cos()
|
||||
self.desiredState.speed *= (self.desiredState.angle - encoderRotation).cos()
|
||||
|
||||
# Calculate the drive output from the drive PID controller.
|
||||
driveOutput = self.drivePIDController.calculate(
|
||||
self.driveEncoder.getRate(), state.speed
|
||||
self.driveEncoder.getRate(), self.desiredState.speed
|
||||
)
|
||||
|
||||
driveFeedforward = self.driveFeedforward.calculate(state.speed)
|
||||
driveFeedforward = self.driveFeedforward.calculate(self.desiredState.speed)
|
||||
|
||||
# Calculate the turning motor output from the turning PID controller.
|
||||
turnOutput = self.turningPIDController.calculate(
|
||||
self.turningEncoder.getDistance(), state.angle.radians()
|
||||
self.turningEncoder.getDistance(), self.desiredState.angle.radians()
|
||||
)
|
||||
|
||||
self.driveMotor.setVoltage(driveOutput + driveFeedforward)
|
||||
|
||||
25
photonlib-python-examples/run.sh
Executable file
25
photonlib-python-examples/run.sh
Executable file
@@ -0,0 +1,25 @@
|
||||
# Check if the first argument is provided
|
||||
if [ $# -eq 0 ]
|
||||
then
|
||||
echo "Error: No example-to-run provided."
|
||||
exit 1
|
||||
fi
|
||||
|
||||
# To run any example, we want to use photonlib out of this repo
|
||||
# Build the wheel first
|
||||
pushd ../photon-lib/py
|
||||
if [ -d build ]
|
||||
then rm -rdf build
|
||||
fi
|
||||
python3 setup.py bdist_wheel
|
||||
popd
|
||||
|
||||
# Add the output directory to PYTHONPATH to make sure it gets picked up
|
||||
export PHOTONLIBPY_ROOT=../photon-lib/py
|
||||
export PYTHONPATH=$PHOTONLIBPY_ROOT
|
||||
|
||||
# Move to the right example folder
|
||||
cd $1
|
||||
|
||||
# Run the example
|
||||
robotpy sim
|
||||
Reference in New Issue
Block a user