Skip to content

Commit

Permalink
Attempt at swerve odometry continue:
Browse files Browse the repository at this point in the history
- use pose estimator wrapper for limelight later
- ensure offset is used in swerve position getter
  • Loading branch information
bobopop787 committed Feb 17, 2024
1 parent 63e280a commit 60763f0
Show file tree
Hide file tree
Showing 2 changed files with 24 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,7 @@ public SDSSwerveModule(String name, int turnID, int driveID, Rotation2d angularO
driveMotor.setSmartCurrentLimit(20);
driveEncoder.setPositionConversionFactor(SwerveConstants.kDrivePositionConversionFactor);
driveEncoder.setVelocityConversionFactor(SwerveConstants.kDriveVelocityConversionFactor);
driveEncoder.setPositionConversionFactor(1); // TEMPORARY JUST TO CHECK IF ODOMETRY GOES THE RIGHT WAY

turnPIDController.setPositionPIDWrappingEnabled(true);
turnPIDController.setPositionPIDWrappingMinInput(0);
Expand Down Expand Up @@ -148,7 +149,7 @@ public SwerveModuleState getDesiredSwerveState() {
public SwerveModulePosition getPosition() {
return new SwerveModulePosition(
driveEncoder.getPosition(),
useAbsolute ? Rotation2d.fromRadians(getAbsTurnPos()) : Rotation2d.fromRadians(getRelTurnPos() / 2)
useAbsolute ? Rotation2d.fromRadians(getAbsTurnPos()).plus(chassisAngularOffset) : Rotation2d.fromRadians(getRelTurnPos() / 2)
);
}

Expand Down
24 changes: 22 additions & 2 deletions src/main/java/frc/robot/subsystems/swerve/SwerveDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,11 +6,14 @@
import com.ctre.phoenix6.hardware.Pigeon2;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator;
import edu.wpi.first.math.geometry.Pose2d;
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.SwerveDriveOdometry;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj.Preferences;
Expand All @@ -36,7 +39,7 @@ public class SwerveDrive extends SubsystemBase {
private Pigeon2 gyro;

private SwerveDriveKinematics swerveKinematics;
private SwerveDriveOdometry swerveOdomentry;
private SwerveDrivePoseEstimator swerveOdomentry;

private RateLimiter magnitudeAccelLimiter;
private RateLimiter directionVelLimiter;
Expand Down Expand Up @@ -108,7 +111,12 @@ private void initMathModels() {
new Translation2d(SwerveConstants.kWheelDistanceMeters / 2, -SwerveConstants.kWheelDistanceMeters / 2),
new Translation2d(SwerveConstants.kWheelDistanceMeters / 2, SwerveConstants.kWheelDistanceMeters / 2)
);
// swerveOdomentry = new SwerveDriveOdometry(m_swerveKinematics, Rotation2d.fromDegrees(m_gyro.getAngle()), null);
swerveOdomentry = new SwerveDrivePoseEstimator(swerveKinematics, Rotation2d.fromDegrees(gyro.getAngle()), new SwerveModulePosition[]{
backLeftModule.getPosition(),
backRightModule.getPosition(),
frontLeftModule.getPosition(),
frontRightModule.getPosition()
}, new Pose2d());
}

private void initSimulations() {
Expand Down Expand Up @@ -141,6 +149,8 @@ private void initSimulations() {

field = new Field2d();

field.setRobotPose(new Pose2d(1, 1, new Rotation2d(0)));

SmartDashboard.putData("Swerve Visualization", swerveVisualizer);
SmartDashboard.putData("Field", field);

Expand Down Expand Up @@ -283,5 +293,15 @@ public void periodic() {
backRightModule.putInfo("backRight");

SmartDashboard.putNumber("Gyro", gyro.getAngle());

swerveOdomentry.update(Rotation2d.fromDegrees(gyro.getAngle()), new SwerveModulePosition[]{
backLeftModule.getPosition(),
backRightModule.getPosition(),
frontLeftModule.getPosition(),
frontRightModule.getPosition()
});
field.setRobotPose(swerveOdomentry.getEstimatedPosition());
System.out.println(swerveOdomentry.getEstimatedPosition().getX() + " " + swerveOdomentry.getEstimatedPosition().getY());
SmartDashboard.putData(field);
}
}

0 comments on commit 60763f0

Please sign in to comment.