Skip to content

Commit

Permalink
Merge pull request #9 from BroncBotz3481/dev
Browse files Browse the repository at this point in the history
Update to latest
  • Loading branch information
clrozeboom authored Mar 6, 2024
2 parents cf3dcc7 + 425b421 commit eb52d81
Show file tree
Hide file tree
Showing 7 changed files with 124 additions and 49 deletions.
20 changes: 10 additions & 10 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -60,25 +60,25 @@ public RobotContainer()
// left stick controls translation
// right stick controls the desired angle NOT angular rotation
Command driveFieldOrientedDirectAngle = drivebase.driveCommand(
() -> -MathUtil.applyDeadband(driverXbox.getLeftY(), OperatorConstants.LEFT_Y_DEADBAND),
() -> -MathUtil.applyDeadband(driverXbox.getLeftX(), OperatorConstants.LEFT_X_DEADBAND),
() -> -driverXbox.getRightX(),
() -> -driverXbox.getRightY());
() -> MathUtil.applyDeadband(driverXbox.getLeftY(), OperatorConstants.LEFT_Y_DEADBAND),
() -> MathUtil.applyDeadband(driverXbox.getLeftX(), OperatorConstants.LEFT_X_DEADBAND),
() -> driverXbox.getRightX(),
() -> driverXbox.getRightY());

// Applies deadbands and inverts controls because joysticks
// are back-right positive while robot
// controls are front-left positive
// left stick controls translation
// right stick controls the angular velocity of the robot
Command driveFieldOrientedAnglularVelocity = drivebase.driveCommand(
() -> -MathUtil.applyDeadband(driverXbox.getLeftY(), OperatorConstants.LEFT_Y_DEADBAND),
() -> -MathUtil.applyDeadband(driverXbox.getLeftX(), OperatorConstants.LEFT_X_DEADBAND),
() -> -driverXbox.getRightX());
() -> MathUtil.applyDeadband(driverXbox.getLeftY(), OperatorConstants.LEFT_Y_DEADBAND),
() -> MathUtil.applyDeadband(driverXbox.getLeftX(), OperatorConstants.LEFT_X_DEADBAND),
() -> driverXbox.getRightX() * 0.5);

Command driveFieldOrientedDirectAngleSim = drivebase.simDriveCommand(
() -> -MathUtil.applyDeadband(driverXbox.getLeftY(), OperatorConstants.LEFT_Y_DEADBAND),
() -> -MathUtil.applyDeadband(driverXbox.getLeftX(), OperatorConstants.LEFT_X_DEADBAND),
() -> -driverXbox.getRawAxis(2));
() -> MathUtil.applyDeadband(driverXbox.getLeftY(), OperatorConstants.LEFT_Y_DEADBAND),
() -> MathUtil.applyDeadband(driverXbox.getLeftX(), OperatorConstants.LEFT_X_DEADBAND),
() -> driverXbox.getRawAxis(2));

drivebase.setDefaultCommand(
!RobotBase.isSimulation() ? driveFieldOrientedDirectAngle : driveFieldOrientedDirectAngleSim);
Expand Down
16 changes: 8 additions & 8 deletions src/main/java/swervelib/SwerveDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -839,9 +839,9 @@ public void setMaximumSpeed(double maximumSpeed, boolean updateModuleFeedforward
module.maxSpeed = maximumSpeed;
if (updateModuleFeedforward)
{
module.feedforward = SwerveMath.createDriveFeedforward(optimalVoltage,
maximumSpeed,
swerveDriveConfiguration.physicalCharacteristics.wheelGripCoefficientOfFriction);
module.setFeedforward(SwerveMath.createDriveFeedforward(optimalVoltage,
maximumSpeed,
swerveDriveConfiguration.physicalCharacteristics.wheelGripCoefficientOfFriction));
}
}
}
Expand All @@ -851,7 +851,7 @@ public void setMaximumSpeed(double maximumSpeed, boolean updateModuleFeedforward
* {@link SwerveDrive#setRawModuleStates(SwerveModuleState[], boolean)} function and
* {@link SwerveController#getTargetSpeeds(double, double, double, double, double)} functions. This function overrides
* what was placed in the JSON and could damage your motor/robot if set too high or unachievable rates. Overwrites the
* {@link SwerveModule#feedforward}.
* {@link SwerveModule#setFeedforward(SimpleMotorFeedforward)}.
*
* @param maximumSpeed Maximum speed for the drive motors in meters / second.
*/
Expand Down Expand Up @@ -908,13 +908,13 @@ public Pose2d[] getSwerveModulePoses(Pose2d robotPose)
/**
* Setup the swerve module feedforward.
*
* @param feedforward Feedforward for the drive motor on swerve modules.
* @param driveFeedforward Feedforward for the drive motor on swerve modules.
*/
public void replaceSwerveModuleFeedforward(SimpleMotorFeedforward feedforward)
public void replaceSwerveModuleFeedforward(SimpleMotorFeedforward driveFeedforward)
{
for (SwerveModule swerveModule : swerveModules)
{
swerveModule.feedforward = feedforward;
swerveModule.setFeedforward(driveFeedforward);
}
}

Expand Down Expand Up @@ -1114,7 +1114,7 @@ public void resetDriveEncoders()
{
for (SwerveModule module : swerveModules)
{
module.configuration.driveMotor.setPosition(0);
module.getDriveMotor().setPosition(0);
}
}

Expand Down
89 changes: 82 additions & 7 deletions src/main/java/swervelib/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
import swervelib.math.SwerveMath;
import swervelib.motors.SwerveMotor;
import swervelib.parser.Cache;
import swervelib.parser.PIDFConfig;
import swervelib.parser.SwerveModuleConfiguration;
import swervelib.simulation.SwerveModuleSimulation;
import swervelib.telemetry.Alert;
Expand Down Expand Up @@ -78,13 +79,17 @@ public class SwerveModule
*/
public int moduleNumber;
/**
* Feedforward for drive motor during closed loop control.
* Feedforward for the drive motor during closed loop control.
*/
public SimpleMotorFeedforward feedforward;
private SimpleMotorFeedforward driveMotorFeedforward;
/**
* Maximum speed of the drive motors in meters per second.
*/
public double maxSpeed;
/**
* Anti-Jitter AKA auto-centering disabled.
*/
private boolean antiJitterEnabled = true;
/**
* Last swerve module state applied.
*/
Expand Down Expand Up @@ -122,8 +127,8 @@ public SwerveModule(int moduleNumber, SwerveModuleConfiguration moduleConfigurat
configuration = moduleConfiguration;
angleOffset = moduleConfiguration.angleOffset;

// Initialize Feedforward for drive motor.
feedforward = driveFeedforward;
// Initialize Feedforwards.
driveMotorFeedforward = driveFeedforward;

// Create motors from configuration and reset them to defaults.
angleMotor = moduleConfiguration.angleMotor;
Expand Down Expand Up @@ -236,6 +241,76 @@ public void queueSynchronizeEncoders()
}
}

/**
* Set the antiJitter functionality, if true the modules will NOT auto center. Pushes the offsets to the angle motor
* controllers as well.
*
* @param antiJitter Anti-Jitter state desired.
*/
public void setAntiJitter(boolean antiJitter)
{
this.antiJitterEnabled = antiJitter;
if (antiJitter)
{
pushOffsetsToControllers();
} else
{
restoreInternalOffset();
}
}

/**
* Set the feedforward attributes to the given parameters.
*
* @param drive Drive motor feedforward for the module.
*/
public void setFeedforward(SimpleMotorFeedforward drive)
{
this.driveMotorFeedforward = drive;
}

/**
* Set the drive PIDF values.
*
* @param config {@link PIDFConfig} of that should be set.
*/
public void setDrivePIDF(PIDFConfig config)
{
configuration.velocityPIDF = config;
driveMotor.configurePIDF(config);
}

/**
* Get the current drive motor PIDF values.
*
* @return {@link PIDFConfig} of the drive motor.
*/
public PIDFConfig getDrivePIDF()
{
return configuration.velocityPIDF;
}

/**
* Set the angle/azimuth/steering motor PID
*
* @param config {@link PIDFConfig} of that should be set.
*/
public void setAnglePIDF(PIDFConfig config)
{
configuration.anglePIDF = config;
angleMotor.configurePIDF(config);
}

/**
* Get the current angle/azimuth/steering motor PIDF values.
*
* @return {@link PIDFConfig} of the angle motor.
*/
public PIDFConfig getAnglePIDF()
{
return configuration.anglePIDF;
}

/**
* Set the desired state of the swerve module. <br /><b>WARNING: If you are not using one of the functions from
* {@link SwerveDrive} you may screw up {@link SwerveDrive#kinematics}</b>
Expand All @@ -250,7 +325,7 @@ public void setDesiredState(SwerveModuleState desiredState, boolean isOpenLoop,
desiredState = SwerveModuleState.optimize(desiredState, Rotation2d.fromDegrees(getAbsolutePosition()));

// If we are forcing the angle
if (!force)
if (!force && antiJitterEnabled)
{
// Prevents module rotation if speed is less than 1%
SwerveMath.antiJitter(desiredState, lastState, Math.min(maxSpeed, 4));
Expand All @@ -267,7 +342,7 @@ public void setDesiredState(SwerveModuleState desiredState, boolean isOpenLoop,
driveMotor.set(percentOutput);
} else
{
driveMotor.setReference(velocity, feedforward.calculate(velocity));
driveMotor.setReference(velocity, driveMotorFeedforward.calculate(velocity));
desiredState.speedMetersPerSecond = velocity;
}

Expand Down Expand Up @@ -507,7 +582,7 @@ public SwerveModuleConfiguration getConfiguration()
*/
public void pushOffsetsToControllers()
{
if (absoluteEncoder != null)
if (absoluteEncoder != null && angleOffset == configuration.angleOffset)
{
if (absoluteEncoder.setAbsoluteEncoderOffset(angleOffset))
{
Expand Down
6 changes: 3 additions & 3 deletions vendordeps/PathplannerLib.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "PathplannerLib.json",
"name": "PathplannerLib",
"version": "2024.2.3",
"version": "2024.2.4",
"uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
"frcYear": "2024",
"mavenUrls": [
Expand All @@ -12,15 +12,15 @@
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-java",
"version": "2024.2.3"
"version": "2024.2.4"
}
],
"jniDependencies": [],
"cppDependencies": [
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-cpp",
"version": "2024.2.3",
"version": "2024.2.4",
"libName": "PathplannerLib",
"headerClassifier": "headers",
"sharedLibrary": false,
Expand Down
22 changes: 11 additions & 11 deletions vendordeps/Phoenix5.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "Phoenix5.json",
"name": "CTRE-Phoenix (v5)",
"version": "5.33.0",
"version": "5.33.1",
"frcYear": 2024,
"uuid": "ab676553-b602-441f-a38d-f1296eff6537",
"mavenUrls": [
Expand All @@ -20,19 +20,19 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-java",
"version": "5.33.0"
"version": "5.33.1"
},
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-java",
"version": "5.33.0"
"version": "5.33.1"
}
],
"jniDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
"version": "5.33.0",
"version": "5.33.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
Expand All @@ -45,7 +45,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim",
"version": "5.33.0",
"version": "5.33.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
Expand All @@ -60,7 +60,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-cpp",
"version": "5.33.0",
"version": "5.33.1",
"libName": "CTRE_Phoenix_WPI",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -75,7 +75,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-cpp",
"version": "5.33.0",
"version": "5.33.1",
"libName": "CTRE_Phoenix",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -90,7 +90,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
"version": "5.33.0",
"version": "5.33.1",
"libName": "CTRE_PhoenixCCI",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -105,7 +105,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "wpiapi-cpp-sim",
"version": "5.33.0",
"version": "5.33.1",
"libName": "CTRE_Phoenix_WPISim",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -120,7 +120,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "api-cpp-sim",
"version": "5.33.0",
"version": "5.33.1",
"libName": "CTRE_PhoenixSim",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -135,7 +135,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim",
"version": "5.33.0",
"version": "5.33.1",
"libName": "CTRE_PhoenixCCISim",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand Down
10 changes: 5 additions & 5 deletions vendordeps/REVLib.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "REVLib.json",
"name": "REVLib",
"version": "2024.2.1",
"version": "2024.2.3",
"frcYear": "2024",
"uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb",
"mavenUrls": [
Expand All @@ -12,14 +12,14 @@
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-java",
"version": "2024.2.1"
"version": "2024.2.3"
}
],
"jniDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver",
"version": "2024.2.1",
"version": "2024.2.3",
"skipInvalidPlatforms": true,
"isJar": false,
"validPlatforms": [
Expand All @@ -37,7 +37,7 @@
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-cpp",
"version": "2024.2.1",
"version": "2024.2.3",
"libName": "REVLib",
"headerClassifier": "headers",
"sharedLibrary": false,
Expand All @@ -55,7 +55,7 @@
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver",
"version": "2024.2.1",
"version": "2024.2.3",
"libName": "REVLibDriver",
"headerClassifier": "headers",
"sharedLibrary": false,
Expand Down
Loading

0 comments on commit eb52d81

Please sign in to comment.