Encoder offsets.

This commit is contained in:
‮Zach Wilke
2021-12-06 16:41:28 -07:00
parent 7672d58439
commit 5f3e48b0ec
3 changed files with 17 additions and 6 deletions
@@ -46,6 +46,11 @@ public final class Constants {
public static final int RIGHT_FRONT_STEER_CAN_ENCODER_ID = 0; public static final int RIGHT_FRONT_STEER_CAN_ENCODER_ID = 0;
public static final int LEFT_BACK_STEER_CAN_ENCODER_ID = 0; public static final int LEFT_BACK_STEER_CAN_ENCODER_ID = 0;
public static final int RIGHT_BACK_STEER_CAN_ENCODER_ID = 0; public static final int RIGHT_BACK_STEER_CAN_ENCODER_ID = 0;
//ofsets are in degrees
public static final float LEFT_FRONT_ENCODER_OFFSET = 0;
public static final float RIGHT_FRONT_ENCODER_OFFSET = 0;
public static final float LEFT_BACK_ENCODER_OFFSET = 0;
public static final float RIGHT_BACK_ENCODER_OFFSET = 0;
} }
public static final class LEDConstants { public static final class LEDConstants {
public static final int LED_SPARK_ID = 0; public static final int LED_SPARK_ID = 0;
+7 -1
View File
@@ -11,6 +11,7 @@ import com.ctre.phoenix.motorcontrol.InvertType;
import com.ctre.phoenix.motorcontrol.NeutralMode; import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX; import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX;
import com.ctre.phoenix.sensors.PigeonIMU; import com.ctre.phoenix.sensors.PigeonIMU;
import com.ctre.phoenix.sensors.AbsoluteSensorRange;
import com.ctre.phoenix.sensors.CANCoder; import com.ctre.phoenix.sensors.CANCoder;
import edu.wpi.first.wpilibj.Spark; import edu.wpi.first.wpilibj.Spark;
@@ -29,6 +30,7 @@ public class RobotMap {
public RobotMap() { public RobotMap() {
configureLEDMotorControllers(); configureLEDMotorControllers();
configureArcadeDriveMotorControllers(); configureArcadeDriveMotorControllers();
configureSwerveMotorControllers();
} }
/* LED Subsystem */ /* LED Subsystem */
@@ -84,6 +86,10 @@ public class RobotMap {
public final CANCoder leftBackEncoder = new CANCoder(SwerveDriveConstants.LEFT_BACK_STEER_CAN_ENCODER_ID); public final CANCoder leftBackEncoder = new CANCoder(SwerveDriveConstants.LEFT_BACK_STEER_CAN_ENCODER_ID);
public final CANCoder rightBackEncoder = new CANCoder(SwerveDriveConstants.RIGHT_BACK_STEER_CAN_ENCODER_ID); public final CANCoder rightBackEncoder = new CANCoder(SwerveDriveConstants.RIGHT_BACK_STEER_CAN_ENCODER_ID);
void configureSwerveMotorController() { void configureSwerveMotorControllers() {
leftFrontEncoder.configMagnetOffset(SwerveDriveConstants.LEFT_BACK_ENCODER_OFFSET);
rightFrontEncoder.configMagnetOffset(SwerveDriveConstants.RIGHT_FRONT_ENCODER_OFFSET);
leftBackEncoder.configMagnetOffset(SwerveDriveConstants.LEFT_BACK_ENCODER_OFFSET);
rightBackEncoder.configMagnetOffset(SwerveDriveConstants.RIGHT_BACK_ENCODER_OFFSET);
} }
} }
@@ -76,13 +76,13 @@ public class SwerveDrive extends SubsystemBase
SwerveModuleState[] moduleStates = m_kinematics.toSwerveModuleStates(speeds); SwerveModuleState[] moduleStates = m_kinematics.toSwerveModuleStates(speeds);
// Front left module state // Front left module state
SwerveModuleState leftFront = SwerveModuleState.optimize(moduleStates[0], new Rotation2d(m_leftFrontEncoder.getPosition())); SwerveModuleState leftFront = SwerveModuleState.optimize(moduleStates[0], Rotation2d.fromDegrees(m_leftFrontEncoder.getPosition()));
// Front right module state // Front right module state
SwerveModuleState rightFront = SwerveModuleState.optimize(moduleStates[1], new Rotation2d(m_rightFrontEncoder.getPosition())); SwerveModuleState rightFront = SwerveModuleState.optimize(moduleStates[1], Rotation2d.fromDegrees(m_rightFrontEncoder.getPosition()));
// Back left module state // Back left module state
SwerveModuleState leftBack = SwerveModuleState.optimize(moduleStates[2], new Rotation2d(m_leftBackEncoder.getPosition())); SwerveModuleState leftBack = SwerveModuleState.optimize(moduleStates[2], Rotation2d.fromDegrees(m_leftBackEncoder.getPosition()));
// Back right module state // Back right module state
SwerveModuleState rightBack = SwerveModuleState.optimize(moduleStates[3], new Rotation2d(m_rightBackEncoder.getPosition())); SwerveModuleState rightBack = SwerveModuleState.optimize(moduleStates[3], Rotation2d.fromDegrees(m_rightBackEncoder.getPosition()));
//Set the Wheel motor speeds //Set the Wheel motor speeds
m_leftFrontWheelMotor.set(m_leftFrontSteerMotor.get() + leftFront.speedMetersPerSecond * SwerveDriveConstants.WHEEL_SPEED); m_leftFrontWheelMotor.set(m_leftFrontSteerMotor.get() + leftFront.speedMetersPerSecond * SwerveDriveConstants.WHEEL_SPEED);