Skip to content

Commit

Permalink
Upgrading to 2025.1.0
Browse files Browse the repository at this point in the history
  • Loading branch information
thenetworkgrinch committed Dec 9, 2024
1 parent 9fe6551 commit 4bc6978
Show file tree
Hide file tree
Showing 35 changed files with 1,889 additions and 1,109 deletions.
2 changes: 1 addition & 1 deletion swervelib/SwerveController.java
Original file line number Diff line number Diff line change
Expand Up @@ -227,7 +227,7 @@ public double headingCalculate(double currentHeadingAngleRadians, double targetH
*
* @param angularVelocity Angular velocity in radians per second.
*/
public void setMaximumAngularVelocity(double angularVelocity)
public void setMaximumChassisAngularVelocity(double angularVelocity)
{
config.maxAngularVelocity = angularVelocity;
}
Expand Down
477 changes: 311 additions & 166 deletions swervelib/SwerveDrive.java

Large diffs are not rendered by default.

35 changes: 18 additions & 17 deletions swervelib/SwerveDriveTest.java
Original file line number Diff line number Diff line change
@@ -1,20 +1,20 @@
package swervelib;

import static edu.wpi.first.units.MutableMeasure.mutable;
import static edu.wpi.first.units.Units.Degrees;
import static edu.wpi.first.units.Units.DegreesPerSecond;
import static edu.wpi.first.units.Units.Meter;
import static edu.wpi.first.units.Units.Meters;
import static edu.wpi.first.units.Units.MetersPerSecond;
import static edu.wpi.first.units.Units.Seconds;
import static edu.wpi.first.units.Units.Volts;

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.units.Angle;
import edu.wpi.first.units.Distance;
import edu.wpi.first.units.Measure;
import edu.wpi.first.units.MutableMeasure;
import edu.wpi.first.units.Velocity;
import edu.wpi.first.units.Voltage;
import edu.wpi.first.units.measure.MutAngle;
import edu.wpi.first.units.measure.MutAngularVelocity;
import edu.wpi.first.units.measure.MutDistance;
import edu.wpi.first.units.measure.MutLinearVelocity;
import edu.wpi.first.units.measure.MutVoltage;
import edu.wpi.first.units.measure.Voltage;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.Timer;
Expand All @@ -37,23 +37,23 @@ public class SwerveDriveTest
/**
* Tracks the voltage being applied to a motor
*/
private static final MutableMeasure<Voltage> m_appliedVoltage = mutable(Volts.of(0));
private static final MutVoltage m_appliedVoltage = new MutVoltage(0, 0, Volts);
/**
* Tracks the distance travelled of a position motor
*/
private static final MutableMeasure<Distance> m_distance = mutable(Meters.of(0));
private static final MutDistance m_distance = new MutDistance(0, 0, Meter);
/**
* Tracks the velocity of a positional motor
*/
private static final MutableMeasure<Velocity<Distance>> m_velocity = mutable(MetersPerSecond.of(0));
private static final MutLinearVelocity m_velocity = new MutLinearVelocity(0, 9, MetersPerSecond);
/**
* Tracks the rotations of an angular motor
*/
private static final MutableMeasure<Angle> m_anglePosition = mutable(Degrees.of(0));
private static final MutAngle m_anglePosition = new MutAngle(0, 0, Degrees);
/**
* Tracks the velocity of an angular motor
*/
private static final MutableMeasure<Velocity<Angle>> m_angVelocity = mutable(DegreesPerSecond.of(0));
private static final MutAngularVelocity m_angVelocity = new MutAngularVelocity(0, 0, DegreesPerSecond);

/**
* Set the angle of the modules to a given {@link Rotation2d}
Expand Down Expand Up @@ -214,7 +214,7 @@ public static double findCouplingRatio(SwerveDrive swerveDrive, double volts, bo
Timer.delay(1);
Rotation2d startingAbsoluteEncoderPosition = Rotation2d.fromDegrees(absoluteEncoder.getAbsolutePosition());
double driveEncoderPositionRotations = module.getDriveMotor().getPosition() /
module.configuration.conversionFactors.drive;
module.configuration.conversionFactors.drive.factor;
if (automatic)
{
module.getAngleMotor().setVoltage(volts);
Expand All @@ -230,8 +230,9 @@ public static double findCouplingRatio(SwerveDrive swerveDrive, double volts, bo
false);
Timer.delay(60);
}
double couplingRatio = (module.getDriveMotor().getPosition() / module.configuration.conversionFactors.drive) -
driveEncoderPositionRotations;
double couplingRatio =
(module.getDriveMotor().getPosition() / module.configuration.conversionFactors.drive.factor) -
driveEncoderPositionRotations;
DriverStation.reportWarning(module.configuration.name + " Coupling Ratio: " + couplingRatio, false);
couplingRatioSum += couplingRatio;
}
Expand Down Expand Up @@ -308,7 +309,7 @@ public static SysIdRoutine setDriveSysIdRoutine(Config config, SubsystemBase swe
SwerveDrive swerveDrive, double maxVolts)
{
return new SysIdRoutine(config, new SysIdRoutine.Mechanism(
(Measure<Voltage> voltage) -> {
(Voltage voltage) -> {
SwerveDriveTest.centerModules(swerveDrive);
SwerveDriveTest.powerDriveMotorsVoltage(swerveDrive, Math.min(voltage.in(Volts), maxVolts));
},
Expand Down Expand Up @@ -380,7 +381,7 @@ public static SysIdRoutine setAngleSysIdRoutine(Config config, SubsystemBase swe
SwerveDrive swerveDrive)
{
return new SysIdRoutine(config, new SysIdRoutine.Mechanism(
(Measure<Voltage> voltage) -> {
(Voltage voltage) -> {
SwerveDriveTest.powerAngleMotorsVoltage(swerveDrive, voltage.in(Volts));
SwerveDriveTest.powerDriveMotorsVoltage(swerveDrive, 0);
},
Expand Down
Loading

0 comments on commit 4bc6978

Please sign in to comment.