Skip to content

Commit

Permalink
Formatted code.
Browse files Browse the repository at this point in the history
Signed-off-by: thenetworkgrinch <thenetworkgrinch@users.noreply.github.com>
  • Loading branch information
thenetworkgrinch committed Jun 12, 2024
1 parent 630ad97 commit 1d0bb34
Show file tree
Hide file tree
Showing 3 changed files with 33 additions and 29 deletions.
22 changes: 13 additions & 9 deletions src/main/java/swervelib/SwerveDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ public class SwerveDrive
/**
* Amount of seconds the duration of the timestep the speeds should be applied for.
*/
private double discretizationdtSeconds = 0.02;
private double discretizationdtSeconds = 0.02;
/**
* Deadband for speeds in heading correction.
*/
Expand Down Expand Up @@ -347,15 +347,17 @@ public void setHeadingCorrection(boolean state, double deadband)
}

/**
* Tertiary method of controlling the drive base given velocity in both field oriented and robot oriented at the same time.
* The inputs are added together so this is not intneded to be used to give the driver both methods of control.
*
* Tertiary method of controlling the drive base given velocity in both field oriented and robot oriented at the same
* time. The inputs are added together so this is not intneded to be used to give the driver both methods of control.
*
* @param fieldOrientedVelocity The field oriented velocties to use
* @param robotOrientedVelocity The robot oriented velocties to use
*/
public void driveFieldOrientedandRobotOriented(ChassisSpeeds fieldOrientedVelocity, ChassisSpeeds robotOrientedVelocity)
public void driveFieldOrientedandRobotOriented(ChassisSpeeds fieldOrientedVelocity,
ChassisSpeeds robotOrientedVelocity)
{
ChassisSpeeds TotalVelocties = ChassisSpeeds.fromFieldRelativeSpeeds(fieldOrientedVelocity, getOdometryHeading()).plus(robotOrientedVelocity);
ChassisSpeeds TotalVelocties = ChassisSpeeds.fromFieldRelativeSpeeds(fieldOrientedVelocity, getOdometryHeading())
.plus(robotOrientedVelocity);
drive(TotalVelocties);
}

Expand Down Expand Up @@ -1174,11 +1176,13 @@ public void setCosineCompensator(boolean enabled)

/**
* Sets the Chassis discretization seconds as well as enableing/disabling the Chassis velocity correction
*
* @param enable Enable chassis velocity correction, which will use {@link ChassisSpeeds#discretize(ChassisSpeeds, double)} with the following.
*
* @param enable Enable chassis velocity correction, which will use
* {@link ChassisSpeeds#discretize(ChassisSpeeds, double)} with the following.
* @param dtSeconds The duration of the timestep the speeds should be applied for.
*/
public void setChassisDiscretization(boolean enable, double dtSeconds){
public void setChassisDiscretization(boolean enable, double dtSeconds)
{
chassisVelocityCorrection = enable;
discretizationdtSeconds = dtSeconds;
}
Expand Down
39 changes: 20 additions & 19 deletions src/main/java/swervelib/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -82,14 +82,14 @@ public class SwerveModule
* Module number for kinematics, usually 0 to 3. front left -> front right -> back left -> back right.
*/
public int moduleNumber;
/**
* Feedforward for the drive motor during closed loop control.
*/
private SimpleMotorFeedforward driveMotorFeedforward;
/**
* Maximum speed of the drive motors in meters per second.
*/
public double maxSpeed;
/**
* Feedforward for the drive motor during closed loop control.
*/
private SimpleMotorFeedforward driveMotorFeedforward;
/**
* Anti-Jitter AKA auto-centering disabled.
*/
Expand Down Expand Up @@ -274,6 +274,16 @@ public void setFeedforward(SimpleMotorFeedforward drive)
this.driveMotorFeedforward = drive;
}

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

/**
* Set the drive PIDF values.
*
Expand All @@ -286,13 +296,13 @@ public void setDrivePIDF(PIDFConfig config)
}

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

/**
Expand All @@ -306,16 +316,6 @@ public void setAnglePIDF(PIDFConfig 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 Down Expand Up @@ -638,7 +638,8 @@ public void updateTelemetry()
}
SmartDashboard.putNumber(rawAngleName, angleMotor.getPosition());
SmartDashboard.putNumber(rawDriveName, driveMotor.getPosition());
SmartDashboard.putNumber(rawDriveVelName, driveMotor.getVelocity()); SmartDashboard.putNumber(adjAbsoluteAngleName, getAbsolutePosition());
SmartDashboard.putNumber(rawDriveVelName, driveMotor.getVelocity());
SmartDashboard.putNumber(adjAbsoluteAngleName, getAbsolutePosition());
SmartDashboard.putNumber(absoluteEncoderIssueName, getAbsoluteEncoderReadIssue() ? 1 : 0);
}
}
1 change: 0 additions & 1 deletion src/main/java/swervelib/motors/TalonSRXSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
import com.ctre.phoenix.motorcontrol.StatusFrameEnhanced;
import com.ctre.phoenix.motorcontrol.can.TalonSRXConfiguration;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
import edu.wpi.first.wpilibj.Timer;
import swervelib.encoders.SwerveAbsoluteEncoder;
import swervelib.math.SwerveMath;
import swervelib.parser.PIDFConfig;
Expand Down

0 comments on commit 1d0bb34

Please sign in to comment.