-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Create CoaxialSwerveModule interface and update NEOCoaxialSwerveModule
- Loading branch information
1 parent
369c91d
commit f3234ff
Showing
2 changed files
with
146 additions
and
188 deletions.
There are no files selected for viewing
54 changes: 54 additions & 0 deletions
54
src/main/java/com/techhounds/houndutil/houndlib/swerve/CoaxialSwerveModule.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,54 @@ | ||
package com.techhounds.houndutil.houndlib.swerve; | ||
|
||
import com.techhounds.houndutil.houndlib.MotorHoldMode; | ||
|
||
import edu.wpi.first.math.geometry.Rotation2d; | ||
import edu.wpi.first.math.kinematics.SwerveModulePosition; | ||
import edu.wpi.first.math.kinematics.SwerveModuleState; | ||
|
||
public interface CoaxialSwerveModule { | ||
public static class SwerveConstants { | ||
public double DRIVE_kP; | ||
public double DRIVE_kI; | ||
public double DRIVE_kD; | ||
public double DRIVE_kS; | ||
public double DRIVE_kV; | ||
public double DRIVE_kA; | ||
|
||
public double STEER_kP; | ||
public double STEER_kI; | ||
public double STEER_kD; | ||
|
||
public double MAX_DRIVING_VELOCITY_METERS_PER_SECOND; | ||
public double MAX_DRIVING_ACCELERATION_METERS_PER_SECOND_SQUARED; | ||
public double MAX_STEER_VELOCITY_RADIANS_PER_SECOND; | ||
public double MAX_STEER_ACCELERATION_RADIANS_PER_SECOND_SQUARED; | ||
|
||
public double ENCODER_ROTATIONS_TO_METERS; | ||
public double STEER_ENCODER_ROTATIONS_TO_METERS; | ||
|
||
public double DRIVE_CURRENT_LIMIT; | ||
public double STEER_CURRENT_LIMIT; | ||
} | ||
|
||
public double getDriveMotorPosition(); | ||
|
||
public double getDriveMotorVelocity(); | ||
|
||
public Rotation2d getWheelAngle(); | ||
|
||
public SwerveModulePosition getPosition(); | ||
|
||
public SwerveModuleState getState(); | ||
|
||
public void setMotorHoldMode(MotorHoldMode motorHoldMode); | ||
|
||
public void setDriveCurrentLimit(int currentLimit); | ||
|
||
public void stop(); | ||
|
||
public void setState(SwerveModuleState state); | ||
|
||
public void setStateClosedLoop(SwerveModuleState state); | ||
|
||
} |
Oops, something went wrong.