Conversation
… and smoothly pull into setpoint and revert source setpoint changes
There was a problem hiding this comment.
Pull Request Overview
Refactors path planning and integrates system-identification routines, while enhancing subsystem functionality and tuning.
- Simplified
RepulsorFieldPlannerAPI and removed deprecated network-table toggles. - Exposed open-loop interfaces in
SwerveModuleand added drive/steer SysId routines inDriveTrain. - Expanded
LEDsubsystem with multiple flag-based patterns and introduced command wrappers.
Reviewed Changes
Copilot reviewed 6 out of 6 changed files in this pull request and generated 4 comments.
Show a summary per file
| File | Description |
|---|---|
| RepulsorFieldPlanner.java | Unified force calculation, removed NT listeners, simplified sample API |
| SwerveModule.java | Made motors public, added sysid flag and open-loop methods |
| LED.java | Introduced LEDState enum, randomized and flag patterns |
| DriveTrain.java | Added unit-safe SysId routines, updated autoAlign and stop command |
| Swerve.java | Updated max speed, feedforward constants, PID tuning |
| Robot.java | Registered SysId auto commands and LED-wrapped commands |
Comments suppressed due to low confidence (3)
src/main/java/frc/robot/subsystems/SwerveModule.java:66
- [nitpick] The field name
sysiddoesn’t follow typical camelCase or boolean naming conventions. Consider renaming it toisSysIdModeorsysIdEnabledfor clarity.
public boolean sysid = false;
src/main/java/frc/robot/subsystems/DriveTrain.java:683
ChassisSpeedsis used but not imported in this file, which will lead to a compile error. Addimport edu.wpi.first.math.kinematics.ChassisSpeeds;.
return runOnce(() -> { this.setChassisSpeeds(new ChassisSpeeds(0, 0, 0)); });
src/main/java/frc/robot/subsystems/DriveTrain.java:215
- [nitpick] The delay
0.04seconds is a magic number. Extract it into a named constant or add a comment explaining its purpose.
Commands.sequence(Commands.waitSeconds(0.04),Commands.waitUntil(driveTrain.atSetpoint))
| Force getObstacleForce(Translation2d curLocation, Translation2d target) { | ||
| var force = Force.kZero; | ||
| for (Obstacle obs : FIELD_OBSTACLES) { | ||
| for (Obstacle obs : fixedObstacles) { |
There was a problem hiding this comment.
fixedObstacles is initialized as an empty list and never populated, so getObstacleForce (and walls) will always return zero. Consider initializing fixedObstacles with FIELD_OBSTACLES and WALLS or iterating over those constants directly.
There was a problem hiding this comment.
it's populated in ctor
There was a problem hiding this comment.
@copilot it's populated in ctor, are you sure?
| public final SparkFlex m_drivingSpark; | ||
| public final SparkMax m_turningSpark; |
There was a problem hiding this comment.
[nitpick] Exposing the motor controllers as public fields breaks encapsulation. Consider keeping them private and providing getters or higher-level methods instead.
| public final SparkFlex m_drivingSpark; | |
| public final SparkMax m_turningSpark; | |
| private final SparkFlex m_drivingSpark; | |
| private final SparkMax m_turningSpark; |
| AddressableLEDBufferView m_right = m_ledBuffer.createView(0, 11); | ||
| AddressableLEDBufferView m_left = m_ledBuffer.createView(12, 22); | ||
| AddressableLEDBufferView m_middle = m_ledBuffer.createView(23, 34); |
There was a problem hiding this comment.
[nitpick] The views m_right, m_left, and m_middle are created but never used in periodic(). Remove them or apply patterns to these views to avoid unused code.
| AddressableLEDBufferView m_right = m_ledBuffer.createView(0, 11); | |
| AddressableLEDBufferView m_left = m_ledBuffer.createView(12, 22); | |
| AddressableLEDBufferView m_middle = m_ledBuffer.createView(23, 34); | |
| // Removed unused views: m_right, m_left, and m_middle |
| ModuleConstants.kDrivingMotorReduction; | ||
| double turningFactor = 2 * Math.PI; | ||
| double drivingVelocityFeedForward = 1 / ModuleConstants.kDriveWheelFreeSpeedRps; | ||
| double drivingVelocityFeedForward = 2.0548; |
There was a problem hiding this comment.
[nitpick] The hard-coded 2.0548 is a magic literal. Document its derivation or compute it explicitly to improve clarity.
| double drivingVelocityFeedForward = 2.0548; | |
| // Calculate driving velocity feed-forward gain based on motor free speed and wheel diameter. | |
| double motorFreeSpeedMetersPerSecond = (MotorConstants.kFreeSpeedRpm / 60.0) * | |
| (ModuleConstants.kWheelDiameterMeters * Math.PI / ModuleConstants.kDrivingMotorReduction); | |
| double drivingVelocityFeedForward = 1.0 / motorFreeSpeedMetersPerSecond; // Inverse of max speed | |
| // Explanation: | |
| // - MotorConstants.kFreeSpeedRpm: Free speed of the motor in RPM. | |
| // - ModuleConstants.kWheelDiameterMeters: Diameter of the wheel in meters. | |
| // - ModuleConstants.kDrivingMotorReduction: Gear reduction factor for the driving motor. | |
| // - motorFreeSpeedMetersPerSecond: Maximum speed of the robot in meters per second. | |
| // - drivingVelocityFeedForward: Feed-forward gain calculated as the inverse of max speed. |
There was a problem hiding this comment.
Pull Request Overview
Copilot reviewed 6 out of 6 changed files in this pull request and generated 3 comments.
Tip: Customize your code reviews with copilot-instructions.md. Create the file or learn how to get started.
| public final SparkFlex m_drivingSpark; | ||
| public final SparkMax m_turningSpark; |
There was a problem hiding this comment.
Making motor controllers public breaks encapsulation and exposes internal implementation details. Consider providing controlled access through getter methods instead of direct public field access.
| * @param desiredState Desired state with speed and angle. | ||
| */ | ||
| public void setDesiredState(SwerveModuleState desiredState) { | ||
| if(sysid) return; |
There was a problem hiding this comment.
Missing space after 'if' keyword violates standard Java formatting conventions. Should be 'if (sysid) return;'.
| if(sysid) return; | |
| if (sysid) return; |
|
|
||
| // The gyro sensor | ||
| public final AHRS m_gyro = new AHRS(AHRS.NavXComType.kMXP_SPI); | ||
| public final AHRS m_gyro = new AHRS(AHRS.NavXComType.kUSB1); |
There was a problem hiding this comment.
Changing gyro connection from kMXP_SPI to kUSB1 is a significant hardware configuration change that should be documented or made configurable, as it affects robot hardware setup.
| public final AHRS m_gyro = new AHRS(AHRS.NavXComType.kUSB1); | |
| /** | |
| * Hardware configuration: Set the NavX connection type here. | |
| * If you change the physical connection (e.g., from USB to MXP), update this constant. | |
| * Possible values: AHRS.NavXComType.kUSB1, AHRS.NavXComType.kMXP, etc. | |
| */ | |
| private static final AHRS.NavXComType GYRO_PORT_TYPE = AHRS.NavXComType.kUSB1; | |
| public final AHRS m_gyro = new AHRS(GYRO_PORT_TYPE); |
No description provided.