Skip to content

Commit

Permalink
prepare for 2024 beta release (#68)
Browse files Browse the repository at this point in the history
* update README for 2024 beta
* remove retired robot configs
* address warnings
  • Loading branch information
gcschmit authored Dec 30, 2023
1 parent b6d4b8f commit 82e46f7
Show file tree
Hide file tree
Showing 13 changed files with 129 additions and 868 deletions.
Binary file removed Log_23-06-23_19-38-49.wpilog
Binary file not shown.
Binary file removed Log_23-06-23_19-45-26.wpilog
Binary file not shown.
11 changes: 7 additions & 4 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ Huskie Robotics, FRC Team 3061's, starter project and library focused on a swerv
----
* git must be installed as the GVersion plugin depends upon it
* [CTRE's Phoenix 6](https://store.ctr-electronics.com/software/) (both free and licensed options are supported)
* [RevLib](https://docs.revrobotics.com/sparkmax/software-resources/spark-max-api-information)
* [AdvantageKit](https://github.com/Mechanical-Advantage/AdvantageKit/blob/main/README.md)
* [PathPlanner](https://github.com/mjansen4857/pathplanner)
* [PhotonLib](https://photonvision.org)
Expand Down Expand Up @@ -40,14 +41,15 @@ To add an additional robot, create a new subclass of ```RobotConfig``` (you can
**Tuning**
----

* If you are using all CTRE hardware, use the Swerve Project Generator in Tuner X. Copy the values from the generated TunerConstants.java file into your RobotConfig subclass, DrivetrainIOCTRE.java, and SwerveConstants.java as appropriate. If you are not using all CTRE hardware, do the following.
* Checking motor and encoder directions:
* The drive motor, angle motor, and angle encoder constants in SwerveModuleConstants should be configured appropriately for the MK4 and MK4i swerve modules. However, it doesn't hurt to verify.
* If you want to verify the following, the ```Subsystem``` example subsystem can be used with ```TESTING``` set to true to directly control the associated motor. Set ```MOTOR_CAN_ID``` in ```SubsystemConstants``` to the appropriate CAN ID and ensure that CAN ID is not specified for any swerve motor in ```DefaultRobotConfig```. Use Shuffleboard to set the motor power.
* When the drive motor is supplied a positive input, it should turn the swerve module wheel such that the robot moves forward; if not, negate.
* When the angle motor is supplied a positive input, it should rotate the swerve module wheel such that the wheel rotates in the CCW direction; if not, negate.
* When the angle motor rotates the swerve module wheel in a CCW direction, the CANcoder should increase its reading; if not, set to negate.
* Setting Steer Offsets (e.g., ```FRONT_LEFT_MODULE_STEER_OFFSET_ROT```) in your ```RobotConfig``` subclass (e.g., DefaultRobotConfig.java):
* For finding the offsets, use a piece of 1x1 metal that is straight against the forks of the front and back modules (on the left and right side) to ensure that the modules are straight
* For finding the offsets, use a piece of 2x1 extrusion that is straight against the forks of the front and back modules (on the left and right side) to ensure that the modules are straight
* Point the bevel gears of all the wheels in the same direction (either facing left or right), and preferably you should have the wheels facing in the direction where a positive input to the drive motor drives forward; if for some reason you set the offsets with the wheels backwards, you can change the appropriate ```DRIVE_MOTOR_INVERTED``` in ```SwerveModuleConstants``` to fix
* Open Phoenix Tuner 6 and, for each CANcoder on a swerve module, copy the negated rotation value of the "Absolute Position No Offset" signal to the ```STEER_OFFSET``` constants. For example, if the CANcoder "Absolute Position No Offset" signal is 0.104004, specify a value of -0.104004 for the corresponding constant.
* Checking geometry:
Expand All @@ -69,14 +71,15 @@ To add an additional robot, create a new subclass of ```RobotConfig``` (you can
16. rotate the cart in a CW direction and verify that the gyro is decreasing
17. use Phoenix Tuner to flash the LEDs on the Falcon 500s and CANcoders to ensure that the CAN IDs are properly assigned to the front-left, front-right, back-left, and back-right positions (all of the above may behave as expected even if the modules aren't assigned to the appropriate corners)
* Angle characterization values (```ANGLE_KS```, ```ANGLE_KV```, ```ANGLE_KA```) in in your ```RobotConfig``` subclass (e.g., DefaultRobotConfig.java):
* set ```TUNING_MODE``` in Constants.java to true (characterization analysis doesn't normally run)
* in Shuffleboard, set the "Auto Routine" chooser to "Swerve Rotate Characterization"
* start the autonomous period
* the ```FeedForwardCharacterization``` command will run and output the KS, KV, and KA values
* copy the KS, KV, and KA values into the corresponding constants in your robot config file
* Angle Motor PID Values (```ANGLE_KP```, ```ANGLE_KI```, ```ANGLE_KD```) in your ```RobotConfig``` subclass (e.g., DefaultRobotConfig.java):
* set ```TUNING_MODE``` in Constants.java to true
* open Shuffleboard, go to the SmartDashboard tab, and see controls for each of the PID values; values can be changed via these controls as you interactively tune the controller
* start with a low P value (10.0)
* start with a P value of 100.0
* double until the module starts oscillating around the set point
* scale back by searching for the value (for example, if it starts oscillating at a P of 100, then try (100 -> 50 -> 75 -> etc.)) until the module overshoots the setpoint but corrects with no oscillation
* graph the ```anglePositionErrorDeg``` in Advantage Scope for each swerve module to assist in tuning
Expand All @@ -85,6 +88,7 @@ To add an additional robot, create a new subclass of ```RobotConfig``` (you can
* copy the values from the Shuffleboard controls into SwerveModuleConstants.java
* set ```TUNING_MODE``` in Constants.java to false
* Drive characterization values (```DRIVE_KS```, ```DRIVE_KV```, ```DRIVE_KA```) in in your ```RobotConfig``` subclass (e.g., DefaultRobotConfig.java):
* set ```TUNING_MODE``` in Constants.java to true (characterization analysis doesn't normally run)
* in Shuffleboard, set the "Auto Routine" chooser to "Swerve Drive Characterization"
* ensure that there is about 40' of carpet in front of the robot before enabling the auto routine; if there is less, increase ```RAMP_RATE_VOLTS_PER_SECOND``` in ```FeedForwardCharacterization```
* start the autonomous period
Expand All @@ -95,6 +99,7 @@ To add an additional robot, create a new subclass of ```RobotConfig``` (you can
* open Shuffleboard, go to the SmartDashboard tab, and see controls for each of the PID values; values can be changed via these controls as you interactively tune the controller
* in Shuffleboard, set the "Auto Routine" chooser to "Drive Velocity Tuning"
* tune ```DRIVE_KP``` until it doesn't overshoot and doesn't oscillate around a target velocity
* start with a P value of 0.2 (DrivetrainIOCTRE) or 0.005 (DrivetrainIOGeneric)
* graph the ```driveVelocityErrorMetersPerSec``` in Advantage Scope for each swerve module to assist in tuning
* copy the values from the Shuffleboard controls into SwerveModuleConstants.java
* set ```TUNING_MODE``` in Constants.java to false
Expand All @@ -120,5 +125,3 @@ To add an additional robot, create a new subclass of ```RobotConfig``` (you can
* general AdvantageKit logging code, AdvantageKit-enabled Gyro classes, swerve module simulation, and drive characterization from Mechanical Advantage's [SwerveDevelopment](https://github.com/Mechanical-Advantage/SwerveDevelopment)
* AdvantageKit-enabled pneumatics classes from Mechanical Advantage's 2022 [robot code](https://github.com/Mechanical-Advantage/RobotCode2022)
* FaultReporter (originally AdvancedSubsystem), SubsystemFault, SelfChecking classes from [Ranger Robotics](https://github.com/3015RangerRobotics/2023Public)
* Talon factories from Citrus Circuits 2022 [robot code](https://github.com/frc1678/C2022)
* FaultReporter (originally AdvancedSubsystem), SubsystemFault, SelfChecking classes from Ranger Robotics 2023 [robot code](https://github.com/3015RangerRobotics/2023Public)
14 changes: 13 additions & 1 deletion src/main/java/frc/lib/team3061/RobotConfig.java
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,8 @@ public double getSwerveAngleKD() {

/*
* Returns the voltage needed to overcome the swerve module's static friction. Defaults to 0.
* This constant will be provided directly to the hardware. Therefore, the units must be that
* as expected by the hardware.
*
* @return the voltage needed to overcome the swerve module's static friction
*/
Expand All @@ -76,6 +78,8 @@ public double getSwerveAngleKS() {

/**
* Returns the voltage needed to hold (or "cruise") at a given constant velocity. Defaults to 0.
* This constant will be provided directly to the hardware. Therefore, the units must be that as
* expected by the hardware.
*
* @return the voltage needed to hold (or "cruise") at a given constant velocity
*/
Expand All @@ -85,6 +89,8 @@ public double getSwerveAngleKV() {

/**
* Returns the voltage needed to induce a given acceleration in the motor shaft. Defaults to 0.
* This constant will be provided directly to the hardware. Therefore, the units must be that as
* expected by the hardware.
*
* @return the voltage needed to induce a given acceleration in the motor shaft
*/
Expand Down Expand Up @@ -124,7 +130,9 @@ public double getSwerveDriveKD() {
}

/**
* Returns the voltage needed to overcome the drivetrain's static friction. Defaults to 0.
* Returns the voltage needed to overcome the drivetrain's static friction. Defaults to 0. This
* constant will be provided directly to the hardware. Therefore, the units must be that as
* expected by the hardware.
*
* @return the voltage needed to overcome the drivetrain's static friction
*/
Expand All @@ -134,6 +142,8 @@ public double getDriveKS() {

/**
* Returns the voltage needed to hold (or "cruise") at a given constant velocity. Defaults to 0.
* This constant will be provided directly to the hardware. Therefore, the units must be that as
* expected by the hardware.
*
* @return the voltage needed to hold (or "cruise") at a given constant velocity
*/
Expand All @@ -143,6 +153,8 @@ public double getDriveKV() {

/**
* Returns the voltage needed to induce a given acceleration in the motor shaft. Defaults to 0.
* This constant will be provided directly to the hardware. Therefore, the units must be that as
* expected by the hardware.
*
* @return the voltage needed to induce a given acceleration in the motor shaft
*/
Expand Down
2 changes: 0 additions & 2 deletions src/main/java/frc/lib/team3061/drivetrain/Drivetrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -368,7 +368,6 @@ public void stop() {
*/
@Override
public void periodic() {
// FIXME: document that TUNING_MODE must be set to true when doing characterization
if (Constants.TUNING_MODE) {
this.prevSpeeds =
new ChassisSpeeds(
Expand Down Expand Up @@ -652,7 +651,6 @@ public boolean isMoveToPoseEnabled() {
}

private Command getSystemCheckCommand() {
// FIXME: add system check commands
return Commands.sequence(Commands.sequence(Commands.waitSeconds(0.25)))
.until(() -> !FaultReporter.getInstance().getFaults(SUBSYSTEM_NAME).isEmpty())
.andThen(Commands.runOnce(() -> drive(0, 0, 0, true, false), this));
Expand Down
24 changes: 2 additions & 22 deletions src/main/java/frc/lib/team3061/drivetrain/DrivetrainIOCTRE.java
Original file line number Diff line number Diff line change
@@ -1,7 +1,5 @@
package frc.lib.team3061.drivetrain;

import static frc.lib.team3061.drivetrain.swerve.SwerveConstants.*;

import com.ctre.phoenix6.BaseStatusSignal;
import com.ctre.phoenix6.StatusCode;
import com.ctre.phoenix6.StatusSignal;
Expand Down Expand Up @@ -83,21 +81,14 @@ public SwerveModuleSignals(TalonFX driveMotor, TalonFX steerMotor) {
RobotConfig.getInstance().getSwerveAngleKP(),
RobotConfig.getInstance().getSwerveAngleKI(),
RobotConfig.getInstance().getSwerveAngleKD(),
RobotConfig.getInstance().getSwerveAngleKV()
* 2
* Math.PI, // convert from V/(radians/s) to V/(rotations/s)
RobotConfig.getInstance().getSwerveAngleKV(),
RobotConfig.getInstance().getSwerveAngleKS());
// FIXME: clean this up
private static final CustomSlotGains driveGains =
new CustomSlotGains(
RobotConfig.getInstance().getSwerveDriveKP(),
RobotConfig.getInstance().getSwerveDriveKI(),
RobotConfig.getInstance().getSwerveDriveKD(),
RobotConfig.getInstance().getDriveKV()
/ Conversions.mpsToFalconRPS(
1.0,
MK4I_L2_WHEEL_CIRCUMFERENCE,
MK4I_L2_DRIVE_GEAR_RATIO), // convert from V/(m/s) to V/(rotations/s)
RobotConfig.getInstance().getDriveKV(),
RobotConfig.getInstance().getDriveKS());

// The closed-loop output type to use for the steer motors
Expand Down Expand Up @@ -539,7 +530,6 @@ public void setGyroOffset(double expectedYaw) {
try {
m_stateLock.writeLock().lock();

// FIXME: check the math here not sure if we should add or subtract
m_fieldRelativeOffset =
getState().Pose.getRotation().plus(Rotation2d.fromDegrees(expectedYaw));
} finally {
Expand All @@ -557,16 +547,6 @@ public void resetPose(Pose2d pose) {
this.seedFieldRelative(pose);
}

@Override
public void setDriveMotorVoltage(double voltage) {
// FIXME: implement later with Idle Swerve Request object?
}

@Override
public void setSteerMotorVoltage(double voltage) {
// FIXME: implement later with Idle Swerve Request object?
}

@Override
public void setBrakeMode(boolean enable) {
for (SwerveModule swerveModule : this.Modules) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -157,8 +157,6 @@ public void updateInputs(DrivetrainIOInputsCollection inputs) {
moduleDeltas[index] =
new SwerveModulePosition(
current.distanceMeters - previous.distanceMeters, current.angle);
// FIXME: I don't think this assignment is needed...
previous.distanceMeters = current.distanceMeters;
}

Twist2d twist = kinematics.toTwist2d(moduleDeltas);
Expand Down Expand Up @@ -238,7 +236,7 @@ public void driveFieldRelative(
@Override
public void driveFieldRelativeFacingAngle(
double xVelocity, double yVelocity, Rotation2d targetDirection, boolean isOpenLoop) {
// FIXME: add support for holding a rotation angle
// currently this is not supported and this code is the same as driveFieldRelative
this.targetChassisSpeeds =
ChassisSpeeds.fromFieldRelativeSpeeds(
xVelocity, yVelocity, 0.0, Rotation2d.fromDegrees(this.robotRotationDeg));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,6 @@ public enum SwerveType {
public static final boolean MK4_L2_ANGLE_MOTOR_INVERTED = false;
public static final boolean MK4_L2_CAN_CODER_INVERTED = false;

// FIXME: tune this; perhaps set to 0?
public static final double OPEN_LOOP_RAMP = 0.25;
public static final double CLOSED_LOOP_RAMP = 0.0;

Expand Down
2 changes: 0 additions & 2 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,6 @@ public final class Constants {
public enum RobotType {
ROBOT_2023_NOVA_CTRE,
ROBOT_2023_NOVA,
ROBOT_2023_MK4I,
ROBOT_DEFAULT,
ROBOT_SIMBOT,
ROBOT_SIMBOT_CTRE
Expand All @@ -64,7 +63,6 @@ public static Mode getMode() {
case ROBOT_DEFAULT:
case ROBOT_2023_NOVA_CTRE:
case ROBOT_2023_NOVA:
case ROBOT_2023_MK4I:
return RobotBase.isReal() ? Mode.REAL : Mode.REPLAY;

case ROBOT_SIMBOT:
Expand Down
Loading

0 comments on commit 82e46f7

Please sign in to comment.