Skip to content

Commit

Permalink
ports + the funny
Browse files Browse the repository at this point in the history
  • Loading branch information
Yxhej committed Jan 16, 2024
1 parent 1c341d0 commit 03e6fce
Show file tree
Hide file tree
Showing 4 changed files with 20 additions and 10 deletions.
7 changes: 7 additions & 0 deletions .vscode/launch.json
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,13 @@
// For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387
"version": "0.2.0",
"configurations": [
{
"type": "java",
"name": "FlexModule",
"request": "launch",
"mainClass": "org.sciborgs1155.robot.drive.FlexModule",
"projectName": "Hydrogen"
},
{
"type": "java",
"name": "TalonSwerveModule",
Expand Down
16 changes: 8 additions & 8 deletions src/main/java/org/sciborgs1155/robot/Ports.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,14 +7,14 @@ public static final class OI {
}

public static final class Drive {
public static final int FRONT_LEFT_DRIVE = 1;
public static final int REAR_LEFT_DRIVE = 38;
public static final int FRONT_RIGHT_DRIVE = 32;
public static final int REAR_RIGHT_DRIVE = 5;
public static final int FRONT_LEFT_DRIVE = 4;
public static final int REAR_LEFT_DRIVE = 1;
public static final int FRONT_RIGHT_DRIVE = 2;
public static final int REAR_RIGHT_DRIVE = 3;

public static final int FRONT_LEFT_TURNING = 31;
public static final int REAR_LEFT_TURNING = 36;
public static final int FRONT_RIGHT_TURNING = 3;
public static final int REAR_RIGHT_TURNING = 40;
public static final int FRONT_LEFT_TURNING = 22;
public static final int REAR_LEFT_TURNING = 16;
public static final int FRONT_RIGHT_TURNING = 44;
public static final int REAR_RIGHT_TURNING = 23;
}
}
4 changes: 3 additions & 1 deletion src/main/java/org/sciborgs1155/robot/drive/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ public class Drive extends SubsystemBase implements Logged, AutoCloseable {
public static Drive create() {
return Robot.isReal()
? new Drive(
new FlexModule(FRONT_LEFT_TURNING, FRONT_LEFT_DRIVE, ANGULAR_OFFSETS.get(0)),
new FlexModule(FRONT_LEFT_DRIVE, FRONT_LEFT_TURNING, ANGULAR_OFFSETS.get(0)),
new FlexModule(FRONT_RIGHT_DRIVE, FRONT_RIGHT_TURNING, ANGULAR_OFFSETS.get(1)),
new FlexModule(REAR_LEFT_DRIVE, REAR_LEFT_TURNING, ANGULAR_OFFSETS.get(2)),
new FlexModule(REAR_RIGHT_DRIVE, REAR_RIGHT_TURNING, ANGULAR_OFFSETS.get(3)))
Expand Down Expand Up @@ -223,11 +223,13 @@ public double getPitch() {
}

/** Returns the module states. */
@Log.NT
private SwerveModuleState[] getModuleStates() {
return modules.stream().map(SwerveModule::state).toArray(SwerveModuleState[]::new);
}

/** Returns the module positions */
@Log.NT
private SwerveModulePosition[] getModulePositions() {
return modules.stream().map(SwerveModule::position).toArray(SwerveModulePosition[]::new);
}
Expand Down
3 changes: 2 additions & 1 deletion src/main/java/org/sciborgs1155/robot/drive/FlexModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkFlex;
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder;
import com.revrobotics.SparkAbsoluteEncoder;
import com.revrobotics.SparkAbsoluteEncoder.Type;
Expand Down Expand Up @@ -41,7 +42,7 @@ public FlexModule(int drivePort, int turnPort, Rotation2d angularOffset) {
driveMotor.setIdleMode(IdleMode.kBrake);
driveMotor.setSmartCurrentLimit((int) Driving.CURRENT_LIMIT.in(Amps));

turnMotor = new CANSparkFlex(turnPort, MotorType.kBrushless);
turnMotor = new CANSparkMax(turnPort, MotorType.kBrushless);
turnMotor.restoreFactoryDefaults();
turnMotor.setInverted(false);
turnMotor.setIdleMode(IdleMode.kBrake);
Expand Down

0 comments on commit 03e6fce

Please sign in to comment.