Skip to content

Commit

Permalink
Addressed extraneous memory utilization.
Browse files Browse the repository at this point in the history
Signed-off-by: thenetworkgrinch <thenetworkgrinch@users.noreply.github.com>
  • Loading branch information
TheGamer1002 authored and thenetworkgrinch committed Feb 13, 2024
1 parent 990f442 commit 94e2241
Show file tree
Hide file tree
Showing 6 changed files with 123 additions and 103 deletions.
41 changes: 33 additions & 8 deletions src/main/java/swervelib/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,26 @@ public class SwerveModule
* An {@link Alert} for if there is no Absolute Encoder on the module.
*/
private final Alert noEncoderWarning;
/**
* NT3 Raw Absolute Angle publisher for the absolute encoder.
*/
private final String rawAbsoluteAngleName;
/**
* NT3 Adjusted Absolute angle publisher for the absolute encoder.
*/
private final String adjAbsoluteAngleName;
/**
* NT3 Absolute encoder read issue.
*/
private final String absoluteEncoderIssueName;
/**
* NT3 raw angle motor.
*/
private final String rawAngleName;
/**
* NT3 Raw drive motor.
*/
private final String rawDriveName;
/**
* Module number for kinematics, usually 0 to 3. front left -> front right -> back left -> back right.
*/
Expand Down Expand Up @@ -176,6 +196,12 @@ public SwerveModule(int moduleNumber, SwerveModuleConfiguration moduleConfigurat
"Pushing the Absolute Encoder offset to the encoder failed on module #" +
moduleNumber,
Alert.AlertType.WARNING);

rawAbsoluteAngleName = "Module[" + configuration.name + "] Raw Absolute Encoder";
adjAbsoluteAngleName = "Module[" + configuration.name + "] Adjusted Absolute Encoder";
absoluteEncoderIssueName = "Module[" + configuration.name + "] Absolute Encoder Read Issue";
rawAngleName = "Module[" + configuration.name + "] Raw Angle Encoder";
rawDriveName = "Module[" + configuration.name + "] Raw Drive Encoder";
}

/**
Expand Down Expand Up @@ -293,7 +319,8 @@ private double getCosineCompensatedVelocity(SwerveModuleState desiredState)
/* If error is close to 0 rotations, we're already there, so apply full power */
/* If the error is close to 0.25 rotations, then we're 90 degrees, so movement doesn't help us at all */
cosineScalar = Rotation2d.fromDegrees(desiredState.angle.getDegrees())
.minus(Rotation2d.fromDegrees(getAbsolutePosition())).getCos(); // TODO: Investigate angle modulus by 180.
.minus(Rotation2d.fromDegrees(getAbsolutePosition()))
.getCos(); // TODO: Investigate angle modulus by 180.
/* Make sure we don't invert our drive, even though we shouldn't ever target over 90 degrees anyway */
if (cosineScalar < 0.0)
{
Expand Down Expand Up @@ -526,13 +553,11 @@ public void updateTelemetry()
{
if (absoluteEncoder != null)
{
SmartDashboard.putNumber("Module[" + configuration.name + "] Raw Absolute Encoder",
absoluteEncoder.getAbsolutePosition());
SmartDashboard.putNumber(rawAbsoluteAngleName, absoluteEncoder.getAbsolutePosition());
}
SmartDashboard.putNumber("Module[" + configuration.name + "] Raw Angle Encoder", angleMotor.getPosition());
SmartDashboard.putNumber("Module[" + configuration.name + "] Raw Drive Encoder", driveMotor.getPosition());
SmartDashboard.putNumber("Module[" + configuration.name + "] Adjusted Absolute Encoder", getAbsolutePosition());
SmartDashboard.putNumber("Module[" + configuration.name + "] Absolute Encoder Read Issue",
getAbsoluteEncoderReadIssue() ? 1 : 0);
SmartDashboard.putNumber(rawAngleName, angleMotor.getPosition());
SmartDashboard.putNumber(rawDriveName, driveMotor.getPosition());
SmartDashboard.putNumber(adjAbsoluteAngleName, getAbsolutePosition());
SmartDashboard.putNumber(absoluteEncoderIssueName, getAbsoluteEncoderReadIssue() ? 1 : 0);
}
}
8 changes: 3 additions & 5 deletions src/main/java/swervelib/imu/Pigeon2Swerve.java
Original file line number Diff line number Diff line change
@@ -1,11 +1,9 @@
package swervelib.imu;

import com.ctre.phoenix6.StatusCode;
import com.ctre.phoenix6.StatusSignal;
import com.ctre.phoenix6.configs.Pigeon2Configuration;
import com.ctre.phoenix6.configs.Pigeon2Configurator;
import com.ctre.phoenix6.hardware.Pigeon2;
import edu.wpi.first.math.geometry.Quaternion;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
Expand All @@ -20,19 +18,19 @@ public class Pigeon2Swerve extends SwerveIMU
/**
* Wait time for status frames to show up.
*/
public static double STATUS_TIMEOUT_SECONDS = 0.04;
public static double STATUS_TIMEOUT_SECONDS = 0.04;
/**
* Pigeon2 IMU device.
*/
Pigeon2 imu;
/**
* Offset for the Pigeon 2.
*/
private Rotation3d offset = new Rotation3d();
private Rotation3d offset = new Rotation3d();
/**
* Inversion for the gyro
*/
private boolean invertedIMU = false;
private boolean invertedIMU = false;

/**
* Generate the SwerveIMU for pigeon.
Expand Down
12 changes: 6 additions & 6 deletions src/main/java/swervelib/motors/TalonFXSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,10 @@
public class TalonFXSwerve extends SwerveMotor
{

/**
* Wait time for status frames to show up.
*/
public static double STATUS_TIMEOUT_SECONDS = 0.02;
/**
* Factory default already occurred.
*/
Expand All @@ -33,22 +37,18 @@ public class TalonFXSwerve extends SwerveMotor
* Velocity voltage setter for controlling drive motor.
*/
private final VelocityVoltage m_velocityVoltageSetter = new VelocityVoltage(0);
/**
* Wait time for status frames to show up.
*/
public static double STATUS_TIMEOUT_SECONDS = 0.02;
/**
* TalonFX motor controller.
*/
TalonFX motor;
/**
* Conversion factor for the motor.
*/
private double conversionFactor;
private double conversionFactor;
/**
* Current TalonFX configuration.
*/
private TalonFXConfiguration configuration = new TalonFXConfiguration();
private TalonFXConfiguration configuration = new TalonFXConfiguration();


/**
Expand Down
30 changes: 7 additions & 23 deletions src/main/java/swervelib/parser/json/DeviceJson.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,9 @@
package swervelib.parser.json;

import static swervelib.telemetry.SwerveDriveTelemetry.canIdWarning;
import static swervelib.telemetry.SwerveDriveTelemetry.i2cLockupWarning;
import static swervelib.telemetry.SwerveDriveTelemetry.serialCommsIssueWarning;

import com.revrobotics.SparkRelativeEncoder.Type;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.I2C;
Expand All @@ -26,45 +30,25 @@
import swervelib.motors.SwerveMotor;
import swervelib.motors.TalonFXSwerve;
import swervelib.motors.TalonSRXSwerve;
import swervelib.telemetry.Alert;
import swervelib.telemetry.Alert.AlertType;

/**
* Device JSON parsed class. Used to access the JSON data.
*/
public class DeviceJson
{

/**
* An {@link Alert} for if the CAN ID is greater than 40.
*/
private final Alert canIdWarning = new Alert("JSON",
"CAN IDs greater than 40 can cause undefined behaviour, please use a CAN ID below 40!",
Alert.AlertType.WARNING);
/**
* An {@link Alert} for if there is an I2C lockup issue on the roboRIO.
*/
private final Alert i2cLockupWarning = new Alert("IMU",
"I2C lockup issue detected on roboRIO. Check console for more information.",
Alert.AlertType.WARNING);
/**
* NavX serial comm issue.
*/
private final Alert serialCommsIssueWarning = new Alert("IMU",
"Serial comms is interrupted with USB and other serial traffic and causes intermittent connected/disconnection issues. Please consider another protocol or be mindful of this.",
AlertType.WARNING);
/**
* The device type, e.g. pigeon/pigeon2/sparkmax/talonfx/navx
*/
public String type;
public String type;
/**
* The CAN ID or pin ID of the device.
*/
public int id;
public int id;
/**
* The CAN bus name which the device resides on if using CAN.
*/
public String canbus = "";
public String canbus = "";

/**
* Create a {@link SwerveAbsoluteEncoder} from the current configuration.
Expand Down
86 changes: 40 additions & 46 deletions src/main/java/swervelib/telemetry/Alert.java
Original file line number Diff line number Diff line change
Expand Up @@ -34,11 +34,9 @@
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import java.util.ArrayList;
import java.util.Comparator;
import java.util.HashMap;
import java.util.List;
import java.util.Map;
import java.util.function.Predicate;

/**
* Class for managing persistent alerts to be sent over NetworkTables.
Expand Down Expand Up @@ -111,24 +109,7 @@ public void set(boolean active)
if (active && !this.active)
{
activeStartTime = Timer.getFPGATimestamp();
switch (type)
{
case ERROR:
DriverStation.reportError(text, false);
break;
case ERROR_TRACE:
DriverStation.reportError(text, true);
break;
case WARNING:
DriverStation.reportWarning(text, false);
break;
case WARNING_TRACE:
DriverStation.reportWarning(text, true);
break;
case INFO:
System.out.println(text);
break;
}
printAlert(text);
}
this.active = active;
}
Expand All @@ -142,28 +123,39 @@ public void setText(String text)
{
if (active && !text.equals(this.text))
{
switch (type)
{
case ERROR:
DriverStation.reportError(text, false);
break;
case ERROR_TRACE:
DriverStation.reportError(text, true);
break;
case WARNING:
DriverStation.reportWarning(text, false);
break;
case WARNING_TRACE:
DriverStation.reportWarning(text, true);
break;
case INFO:
System.out.println(text);
break;
}
printAlert(text);
}
this.text = text;
}


/**
* Print the alert message.
*
* @param text Text to print.
*/
private void printAlert(String text)
{
switch (type)
{
case ERROR:
DriverStation.reportError(text, false);
break;
case ERROR_TRACE:
DriverStation.reportError(text, true);
break;
case WARNING:
DriverStation.reportWarning(text, false);
break;
case WARNING_TRACE:
DriverStation.reportWarning(text, true);
break;
case INFO:
System.out.println(text);
break;
}
}

/**
* Represents an alert's level of urgency.
*/
Expand Down Expand Up @@ -219,14 +211,16 @@ private static class SendableAlerts implements Sendable
*/
public String[] getStrings(AlertType type)
{
Predicate<Alert> activeFilter = (Alert x) -> x.type == type && x.active;
Comparator<Alert> timeSorter =
(Alert a1, Alert a2) -> (int) (a2.activeStartTime - a1.activeStartTime);
return alerts.stream()
.filter(activeFilter)
.sorted(timeSorter)
.map((Alert a) -> a.text)
.toArray(String[]::new);
List<String> alertStrings = new ArrayList<>();
for (Alert alert : alerts)
{
if (alert.type == type && alert.active)
{
alertStrings.add(alert.text);
}
}
// alertStrings.sort((a1, a2) -> (int) (a2.activeStartTime - a1.activeStartTime));
return alertStrings.toArray(new String[alertStrings.size()]);
}

@Override
Expand Down
Loading

0 comments on commit 94e2241

Please sign in to comment.