Skip to content

Commit

Permalink
Added SwerveDrive.getGyro(). reformatted code.
Browse files Browse the repository at this point in the history
Signed-off-by: thenetworkgrinch <[email protected]>
  • Loading branch information
thenetworkgrinch committed Jan 26, 2024
1 parent d153712 commit 8f0ed77
Show file tree
Hide file tree
Showing 4 changed files with 32 additions and 23 deletions.
48 changes: 28 additions & 20 deletions src/main/java/swervelib/SwerveDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -451,8 +451,7 @@ public void drive(ChassisSpeeds velocity, boolean isOpenLoop, Translation2d cent
{
velocity.omegaRadiansPerSecond =
swerveController.headingCalculate(getOdometryHeading().getRadians(), lastHeadingRadians);
}
else
} else
{
lastHeadingRadians = getOdometryHeading().getRadians();
}
Expand Down Expand Up @@ -679,6 +678,33 @@ public SwerveModulePosition[] getModulePositions()
return positions;
}

/**
* Getter for the {@link SwerveIMU}.
*
* @return generated {@link SwerveIMU}
*/
public SwerveIMU getGyro()
{
return swerveDriveConfiguration.imu;
}

/**
* Set the expected gyroscope angle using a {@link Rotation3d} object. To reset gyro, set to a new {@link Rotation3d}
* subtracted from the current gyroscopic readings {@link SwerveIMU#getRotation3d()}.
*
* @param gyro expected gyroscope angle as {@link Rotation3d}.
*/
public void setGyro(Rotation3d gyro)
{
if (SwerveDriveTelemetry.isSimulation)
{
setGyroOffset(simIMU.getGyroRotation3d().minus(gyro));
} else
{
setGyroOffset(imu.getRawRotation3d().minus(gyro));
}
}

/**
* Resets the gyro angle to zero and resets odometry to the same position, but facing toward 0.
*/
Expand Down Expand Up @@ -1042,24 +1068,6 @@ public void addVisionMeasurement(Pose2d robotPose, double timestamp)
// resetOdometry(newOdometry);
}


/**
* Set the expected gyroscope angle using a {@link Rotation3d} object. To reset gyro, set to a new {@link Rotation3d}
* subtracted from the current gyroscopic readings {@link SwerveIMU#getRotation3d()}.
*
* @param gyro expected gyroscope angle as {@link Rotation3d}.
*/
public void setGyro(Rotation3d gyro)
{
if (SwerveDriveTelemetry.isSimulation)
{
setGyroOffset(simIMU.getGyroRotation3d().minus(gyro));
} else
{
setGyroOffset(imu.getRawRotation3d().minus(gyro));
}
}

/**
* Helper function to get the {@link SwerveDrive#swerveController} for the {@link SwerveDrive} which can be used to
* generate {@link ChassisSpeeds} for the robot to orient it correctly given axis or angles, and apply
Expand Down
3 changes: 2 additions & 1 deletion src/main/java/swervelib/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -205,7 +205,8 @@ public void setDesiredState(SwerveModuleState desiredState, boolean isOpenLoop,
} else
{
double cosineScalar = 1.0;
if (configuration.useCosineCompensator) {
if (configuration.useCosineCompensator)
{
// Taken from the CTRE SwerveModule class.
// https://api.ctr-electronics.com/phoenix6/release/java/src-html/com/ctre/phoenix6/mechanisms/swerve/SwerveModule.html#line.46
/* From FRC 900's whitepaper, we add a cosine compensator to the applied drive velocity */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -164,7 +164,7 @@ public SwerveModuleConfiguration(
false,
false,
false,
name,
name,
useCosineCompensator);
}

Expand Down
2 changes: 1 addition & 1 deletion src/main/java/swervelib/parser/json/ModuleJson.java
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ public class ModuleJson
/**
* Should do cosine compensation when not pointing correct direction;.
*/
public boolean useCosineCompensator = true;
public boolean useCosineCompensator = true;

/**
* Create the swerve module configuration based off of parsed data.
Expand Down

0 comments on commit 8f0ed77

Please sign in to comment.