Skip to content

Commit

Permalink
Expose required methods
Browse files Browse the repository at this point in the history
  • Loading branch information
anivanchen committed Jan 23, 2024
1 parent bc52ea2 commit 96a0e18
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 9 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,10 @@
import com.stuypulse.robot.constants.Settings.Swerve.FrontLeft;
import com.stuypulse.robot.constants.Settings.Swerve.FrontRight;

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.smartdashboard.Field2d;
Expand All @@ -31,7 +33,8 @@ public static AbstractSwerveDrive getInstance() {
}

public abstract void initFieldObject(Field2d field);


public abstract SwerveDriveKinematics getKinematics();
public abstract SwerveModuleState[] getModuleStates();
public abstract SwerveModulePosition[] getModulePositions();
public abstract Translation2d[] getModuleOffsets();
Expand All @@ -41,4 +44,6 @@ public static AbstractSwerveDrive getInstance() {
public abstract void setModuleStates(SwerveModuleState[] states);
public abstract void drive(Vector2D velocity, double Rotation2D);
public abstract void stop(double Rotation2D);

public abstract Rotation2d getGyroAngle();
}
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,7 @@ public void initFieldObject(Field2d field) {
}
}

@Override
public SwerveDriveKinematics getKinematics() {
return kinematics;
}
Expand Down Expand Up @@ -169,21 +170,18 @@ public void stop(double Rotation2D) {
}

/*Gyro */
public Rotation2d getGyroPitch() {
return Rotation2d.fromDegrees(gyro.getPitch());
}

@Override
public Rotation2d getGyroAngle() {
return gyro.getRotation2d();
}

public Rotation2d getGyroPitch() {
return Rotation2d.fromDegrees(gyro.getPitch());
}

public Rotation2d getGyroRoll() {
return Rotation2d.fromDegrees(gyro.getRoll());
}

public Rotation2d getGyroYaw() {
return Rotation2d.fromDegrees(gyro.getYaw());
}

public double getForwardAccelerationGs() {
return gyro.getWorldLinearAccelY();
Expand Down

0 comments on commit 96a0e18

Please sign in to comment.