Skip to content

Commit

Permalink
Merge SwerveDrive into Vision/Odometry (#8)
Browse files Browse the repository at this point in the history
* use CANcoders

Co-authored-by: simon <[email protected]>
Co-authored-by: Tmanxyz <[email protected]>
Co-authored-by: dchen60 <[email protected]>
Co-authored-by: alex <[email protected]>
Co-authored-by: urnotkool <[email protected]>
Co-authored-by: rzheng287 <[email protected]>

* remove used imports in swerve

* Finish periodic after getting odometry logic

* add SimModules

* Refactor identifyPositionVelocitySystem into PositionVelocitySystem.java

---------

Co-authored-by: Keobkeig <[email protected]>
Co-authored-by: simon <[email protected]>
Co-authored-by: Tmanxyz <[email protected]>
Co-authored-by: dchen60 <[email protected]>
Co-authored-by: alex <[email protected]>
Co-authored-by: urnotkool <[email protected]>
Co-authored-by: rzheng287 <[email protected]>
Co-authored-by: Richie_Xue <[email protected]>
  • Loading branch information
9 people authored Jan 24, 2024
1 parent 5aca825 commit 810885a
Show file tree
Hide file tree
Showing 7 changed files with 304 additions and 48 deletions.
46 changes: 37 additions & 9 deletions src/main/java/com/stuypulse/robot/constants/Settings.java
Original file line number Diff line number Diff line change
Expand Up @@ -36,37 +36,35 @@ public interface Drive {
double WHEEL_CIRCUMFERENCE = WHEEL_DIAMETER * Math.PI;
double GEAR_RATIO = 1.0 / 4.71; //TODO: Find Gear Ratio

//TODO: CHECK THESE
double POSITION_CONVERSION = WHEEL_CIRCUMFERENCE * GEAR_RATIO;
double VELOCITY_CONVERSION = POSITION_CONVERSION / 60.0;
}

public interface Turn {
//TODO: CHECK THESE
double POSITION_CONVERSION = 1;
double VELOCITY_CONVERSION = POSITION_CONVERSION / 60.0;
}
}

public interface Controller {
//TODO: CHECK THESE
public interface Turn {
SmartNumber kP = new SmartNumber("Swerve/Turn/kP", 1.0);
SmartNumber kI = new SmartNumber("Swerve/Turn/kI", 0.0);
SmartNumber kD = new SmartNumber("Swerve/Turn/kD", 0.0);

SmartNumber kS = new SmartNumber("Swerve/Turn/kS", 0.25);
SmartNumber kV = new SmartNumber("Swerve/Turn/kV", 0.00);
SmartNumber kS = new SmartNumber("Swerve/Turn/kS", 0.01);
SmartNumber kV = new SmartNumber("Swerve/Turn/kV", 0.25);
SmartNumber kA = new SmartNumber("Swerve/Turn/kA", 0.01);
}

public interface Drive {
SmartNumber kP = new SmartNumber("Swerve/Drive/kP", 0.10);
SmartNumber kP = new SmartNumber("Swerve/Drive/kP", 1.0);
SmartNumber kI = new SmartNumber("Swerve/Drive/kI", 0.00);
SmartNumber kD = new SmartNumber("Swerve/Drive/kD", 0.00);

SmartNumber kS = new SmartNumber("Swerve/Drive/kS", 0.25);
SmartNumber kV = new SmartNumber("Swerve/Drive/kV", 0.00);
SmartNumber kA = new SmartNumber("Swerve/Drive/kA", 0.00);
SmartNumber kS = new SmartNumber("Swerve/Drive/kS", 0.01);
SmartNumber kV = new SmartNumber("Swerve/Drive/kV", 0.25);
SmartNumber kA = new SmartNumber("Swerve/Drive/kA", 0.01);
}
}

Expand Down Expand Up @@ -121,4 +119,34 @@ public interface Rotation {
SmartNumber D = new SmartNumber("Note Detection/Rotation/kD", 0.1);
}
}

public interface Driver {
public interface Drive {
SmartNumber DEADBAND = new SmartNumber("Driver Settings/Drive/Deadband", 0.03);

SmartNumber RC = new SmartNumber("Driver Settings/Drive/RC", 0.01);
SmartNumber POWER = new SmartNumber("Driver Settings/Drive/Power", 2);

SmartNumber MAX_TELEOP_SPEED = new SmartNumber("Driver Settings/Drive/Max Speed", Swerve.MAX_MODULE_SPEED.get());
SmartNumber MAX_TELEOP_ACCEL = new SmartNumber("Driver Settings/Drive/Max Accleration", 15);
}

public interface Turn {
SmartNumber DEADBAND = new SmartNumber("Driver Settings/Turn/Deadband", 0.05);

SmartNumber RC = new SmartNumber("Driver Settings/Turn/RC", 0.1);
SmartNumber POWER = new SmartNumber("Driver Settings/Turn/Power", 2);

SmartNumber MAX_TELEOP_TURNING = new SmartNumber("Driver Settings/Turn/Max Turning", 6.0);

public interface GyroFeedback {
SmartBoolean GYRO_FEEDBACK_ENABLED = new SmartBoolean("Driver Settings/Gyro Feedback/Enabled", true);

SmartNumber P = new SmartNumber("Driver Settings/Gyro Feedback/kP", 0.5);
SmartNumber I = new SmartNumber("Driver Settings/Gyro Feedback/kI", 0.0);
SmartNumber D = new SmartNumber("Driver Settings/Gyro Feedback/kD", 0.1);
}
}

}
}
Original file line number Diff line number Diff line change
Expand Up @@ -5,13 +5,16 @@
import com.stuypulse.robot.constants.Settings.Swerve.BackRight;
import com.stuypulse.robot.constants.Settings.Swerve.FrontLeft;
import com.stuypulse.robot.constants.Settings.Swerve.FrontRight;
import com.stuypulse.robot.subsystems.swerve.modules.SimModule;
import com.stuypulse.robot.subsystems.swerve.modules.SwerveModule;

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.wpilibj.RobotBase;
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

Expand All @@ -20,12 +23,22 @@ public abstract class AbstractSwerveDrive extends SubsystemBase {
private static final AbstractSwerveDrive instance;

static {
instance = new SwerveDrive(
new SwerveModule(FrontRight.ID, FrontRight.MODULE_OFFSET, Ports.Swerve.FrontRight.TURN, FrontRight.ABSOLUTE_OFFSET, Ports.Swerve.FrontRight.DRIVE),
new SwerveModule(FrontLeft.ID, FrontLeft.MODULE_OFFSET, Ports.Swerve.FrontLeft.TURN, FrontLeft.ABSOLUTE_OFFSET, Ports.Swerve.FrontLeft.DRIVE),
new SwerveModule(BackLeft.ID, BackLeft.MODULE_OFFSET, Ports.Swerve.BackLeft.TURN, BackLeft.ABSOLUTE_OFFSET, Ports.Swerve.BackLeft.DRIVE),
new SwerveModule(BackRight.ID, BackRight.MODULE_OFFSET, Ports.Swerve.BackRight.TURN, BackRight.ABSOLUTE_OFFSET, Ports.Swerve.BackRight.DRIVE)
);
if (RobotBase.isSimulation()) {
instance = new SwerveDrive(
new SimModule(FrontRight.ID, FrontRight.MODULE_OFFSET),
new SimModule(FrontLeft.ID, FrontLeft.MODULE_OFFSET),
new SimModule(BackLeft.ID, BackLeft.MODULE_OFFSET),
new SimModule(BackRight.ID, BackRight.MODULE_OFFSET)
);
}
else {
instance = new SwerveDrive(
new SwerveModule(FrontRight.ID, FrontRight.MODULE_OFFSET, Ports.Swerve.FrontRight.TURN, FrontRight.ABSOLUTE_OFFSET, Ports.Swerve.FrontRight.DRIVE),
new SwerveModule(FrontLeft.ID, FrontLeft.MODULE_OFFSET, Ports.Swerve.FrontLeft.TURN, FrontLeft.ABSOLUTE_OFFSET, Ports.Swerve.FrontLeft.DRIVE),
new SwerveModule(BackLeft.ID, BackLeft.MODULE_OFFSET, Ports.Swerve.BackLeft.TURN, BackLeft.ABSOLUTE_OFFSET, Ports.Swerve.BackLeft.DRIVE),
new SwerveModule(BackRight.ID, BackRight.MODULE_OFFSET, Ports.Swerve.BackRight.TURN, BackRight.ABSOLUTE_OFFSET, Ports.Swerve.BackRight.DRIVE)
);
}
}

public static AbstractSwerveDrive getInstance() {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,10 @@
package com.stuypulse.robot.subsystems.swerve;

import com.ctre.phoenix6.mechanisms.swerve.SwerveDrivetrain.SwerveDriveState;
import com.ctre.phoenix6.sim.ChassisReference;
import com.kauailabs.navx.frc.AHRS;
import com.stuypulse.robot.constants.Settings;
import com.stuypulse.robot.constants.Settings.Swerve;
import com.stuypulse.robot.subsystems.odometry.Odometry;
import com.stuypulse.robot.subsystems.swerve.modules.AbstractSwerveModule;
import com.stuypulse.stuylib.math.Vector2D;

import edu.wpi.first.math.geometry.Pose2d;
Expand Down Expand Up @@ -63,6 +64,11 @@ public class SwerveDrive extends AbstractSwerveDrive {
private AHRS gyro;
private FieldObject2d[] modules2D;


/**
* Creates a new Swerve Drive using the provided modules
* @param modules the modules to use
*/
public SwerveDrive(AbstractSwerveModule... modules){
this.modules = modules;
this.kinematics = new SwerveDriveKinematics(getModuleOffsets());
Expand All @@ -76,7 +82,9 @@ public void initFieldObject(Field2d field) {
modules2D[i] = field.getObject(modules[i].getId() + "-2d");
}
}



/*Getters */
@Override
public SwerveDriveKinematics getKinematics() {
return kinematics;
Expand Down Expand Up @@ -117,7 +125,7 @@ public ChassisSpeeds getChassisSpeeds() {
/*Setters */

private static SwerveModuleState filterModuleState(SwerveModuleState state) {
if (Math.abs(state.speedMetersPerSecond) > Settings.Swerve.MODULE_VELOCITY_DEADBAND.get())
if (Math.abs(state.speedMetersPerSecond) > Swerve.MODULE_VELOCITY_DEADBAND.get())
return state;

return new SwerveModuleState(0, state.angle);
Expand All @@ -129,7 +137,7 @@ public void setModuleStates(SwerveModuleState[] states) {
throw new IllegalArgumentException("Provided incorrect number of states for swerve drive modules");
}

SwerveDriveKinematics.desaturateWheelSpeeds(states, Settings.Swerve.MAX_MODULE_SPEED.get());
SwerveDriveKinematics.desaturateWheelSpeeds(states, Swerve.MAX_MODULE_SPEED.get());

for (int i = 0; i < modules.length; i++){
modules[i].setState(filterModuleState(states[i]));
Expand All @@ -141,12 +149,13 @@ public void setChassisSpeed(ChassisSpeeds robotSpeeds) {
setModuleStates(kinematics.toSwerveModuleStates(robotSpeeds));
}

/*Drive Functions*/
@Override
public void drive(Vector2D velocity, double rotation) {
ChassisSpeeds speeds = ChassisSpeeds.fromFieldRelativeSpeeds(
velocity.x, -velocity.y,
rotation,
getGyroAngle()
Odometry.getInstance().getPose().getRotation()
);

Pose2d pose = new Pose2d(
Expand Down Expand Up @@ -189,15 +198,31 @@ public double getForwardAccelerationGs() {

@Override
public void periodic() {
/*XXX: WAITING FOR ODOMETRY TO WRITE PERIODIC */
Odometry odometry = Odometry.getInstance();
Pose2d pose = odometry.getPose();
Rotation2d angle = pose.getRotation();

SmartDashboard.putNumber("Swerve/Gyro Angle (deg)", getGyroAngle().getDegrees());
SmartDashboard.putNumber("Swerve/Gyro Pitch", getGyroPitch().getDegrees());
SmartDashboard.putNumber("Swerve/Gyro Roll", getGyroRoll().getDegrees());
for (int i = 0; i < modules.length; i++) {
modules2D[i].setPose(new Pose2d(
pose.getTranslation().plus(modules[i].getModuleOffset().rotateBy(angle)),
modules[i].getAngle().plus(angle)
));
}

SmartDashboard.putNumber("Swerve/Gyro/Angle (deg)", getGyroAngle().getDegrees());
SmartDashboard.putNumber("Swerve/Gyro/Pitch (deg)", getGyroPitch().getDegrees());
SmartDashboard.putNumber("Swerve/Gyro/Roll (deg)", getGyroRoll().getDegrees());

SmartDashboard.putNumber("Swerve/Forward Acceleration (Gs)", getForwardAccelerationGs());
SmartDashboard.putNumber("Swerve/Forward Acceleration (Gs)", getForwardAccelerationGs());
SmartDashboard.putNumber("Swerve/X Acceleration (Gs)", gyro.getWorldLinearAccelX());
SmartDashboard.putNumber("Swerve/Y Acceleration (Gs)", gyro.getWorldLinearAccelY());
SmartDashboard.putNumber("Swerve/Z Acceleration (Gs)", gyro.getWorldLinearAccelZ());
}

@Override
public void simulationPeriodic() {
//show gyro angle in simulation
ChassisSpeeds speeds = kinematics.toChassisSpeeds(getModuleStates());
gyro.setAngleAdjustment(speeds.omegaRadiansPerSecond * Settings.DT);
}
}
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package com.stuypulse.robot.subsystems.swerve;
package com.stuypulse.robot.subsystems.swerve.modules;

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
Expand All @@ -14,7 +14,6 @@ public abstract class AbstractSwerveModule extends SubsystemBase {
public abstract Translation2d getModuleOffset();
public abstract SwerveModulePosition getModulePosition();
public abstract void setState(SwerveModuleState state);
public abstract void periodic();
}


Original file line number Diff line number Diff line change
@@ -0,0 +1,128 @@
package com.stuypulse.robot.subsystems.swerve.modules;import com.stuypulse.robot.constants.Settings;
import com.stuypulse.robot.constants.Settings.Swerve;
import com.stuypulse.robot.constants.Settings.Swerve.Controller.Drive;
import com.stuypulse.robot.constants.Settings.Swerve.Controller.Turn;
import com.stuypulse.robot.util.PositionVelocitySystem;
import com.stuypulse.stuylib.control.Controller;
import com.stuypulse.stuylib.control.angle.AngleController;
import com.stuypulse.stuylib.control.angle.feedback.AnglePIDController;
import com.stuypulse.stuylib.control.feedback.PIDController;
import com.stuypulse.stuylib.control.feedforward.MotorFeedforward;
import com.stuypulse.stuylib.math.Angle;
import com.stuypulse.stuylib.streams.angles.filters.ARateLimit;

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.numbers.N2;

import edu.wpi.first.math.system.plant.LinearSystemId;
import edu.wpi.first.wpilibj.simulation.BatterySim;
import edu.wpi.first.wpilibj.simulation.LinearSystemSim;
import edu.wpi.first.wpilibj.simulation.RoboRioSim;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

public class SimModule extends AbstractSwerveModule {
private String id;

private Translation2d offset;

private SwerveModuleState state;

private Controller driveController;
private AngleController angleController;

private LinearSystemSim<N2, N1, N2> driveSim;
private LinearSystemSim<N2, N1, N1> turnSim;

public SimModule(String id, Translation2d offset) {
this.id = id;
this.offset = offset;

this.state = new SwerveModuleState();

this.driveController = new PIDController(Drive.kP, Drive.kI, Drive.kD)
.add(new MotorFeedforward(Drive.kS, Drive.kV, Drive.kA).velocity());

this.angleController = new AnglePIDController(Turn.kP, Turn.kI, Turn.kD)
.setSetpointFilter(new ARateLimit(Swerve.MAX_TURNING));

this.driveSim = new PositionVelocitySystem(Drive.kV, Drive.kA).getSim();
this.turnSim = new LinearSystemSim<N2,N1,N1>(LinearSystemId.identifyPositionSystem(Turn.kV.get(), Turn.kA.get()));
}

@Override
public double getVelocity() {
return driveSim.getOutput(1);
}

public double getDistance() {
return driveSim.getOutput(0);
}

@Override
public Rotation2d getAngle() {
return Rotation2d.fromRadians(turnSim.getOutput(0));
}

@Override
public String getId() {
return this.id;
}

@Override
public SwerveModuleState getState() {
return state;
}

@Override
public Translation2d getModuleOffset() {
return offset;
}

@Override
public SwerveModulePosition getModulePosition() {
return new SwerveModulePosition(getDistance(), getAngle());
}

@Override
public void setState(SwerveModuleState state) {
this.state = state;
}

@Override
public void periodic() {
driveController.update(
state.speedMetersPerSecond,
getVelocity()
);

angleController.update(
Angle.fromRotation2d(state.angle),
Angle.fromRotation2d(getAngle())
);

SmartDashboard.putNumber("Swerve/Modules/" + id + "/Drive Voltage", driveController.getOutput());
SmartDashboard.putNumber("Swerve/Modules/" + id + "/Turn Voltage", angleController.getOutput());
SmartDashboard.putNumber("Swerve/Modules/" + id + "/Target Angle", state.angle.getDegrees());
SmartDashboard.putNumber("Swerve/Modules/" + id + "/Angle", getAngle().getDegrees());
SmartDashboard.putNumber("Swerve/Modules/" + id + "/Target Speed", state.speedMetersPerSecond);
SmartDashboard.putNumber("Swerve/Modules/" + id + "/Speed", getVelocity());
}

@Override
public void simulationPeriodic() {
driveSim.setInput(driveController.getOutput());
driveSim.update(Settings.DT);

turnSim.setInput(angleController.getOutput());
turnSim.update(Settings.DT);

RoboRioSim.setVInVoltage(BatterySim.calculateDefaultBatteryLoadedVoltage(
turnSim.getCurrentDrawAmps() + driveSim.getCurrentDrawAmps()
));
}

}
Loading

0 comments on commit 810885a

Please sign in to comment.