Skip to content

Commit

Permalink
Updated to the latest main branch
Browse files Browse the repository at this point in the history
  • Loading branch information
AyushSagar16 committed Feb 24, 2024
2 parents e0642c9 + a532db5 commit 601c2f6
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 15 deletions.
6 changes: 3 additions & 3 deletions src/main/java/org/ghrobotics/frc2024/CANCoderSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -54,9 +54,9 @@ public void configure(boolean inverted) {
MagnetSensorConfigs magnetSensorConfiguration = new MagnetSensorConfigs();
cfg.refresh(magnetSensorConfiguration);
cfg.apply(magnetSensorConfiguration
.withAbsoluteSensorRange(AbsoluteSensorRangeValue.Signed_PlusMinusHalf)
.withSensorDirection(inverted ? SensorDirectionValue.Clockwise_Positive
: SensorDirectionValue.CounterClockwise_Positive));
.withAbsoluteSensorRange(AbsoluteSensorRangeValue.Signed_PlusMinusHalf)
.withSensorDirection(inverted ? SensorDirectionValue.Clockwise_Positive
: SensorDirectionValue.CounterClockwise_Positive));
}

/**
Expand Down
4 changes: 0 additions & 4 deletions src/main/java/org/ghrobotics/frc2024/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -26,14 +26,10 @@ public class Robot extends TimedRobot {

// Xbox Controller
private final CommandXboxController driver_controller_ = new CommandXboxController(0);

// private final AutoSelector auto_selector_ = new AutoSelector(drive_, robot_state_);

@Override
public void robotInit() {
drive_.setDefaultCommand(new DriveTeleop(drive_, robot_state_, driver_controller_));

drive_.setBrakeMode(true);
}

@Override
Expand Down
8 changes: 4 additions & 4 deletions src/main/java/org/ghrobotics/frc2024/subsystems/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -159,26 +159,26 @@ private static class Constants {
kFrontLeftConfig.drive_id = 1;
kFrontLeftConfig.steer_id = 2;
kFrontLeftConfig.cancoder_id = 11;
kFrontLeftConfig.module_offset_deg = -24.69 + 90;
kFrontLeftConfig.module_offset_deg = -8.0;
kFrontLeftConfig.invert = false;

kFrontRightConfig.drive_id = 3;
kFrontRightConfig.steer_id = 4;
kFrontRightConfig.cancoder_id = 12;
kFrontRightConfig.module_offset_deg = 0;
kFrontRightConfig.module_offset_deg = 173.44;
kFrontRightConfig.invert = true;

kBackLeftConfig.drive_id = 5;
kBackLeftConfig.steer_id = 6;
kBackLeftConfig.cancoder_id = 13;
kBackLeftConfig.module_offset_deg = -8 + 180;
kBackLeftConfig.module_offset_deg = 9.14;
kBackLeftConfig.invert = false;
// (228.00 + -46.799534) + 180;

kBackRightConfig.drive_id = 7;
kBackRightConfig.steer_id = 8;
kBackRightConfig.cancoder_id = 14;
kBackRightConfig.module_offset_deg = -14;
kBackRightConfig.module_offset_deg = 60.90;
kBackRightConfig.invert = true;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,12 +34,12 @@ public SwerveModule(Configuration configuration) {
// Initialize motor controllers
drive_motor_ = new CANSparkMax(configuration_.drive_id, CANSparkMax.MotorType.kBrushless);
drive_motor_.restoreFactoryDefaults();
drive_motor_.setIdleMode(CANSparkMax.IdleMode.kBrake);
drive_motor_.setIdleMode(CANSparkMax.IdleMode.kCoast);
drive_motor_.setInverted(configuration_.invert);

steer_motor_ = new CANSparkMax(configuration_.steer_id, CANSparkMax.MotorType.kBrushless);
steer_motor_.restoreFactoryDefaults();
steer_motor_.setIdleMode(CANSparkMax.IdleMode.kBrake);
steer_motor_.setIdleMode(CANSparkMax.IdleMode.kCoast);
steer_motor_.setInverted(true);

// Initialize encoders
Expand Down Expand Up @@ -75,7 +75,7 @@ public double getDrivePosition() {
// Get Steer Position
public Rotation2d getSteerPosition() {
return new Rotation2d(
Math.IEEEremainder(steer_encoder_.getPosition(), 2 * Math.PI));
Math.IEEEremainder(steer_encoder_.getPosition(), 2 * Math.PI));
}

// Get Module Position
Expand Down Expand Up @@ -121,7 +121,7 @@ public void setAngle(double desired_angle_degs) {

// Set steer angle
double steering_correction = steer_pid_controller_.calculate(
getSteerPosition().getRadians(), desired_angle_rad);
getSteerPosition().getRadians(), desired_angle_rad);
steer_motor_.set(steering_correction);
}

Expand Down

0 comments on commit 601c2f6

Please sign in to comment.