Skip to content

Commit

Permalink
Consolidated Spark Flex Motor Factories
Browse files Browse the repository at this point in the history
  • Loading branch information
danjburke12 committed Jan 29, 2024
1 parent ac580a6 commit 6932da6
Show file tree
Hide file tree
Showing 3 changed files with 64 additions and 89 deletions.
32 changes: 15 additions & 17 deletions src/main/java/com/team1701/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,15 +20,13 @@
import com.team1701.lib.util.GeometryUtil;
import com.team1701.lib.util.LoggedTunableNumber;
import com.team1701.robot.Configuration.Mode;
import com.team1701.robot.SparkFlexMotorFactory.ShooterMotorUsage;
import com.team1701.robot.commands.AutonomousCommands;
import com.team1701.robot.commands.DriveCommands;
import com.team1701.robot.states.RobotState;
import com.team1701.robot.subsystems.drive.Drive;
import com.team1701.robot.subsystems.drive.DriveMotorFactory;
import com.team1701.robot.subsystems.drive.SwerveModule.SwerveModuleIO;
import com.team1701.robot.subsystems.shooter.Shooter;
import com.team1701.robot.subsystems.shooter.ShooterMotorFactory;
import com.team1701.robot.subsystems.shooter.ShooterMotorFactory.ShooterMotorUsage;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.system.plant.DCMotor;
Expand Down Expand Up @@ -65,31 +63,31 @@ public RobotContainer() {
new GyroIOPigeon2(10),
new SwerveModuleIO[] {
new SwerveModuleIO(
DriveMotorFactory.createDriveMotorIOSparkMax(10),
DriveMotorFactory.createSteerMotorIOSparkMax(11),
SparkFlexMotorFactory.createDriveMotorIOSparkMax(10),
SparkFlexMotorFactory.createSteerMotorIOSparkMax(11),
new EncoderIOAnalog(0)),
new SwerveModuleIO(
DriveMotorFactory.createDriveMotorIOSparkMax(12),
DriveMotorFactory.createSteerMotorIOSparkMax(13),
SparkFlexMotorFactory.createDriveMotorIOSparkMax(12),
SparkFlexMotorFactory.createSteerMotorIOSparkMax(13),
new EncoderIOAnalog(1)),
new SwerveModuleIO(
DriveMotorFactory.createDriveMotorIOSparkMax(16),
DriveMotorFactory.createSteerMotorIOSparkMax(17),
SparkFlexMotorFactory.createDriveMotorIOSparkMax(16),
SparkFlexMotorFactory.createSteerMotorIOSparkMax(17),
new EncoderIOAnalog(3)),
new SwerveModuleIO(
DriveMotorFactory.createDriveMotorIOSparkMax(14),
DriveMotorFactory.createSteerMotorIOSparkMax(15),
SparkFlexMotorFactory.createDriveMotorIOSparkMax(14),
SparkFlexMotorFactory.createSteerMotorIOSparkMax(15),
new EncoderIOAnalog(2)),
},
mRobotState));

// TODO: update IDs
shooter = Optional.of(new Shooter(
ShooterMotorFactory.createShooterMotorIOSparkFlex(
SparkFlexMotorFactory.createShooterMotorIOSparkFlex(
Constants.Shooter.kShooterUpperRollerMotorId, ShooterMotorUsage.ROLLER),
ShooterMotorFactory.createShooterMotorIOSparkFlex(
SparkFlexMotorFactory.createShooterMotorIOSparkFlex(
Constants.Shooter.kShooterUpperRollerMotorId, ShooterMotorUsage.ROLLER),
ShooterMotorFactory.createShooterMotorIOSparkFlex(
SparkFlexMotorFactory.createShooterMotorIOSparkFlex(
Constants.Shooter.kShooterRotationMotorId, ShooterMotorUsage.ROTATION),
new EncoderIOAnalog(Constants.Shooter.kShooterThroughBoreEncoderId)));
break;
Expand Down Expand Up @@ -138,11 +136,11 @@ public RobotContainer() {
new AprilTagCameraIO() {})); */

this.mShooter = shooter.orElseGet(() -> new Shooter(
ShooterMotorFactory.createShooterMotorIOSparkFlex(
SparkFlexMotorFactory.createShooterMotorIOSparkFlex(
Constants.Shooter.kShooterUpperRollerMotorId, ShooterMotorUsage.ROLLER),
ShooterMotorFactory.createShooterMotorIOSparkFlex(
SparkFlexMotorFactory.createShooterMotorIOSparkFlex(
Constants.Shooter.kShooterUpperRollerMotorId, ShooterMotorUsage.ROLLER),
ShooterMotorFactory.createShooterMotorIOSparkFlex(
SparkFlexMotorFactory.createShooterMotorIOSparkFlex(
Constants.Shooter.kShooterRotationMotorId, ShooterMotorUsage.ROTATION),
new EncoderIOAnalog(Constants.Shooter.kShooterThroughBoreEncoderId)));

Expand Down
Original file line number Diff line number Diff line change
@@ -1,15 +1,56 @@
package com.team1701.robot.subsystems.drive;
package com.team1701.robot;

import java.util.function.Supplier;

import com.revrobotics.CANSparkFlex;
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.CANSparkMax;
import com.revrobotics.REVLibError;
import com.team1701.lib.alerts.REVAlert;
import com.team1701.lib.drivers.motors.MotorIOSparkFlex;
import com.team1701.lib.drivers.motors.MotorIOSparkMax;
import com.team1701.robot.Constants;

public final class DriveMotorFactory {
public class SparkFlexMotorFactory {
public static MotorIOSparkFlex createShooterMotorIOSparkFlex(int deviceId, ShooterMotorUsage motorUse) {
var motor = new CANSparkFlex(deviceId, MotorType.kBrushless);
var encoder = motor.getEncoder();
var controller = motor.getPIDController();
var errorAlert = new REVAlert(motor, deviceId);

motor.setCANTimeout(200);

// TODO: Update values for actual shooter
configureWithRetry(() -> motor.restoreFactoryDefaults(), errorAlert);

configureWithRetry(() -> motor.setSmartCurrentLimit(80), errorAlert);
configureWithRetry(() -> motor.enableVoltageCompensation(12), errorAlert);

configureWithRetry(() -> encoder.setPosition(0), errorAlert);
configureWithRetry(() -> encoder.setMeasurementPeriod(10), errorAlert);
configureWithRetry(() -> encoder.setAverageDepth(2), errorAlert);

switch (motorUse) {
case ROLLER:
configureWithRetry(() -> controller.setP(Constants.Shooter.kRollerKp.get()), errorAlert);
configureWithRetry(() -> controller.setD(Constants.Shooter.kRollerKd.get()), errorAlert);
configureWithRetry(() -> controller.setFF(Constants.Shooter.kRollerKff.get()), errorAlert);
break;
case ROTATION:
configureWithRetry(() -> controller.setP(Constants.Shooter.kRotationKp.get()), errorAlert);
configureWithRetry(() -> controller.setD(Constants.Shooter.kRotationKd.get()), errorAlert);
configureWithRetry(() -> controller.setFF(Constants.Shooter.kRotationKff.get()), errorAlert);
break;
default:
break;
}

configureWithRetry(() -> motor.burnFlash(), errorAlert);

motor.setCANTimeout(0);

return new MotorIOSparkFlex(motor, Constants.Shooter.kShooterReduction);
}

public static MotorIOSparkMax createDriveMotorIOSparkMax(int deviceId) {
var motor = new CANSparkMax(deviceId, MotorType.kBrushless);
var encoder = motor.getEncoder();
Expand Down Expand Up @@ -83,4 +124,9 @@ private static void configureWithRetry(Supplier<REVLibError> config, REVAlert fa

failureAlert.enable(error);
}

public enum ShooterMotorUsage {
ROLLER,
ROTATION
}
}

This file was deleted.

0 comments on commit 6932da6

Please sign in to comment.