Skip to content

Commit

Permalink
recreated module class, did not implement torque based ff control
Browse files Browse the repository at this point in the history
  • Loading branch information
dabeycorn committed Feb 8, 2025
1 parent 7794c2a commit 732bad3
Show file tree
Hide file tree
Showing 7 changed files with 80 additions and 269 deletions.
1 change: 1 addition & 0 deletions src/main/java/org/frc6423/frc2025/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ public static enum DeployMode {
}

/** Get selected robot type */
@SuppressWarnings("resource")
public static RobotType getRobot() {
if (Robot.isReal() && m_robotType == RobotType.SIMULATED) {
new Alert("Simulated robot type selected; Defaulting to devbot", AlertType.kError);
Expand Down
5 changes: 0 additions & 5 deletions src/main/java/org/frc6423/frc2025/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@

import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.Threads;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import org.littletonrobotics.junction.LogFileUtil;
import org.littletonrobotics.junction.LoggedRobot;
Expand All @@ -21,8 +20,6 @@

public class Robot extends LoggedRobot {

private final XboxController m_DriverController;

public Robot() {
// AKit init
Logger.recordMetadata("ProjectName", BuildConstants.MAVEN_NAME);
Expand Down Expand Up @@ -55,8 +52,6 @@ public Robot() {

RobotController.setBrownoutVoltage(6.0);

m_DriverController = new XboxController(0);

// Subsystem init

// Default Commands
Expand Down

This file was deleted.

153 changes: 76 additions & 77 deletions src/main/java/org/frc6423/frc2025/subsystems/swerve/module/Module.java
Original file line number Diff line number Diff line change
@@ -1,100 +1,99 @@
// Copyright (c) 2025 FRC 6423 - Ward Melville Iron Patriots
// https://github.com/FIRSTTeam6423
//
// Open Source Software; you can modify and/or share it under the terms of
// MIT license file in the root directory of this project

package org.frc6423.frc2025.subsystems.swerve.module;

import org.frc6423.frc2025.util.swerveUtil.ModuleConfig;
import org.littletonrobotics.junction.Logger;

import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.wpilibj.Alert;
import edu.wpi.first.wpilibj.Alert.AlertType;
import org.littletonrobotics.junction.Logger;

public class Module {
private final int index;
private final ModuleIO io;
private final ModuleIOInputsAutoLogged inputs;
private final ModuleIO m_IO;

private final int m_index;
private final ModuleConfig m_config;

private final ModuleIOInputsAutoLogged m_inputs;

private SimpleMotorFeedforward m_driveff;

public Module(ModuleConfig config) {
m_IO = new ModuleIOTalonFX(config);

m_index = config.kIndex;
this.m_config = config;

m_inputs = new ModuleIOInputsAutoLogged();

m_driveff = new SimpleMotorFeedforward(0.0, 0.0);
}

private SwerveModuleState m_goalState;
/** Update auto logged inputs */
public void updateInputs() {
m_IO.updateInputs(m_inputs);
}

private final SimpleMotorFeedforward m_driveFeedforward;
/** Periodically ran logic */
public void periodic() {
Logger.processInputs("Swerve/Module" + m_index, m_inputs);
}

private final Alert m_pivotConnectionAlert;
private final Alert m_driveConnectionAlert;
/** Run SwerveModuleState setpoint */
public SwerveModuleState runSetpoint(SwerveModuleState setpointState) {
setpointState.optimize(getPivotAngle());
setpointState.speedMetersPerSecond *= setpointState.angle.minus(getPivotAngle()).getCos();

public Module(ModuleIO io, int index) {
this.index = index;
this.io = io;
this.inputs = new ModuleIOInputsAutoLogged();
double speedMPS = setpointState.speedMetersPerSecond;
m_IO.setPivotAngle(setpointState.angle);
m_IO.setDriveVelocity(speedMPS, m_driveff.calculate(speedMPS)); // !
return setpointState;
}

m_driveFeedforward = new SimpleMotorFeedforward(0.088468, 2.1314); // ! Add constants later
/** Run SwerveModuleState setpoint with setpoint wheel torque (torque-based ff) */
public SwerveModuleState runSetpoint(SwerveModuleState setpointState, double driveTorqueNm) {
// TODO Auto-generated method stub
throw new UnsupportedOperationException("Unimplemented method 'runSetpoint'");
}

m_pivotConnectionAlert = new Alert(index + " pivot disconnected", AlertType.kWarning);
m_driveConnectionAlert = new Alert(index + " drive disconnected", AlertType.kWarning);
}
/** Runs SwerveModuleState setpoint but runs drive in open loop mode */
public SwerveModuleState runSetpointOpenloop(SwerveModuleState setpointState, boolean FOCEnabled) {
setpointState.optimize(getPivotAngle());
setpointState.speedMetersPerSecond *= setpointState.angle.minus(getPivotAngle()).getCos();

/** Update Module */
public void periodic() {
io.updateInputs(inputs);
Logger.processInputs("Swerve/Module" + index, inputs);
double speedMPS = setpointState.speedMetersPerSecond;
m_IO.setPivotAngle(setpointState.angle);
m_IO.setDriveVolts(speedMPS, FOCEnabled); // !
return new SwerveModuleState();
}

m_pivotConnectionAlert.set(inputs.pivotEnabled);
m_driveConnectionAlert.set(inputs.driveEnabled);
}
/** Set pivot angle setpoint */
public void setPivotAngle(Rotation2d desiredAngle) {
m_IO.setPivotAngle(desiredAngle);
}

/** Set swerve state goal */
public void setDesiredSate(SwerveModuleState goalState, DriveControlMode controlMode) {
Rotation2d currentAngle = getCurrentState().angle;
/** Set drive torque current setpoint */
public void runDriveCurrent(double currentAmps) {
m_IO.setDriveTorqueCurrent(currentAmps);
}

goalState.optimize(currentAngle);
// Scaless speed based on how far the module angle is from goal angle
goalState.speedMetersPerSecond *= goalState.angle.minus(currentAngle).getCos();
/** Stop all motor input */
public void stop() {
m_IO.stop();
}

/** Enable module coasting */
public void enableCoast(boolean enabled) {
// TODO Auto-generated method stub
throw new UnsupportedOperationException("Unimplemented method 'enableCoast'");
}

io.setPivotAngle(goalState.angle);
/** Get Module index */
public int getModuleIndex() {
return m_index;
}

if (controlMode == DriveControlMode.CLOSEDLOOP) {
io.setDriveVelocity(
goalState.speedMetersPerSecond,
m_driveFeedforward.calculate(goalState.speedMetersPerSecond)); // Closed loop control
} else {
io.setDriveVolts(
m_driveFeedforward.calculate(goalState.speedMetersPerSecond)); // Open Loop control
/** returns current module angle */
public Rotation2d getPivotAngle() {
return m_inputs.pivotABSPose;
}
}

/** Set all Module motor input to 0 */
public void stopModuleInputs() {
io.stop();
}

/** Get current goal state */
public SwerveModuleState getDesiredState() {
return m_goalState;
}

/** Get current swerve module state {@link SwerveModuleState} */
public SwerveModuleState getCurrentState() {
return new SwerveModuleState(inputs.driveVelRadsPerSec, inputs.pivotABSPose);
}

/** Get current swerve module pose {@link SwerveModulePosition} */
public SwerveModulePosition getCurrentPose() {
return new SwerveModulePosition(inputs.drivePoseRads, inputs.pivotPose);
}

/** Get module index */
public int getIndex() {
return index;
}

public static enum DriveControlMode {
OPENLOOP,
CLOSEDLOOP
}
}
Loading

0 comments on commit 732bad3

Please sign in to comment.