Skip to content

Commit

Permalink
Renamed swerve/Adjusted IMU Reading to swerve/imu/adjusted and `s…
Browse files Browse the repository at this point in the history
…werve/Raw IMU Yaw` to `swerve/imu/raw`. Removed unnecessary warning. Made Pigeon2 use `refresh` instead of `waitForUpdate`. Shortened CANCoder refresh time to 1ms.

Signed-off-by: thenetworkgrinch <thenetworkgrinch@users.noreply.github.com>
  • Loading branch information
thenetworkgrinch committed Jan 7, 2025
1 parent f557d07 commit ace71bb
Show file tree
Hide file tree
Showing 7 changed files with 16 additions and 29 deletions.
8 changes: 6 additions & 2 deletions src/main/java/swervelib/SwerveDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -118,16 +118,20 @@ public class SwerveDrive
*/
private final DoublePublisher rawIMUPublisher
= NetworkTableInstance.getDefault()
.getTable(
"SmartDashboard")
.getDoubleTopic(
"SmartDashboard/swerve/Raw IMU Yaw")
"swerve/imu/raw")
.publish();
/**
* NT4 Publisher for the IMU reading adjusted by offset and inversion.
*/
private final DoublePublisher adjustedIMUPublisher
= NetworkTableInstance.getDefault()
.getTable(
"SmartDashboard")
.getDoubleTopic(
"SmartDashboard/swerve/Adjusted IMU Yaw")
"swerve/imu/adjusted")
.publish();
/**
* Field object.
Expand Down
6 changes: 5 additions & 1 deletion src/main/java/swervelib/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -796,13 +796,17 @@ public void updateTelemetry()
{
rawAbsoluteAnglePublisher.set(absoluteEncoder.getAbsolutePosition());
}
if (SwerveDriveTelemetry.isSimulation)
if (SwerveDriveTelemetry.isSimulation && SwerveDriveTelemetry.verbosity == TelemetryVerbosity.HIGH)
{
SwerveModulePosition pos = simModule.getPosition();
SwerveModuleState state = simModule.getState();
rawAnglePublisher.set(pos.angle.getDegrees());
rawDriveEncoderPublisher.set(pos.distanceMeters);
rawDriveVelocityPublisher.set(state.speedMetersPerSecond);
// For code coverage
angleMotor.getPosition();
drivePositionCache.getValue();
driveVelocityCache.getValue();
} else
{
rawAnglePublisher.set(angleMotor.getPosition());
Expand Down
8 changes: 4 additions & 4 deletions src/main/java/swervelib/encoders/CANCoderSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ public class CANCoderSwerve extends SwerveAbsoluteEncoder
/**
* Wait time for status frames to show up.
*/
public static double STATUS_TIMEOUT_SECONDS = Milliseconds.of(10).in(Seconds);
public static double STATUS_TIMEOUT_SECONDS = Milliseconds.of(1).in(Seconds);
/**
* An {@link Alert} for if the CANCoder magnet field is less than ideal.
*/
Expand Down Expand Up @@ -158,6 +158,7 @@ public double getAbsolutePosition()
{
readingError = false;
MagnetHealthValue strength = magnetHealth.refresh().getValue();
angle.refresh();

magnetFieldLessThanIdeal.set(strength != MagnetHealthValue.Magnet_Green);
if (strength == MagnetHealthValue.Magnet_Invalid || strength == MagnetHealthValue.Magnet_Red)
Expand All @@ -170,7 +171,6 @@ public double getAbsolutePosition()
readingFaulty.set(false);
}

angle.refresh();

// Taken from democat's library.
// Source: https://github.com/democat3457/swerve-lib/blob/7c03126b8c22f23a501b2c2742f9d173a5bcbc40/src/main/java/com/swervedrivespecialties/swervelib/ctre/CanCoderFactoryBuilder.java#L51-L74
Expand All @@ -190,8 +190,8 @@ public double getAbsolutePosition()
{
readingIgnored.set(false);
}

return angle.getValue().in(Degrees);
// Convert from Rotations to Degrees.
return angle.getValueAsDouble() * 360;
}

/**
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/swervelib/imu/Pigeon2Swerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -167,7 +167,7 @@ public Optional<Translation3d> getAccel()
@Override
public MutAngularVelocity getYawAngularVelocity()
{
return yawVel.mut_replace(imu.getAngularVelocityZWorld().waitForUpdate(STATUS_TIMEOUT_SECONDS).getValue());
return yawVel.mut_replace(imu.getAngularVelocityZWorld().refresh().getValue());
}

/**
Expand Down
13 changes: 0 additions & 13 deletions src/main/java/swervelib/motors/SparkFlexSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -57,18 +57,10 @@ public class SparkFlexSwerve extends SwerveMotor
* Supplier for the position of the motor controller.
*/
private Supplier<Double> position;
/**
* Factory default already occurred.
*/
private boolean factoryDefaultOccurred = false;
/**
* An {@link Alert} for if there is an error configuring the motor.
*/
private Alert failureConfiguring;
/**
* An {@link Alert} for if the absolute encoder's offset is set in the json instead of the hardware client.
*/
private Alert absoluteEncoderOffsetWarning;
/**
* Configuration object for {@link SparkFlex} motor.
*/
Expand Down Expand Up @@ -99,10 +91,6 @@ public SparkFlexSwerve(SparkFlex motor, boolean isDriveMotor, DCMotor motorType)
"Failure configuring motor " +
motor.getDeviceId(),
AlertType.kWarning);
absoluteEncoderOffsetWarning = new Alert("Motors",
"IF possible configure the duty cycle encoder offset in the REV Hardware Client instead of using the " +
"absoluteEncoderOffset in the Swerve Module JSON!",
AlertType.kWarning);
velocity = encoder::getVelocity;
position = encoder::getPosition;
}
Expand Down Expand Up @@ -272,7 +260,6 @@ public SwerveMotor setAbsoluteEncoder(SwerveAbsoluteEncoder encoder)
} else if (encoder.getAbsoluteEncoder() instanceof AbsoluteEncoder)
{
cfg.closedLoop.feedbackSensor(FeedbackSensor.kAbsoluteEncoder);
absoluteEncoderOffsetWarning.set(true);
absoluteEncoder = encoder;

velocity = absoluteEncoder::getVelocity;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -333,10 +333,6 @@ public SwerveMotor setAbsoluteEncoder(SwerveAbsoluteEncoder encoder)
cfg.closedLoop.feedbackSensor(encoder instanceof SparkMaxAnalogEncoderSwerve
? FeedbackSensor.kAnalogSensor : FeedbackSensor.kAbsoluteEncoder);

DriverStation.reportWarning(
"IF possible configure the encoder offset in the REV Hardware Client instead of using the" +
" absoluteEncoderOffset in the Swerve Module JSON!",
false);
absoluteEncoder = encoder;
velocity = absoluteEncoder::getVelocity;
position = absoluteEncoder::getAbsolutePosition;
Expand Down
4 changes: 0 additions & 4 deletions src/main/java/swervelib/motors/SparkMaxSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -262,10 +262,6 @@ public SwerveMotor setAbsoluteEncoder(SwerveAbsoluteEncoder encoder)
cfg.closedLoop.feedbackSensor(encoder instanceof SparkMaxAnalogEncoderSwerve
? FeedbackSensor.kAnalogSensor : FeedbackSensor.kAbsoluteEncoder);

DriverStation.reportWarning(
"IF possible configure the encoder offset in the REV Hardware Client instead of using the" +
" absoluteEncoderOffset in the Swerve Module JSON!",
false);
absoluteEncoder = encoder;
velocity = absoluteEncoder::getVelocity;
position = absoluteEncoder::getAbsolutePosition;
Expand Down

0 comments on commit ace71bb

Please sign in to comment.