Skip to content

Commit

Permalink
Swerve changes necessary to drive
Browse files Browse the repository at this point in the history
Signed-off-by: Naowal Rahman <[email protected]>
  • Loading branch information
naowalrahman committed Sep 29, 2023
1 parent e14f558 commit 0cf4858
Show file tree
Hide file tree
Showing 2 changed files with 50 additions and 13 deletions.
5 changes: 3 additions & 2 deletions src/main/java/com/stuypulse/robot/constants/Settings.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@

package com.stuypulse.robot.constants;

import com.stuypulse.stuylib.network.SmartBoolean;
import com.stuypulse.stuylib.network.SmartNumber;

/*-
Expand All @@ -17,6 +16,8 @@
public interface Settings {
double DT = 0.02;

public interface Swerve {
public interface Swerve {
SmartNumber MODULE_SPEED_DEADBAND = new SmartNumber("Module speed deadband", 0.02);
SmartNumber MAX_MODULE_SPEED = new SmartNumber("Maximum module speed", 5);
}
}
58 changes: 47 additions & 11 deletions src/main/java/com/stuypulse/robot/subsystems/Swerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

import com.kauailabs.navx.frc.AHRS;
import com.stuypulse.robot.constants.Settings;
import com.stuypulse.robot.constants.Settings.Swerve;
import com.stuypulse.stuylib.math.Vector2D;

import edu.wpi.first.math.geometry.Pose2d;
Expand Down Expand Up @@ -46,15 +47,14 @@
* chassisspeeds.fromfieldrelative(speeds towards opponent, speed left, angles we want to turn per sec, current angle)
*/


public class Swerve {
public class SwerveDrive {
//creating singleton
public final static Swerve instance;
public final static SwerveDrive instance;
static {
instance = new Swerve();
instance = new SwerveDrive();
}

public static Swerve getInstance() {
public static SwerveDrive getInstance() {
return instance;
}

Expand All @@ -63,13 +63,16 @@ public static Swerve getInstance() {
private final SwerveDriveKinematics kinematics;
private final AHRS gyro;

public Swerve(SwerveModule... modules) {
public SwerveDrive(SwerveModule... modules) {
this.modules = modules;
kinematics = new SwerveDriveKinematics(getModuleOffsets());
gyro = new AHRS(SPI.Port.kMXP);
moduleObjects = new FieldObject2d[modules.length];
}

/**
* @return Returns translation of each module relative to the center of the robot.
*/
public Translation2d[] getModuleOffsets() {
var offsets = new Translation2d[modules.length];
for (int i = 0; i < modules.length; i++) {
Expand All @@ -78,6 +81,9 @@ public Translation2d[] getModuleOffsets() {
return offsets;
}

/**
* @return Array with current state of each swerve module.
*/
public SwerveModuleState[] getModuleStates() {
SwerveModuleState[] states = new SwerveModuleState[modules.length];
for(int i = 0; i < modules.length; i++) {
Expand All @@ -87,12 +93,33 @@ public SwerveModuleState[] getModuleStates() {
}

public ChassisSpeeds getChassisSpeeds() {
return kinematics.toChassisSpeeds(getModuleStates())
return kinematics.toChassisSpeeds(getModuleStates());
}

public void setModuleStates(SwerveModuleState[] states) {
/**
* Applies deadband to module state.
* @param state
* @return The original state if the speed is greater than the deadband, otherwise a state with zero speed
*/
public SwerveModuleState filterModuleState(SwerveModuleState state) {
if(Math.abs(state.speedMetersPerSecond) > Swerve.MODULE_SPEED_DEADBAND.get()) {
return state;
}

return new SwerveModuleState(0, state.angle);
}

public void setModuleStates(SwerveModuleState... states) {
if(states.length != modules.length) {
throw new IllegalArgumentException(
String.format("state count mismath error: %d states does not equal %d modules", states.length, modules.length)
);
}

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

for(int i = 0; i < modules.length; i++) {
modules[i].setState(states[i]);
modules[i].setState(filterModuleState(states[i]));
}
}

Expand All @@ -105,14 +132,23 @@ public void drive(Vector2D translation, double rotation) {
translation.y, -translation.x, -rotation, Rotation2d.fromDegrees(gyro.getAngle())
);

// straight spinning drift fix
Pose2d robotVelocity = new Pose2d(
Settings.DT * speeds.vxMetersPerSecond,
Settings.DT * speeds.vyMetersPerSecond,
Rotation2d.fromRadians(Settings.DT * speeds.omegaRadiansPerSecond)
);
Twist2d twistVel = new Pose2d().log(robotVelocity);

ChassisSpeeds updatedSpeeds = new ChassisSpeeds(
twistVel.dx / Settings.DT,
twistVel.dy / Settings.DT,
twistVel.dtheta / Settings.DT
);
setChassisSpeeds(updatedSpeeds);
}



public void stop() {
setChassisSpeeds(new ChassisSpeeds());
}
}

0 comments on commit 0cf4858

Please sign in to comment.