generated from StuyPulse/Phil
-
Notifications
You must be signed in to change notification settings - Fork 1
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
swerve abstraction + drive command (no deadbands)
- Loading branch information
1 parent
0cf4858
commit 5559d1d
Showing
7 changed files
with
459 additions
and
274 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
76 changes: 76 additions & 0 deletions
76
src/main/java/com/stuypulse/robot/commands/swerve/SwerveDriveDrive.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,76 @@ | ||
package com.stuypulse.robot.commands.swerve; | ||
|
||
import java.util.Optional; | ||
|
||
import com.stuypulse.robot.constants.Settings.Swerve; | ||
import com.stuypulse.robot.subsystems.SwerveDrive; | ||
import com.stuypulse.stuylib.input.Gamepad; | ||
import com.stuypulse.stuylib.streams.IStream; | ||
import com.stuypulse.stuylib.streams.vectors.VStream; | ||
|
||
import edu.wpi.first.math.geometry.Rotation2d; | ||
import edu.wpi.first.wpilibj2.command.CommandBase; | ||
|
||
public class SwerveDriveDrive extends CommandBase { | ||
|
||
private SwerveDrive swerve; | ||
|
||
private VStream speed; | ||
private IStream turn; | ||
|
||
private final Gamepad driver; | ||
|
||
private Optional<Rotation2d> holdAngle; | ||
|
||
public SwerveDriveDrive(Gamepad driver) { | ||
this.driver = driver; | ||
swerve = SwerveDrive.getInstance(); | ||
|
||
speed = VStream.create(driver::getLeftStick); | ||
turn = IStream.create(driver::getRightX); | ||
|
||
holdAngle = Optional.empty(); | ||
|
||
addRequirements(swerve); | ||
|
||
|
||
} | ||
|
||
@Override | ||
public void initialize() { | ||
holdAngle = Optional.empty(); | ||
} | ||
|
||
private boolean isWithinTurnDeadband() { | ||
return Math.abs(turn.get()) < Swerve.MAX_MODULE_TURN.get(); | ||
} | ||
|
||
private boolean isWithinDriveDeadband() { | ||
return Math.abs(speed.get().magnitude()) < Swerve.MAX_MODULE_SPEED.get(); | ||
} | ||
|
||
@Override | ||
public void execute() { | ||
swerve.drive(speed.get(), turn.get()); | ||
|
||
|
||
if(isWithinTurnDeadband()){ | ||
if(holdAngle.isEmpty()) { | ||
holdAngle = Optional.of(swerve.getGyroAngle()); | ||
} | ||
|
||
} | ||
/*if (isWithinDriveDeadband()) { | ||
if () { | ||
} | ||
if () { | ||
} | ||
} | ||
else { | ||
}*/ | ||
} | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
98 changes: 98 additions & 0 deletions
98
src/main/java/com/stuypulse/robot/subsystems/SL_SwerveModule.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,98 @@ | ||
package com.stuypulse.robot.subsystems; | ||
|
||
import com.revrobotics.CANSparkMax; | ||
import com.revrobotics.CANSparkMaxLowLevel.MotorType; | ||
import com.revrobotics.RelativeEncoder; | ||
import com.revrobotics.SparkMaxAbsoluteEncoder; | ||
import com.revrobotics.SparkMaxAbsoluteEncoder.Type; | ||
import com.stuypulse.robot.constants.Settings.Swerve.Drive; | ||
import com.stuypulse.robot.constants.Settings.Swerve.Turn; | ||
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 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; | ||
|
||
public class SL_SwerveModule extends SwerveModule { | ||
// data | ||
private final String id; | ||
private SwerveModuleState targetState; | ||
private Translation2d translationOffset; | ||
private Rotation2d angleOffset; | ||
|
||
// turn | ||
private CANSparkMax turnMotor; | ||
private SparkMaxAbsoluteEncoder turnEncoder; | ||
|
||
// drive | ||
private CANSparkMax driveMotor; | ||
private RelativeEncoder driveEncoder; | ||
|
||
// controllers | ||
private Controller driveController; | ||
private AngleController turnController; | ||
|
||
public SL_SwerveModule(String id, Translation2d translationOffset, Rotation2d angleOffset, int turnID, int driveID) { | ||
this.id = id; | ||
this.translationOffset = translationOffset; | ||
|
||
turnMotor = new CANSparkMax(turnID, MotorType.kBrushless); | ||
driveMotor = new CANSparkMax(turnID, MotorType.kBrushless); | ||
|
||
turnEncoder = turnMotor.getAbsoluteEncoder(Type.kDutyCycle); | ||
driveEncoder = driveMotor.getEncoder(); | ||
|
||
driveController = new PIDController(Drive.kP, Drive.kI, Drive.kP) | ||
.add(new MotorFeedforward(Drive.kS, Drive.kV, Drive.kA).velocity()); | ||
|
||
turnController = new AnglePIDController(Turn.kP, Turn.kI, Turn.kP); | ||
} | ||
|
||
public Translation2d getOffset() { | ||
return translationOffset; | ||
} | ||
|
||
public String getID() { | ||
return id; | ||
} | ||
|
||
public SwerveModuleState getState() { | ||
return new SwerveModuleState(getVelocity(), getAngle()); | ||
} | ||
|
||
public double getVelocity() { | ||
return driveEncoder.getVelocity(); | ||
} | ||
|
||
public Rotation2d getAngle() { | ||
return Rotation2d.fromRotations(turnEncoder.getPosition()).minus(angleOffset); | ||
} | ||
|
||
public SwerveModulePosition getModulePosition() { | ||
return new SwerveModulePosition(driveEncoder.getPosition(), getAngle()); | ||
} | ||
|
||
public void setState(SwerveModuleState state) { | ||
targetState = SwerveModuleState.optimize(state, getAngle()); | ||
} | ||
|
||
@Override | ||
public void periodic() { | ||
turnMotor.setVoltage(turnController.update( | ||
Angle.fromRotation2d(targetState.angle), | ||
Angle.fromRotation2d(getAngle())) | ||
); | ||
|
||
driveMotor.setVoltage(driveController.update( | ||
targetState.speedMetersPerSecond, | ||
getVelocity()) | ||
); | ||
} | ||
} | ||
|
Oops, something went wrong.