Skip to content

Commit

Permalink
implement inline motor config w/ sparkutils
Browse files Browse the repository at this point in the history
  • Loading branch information
Yxhej committed Oct 26, 2023
1 parent 35e7783 commit 360f8d6
Show file tree
Hide file tree
Showing 9 changed files with 120 additions and 84 deletions.
16 changes: 9 additions & 7 deletions src/main/java/org/sciborgs1155/lib/constants/SparkUtils.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
package org.sciborgs1155.lib.constants;

/** Add your docs here. */
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
import com.revrobotics.CANSparkMaxLowLevel.PeriodicFrame;
Expand All @@ -17,23 +16,20 @@ public class SparkUtils {
* Creates and configures a CANSparkMax.
*
* @param port
* @param type
* @param config
* @return The configured CANSparkMax
*/
public static CANSparkMax create(int port, MotorType type, Consumer<CANSparkMax> config) {
CANSparkMax spark = new CANSparkMax(port, type);
public static CANSparkMax create(int port, Consumer<CANSparkMax> config) {
CANSparkMax spark = new CANSparkMax(port, MotorType.kBrushless);
spark.restoreFactoryDefaults();
config.accept(spark);
sparks.add(spark);
return spark;
}

/**
* Burn to flash all motor configs at once, accounting for CAN bus delay. Use after fully
* Burn all motor configs to flash at the same time, accounting for CAN bus delay. Use after fully
* configuring motors.
*
* @param sparks
*/
public static void safeBurnFlash() {
Timer.delay(0.2);
Expand All @@ -44,6 +40,12 @@ public static void safeBurnFlash() {
Timer.delay(0.2);
}

/**
* Disables a list of frames for a specific motor.
*
* @param spark
* @param frames
*/
public static void disableFrames(CANSparkMax spark, int... frames) {
for (int frame : frames) {
spark.setPeriodicFramePeriod(PeriodicFrame.fromId(frame), 65535);
Expand Down
1 change: 0 additions & 1 deletion src/main/java/org/sciborgs1155/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@
import edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints;
import java.awt.Color;
import java.util.Map;
import org.sciborgs1155.lib.constants.MotorConfig;
import org.sciborgs1155.lib.constants.PIDConstants;

/**
Expand Down
11 changes: 0 additions & 11 deletions src/main/java/org/sciborgs1155/robot/arm/ArmConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,6 @@
import edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints;
import org.sciborgs1155.lib.constants.ArmFFConstants;
import org.sciborgs1155.lib.constants.ElevatorFFConstants;
import org.sciborgs1155.lib.constants.MotorConfig;
import org.sciborgs1155.lib.constants.MotorConfig.NeutralBehavior;
import org.sciborgs1155.lib.constants.PIDConstants;
import org.sciborgs1155.robot.Constants;
import org.sciborgs1155.robot.Constants.Dimensions;
Expand All @@ -15,9 +13,6 @@
public class ArmConstants {

public static final class Wrist {
public static final MotorConfig MOTOR_CFG =
MotorConfig.base().withNeutralBehavior(NeutralBehavior.BRAKE);

public static final double MOTOR_GEARING = 53.125 / 1.0;
// Gearing for motor : angle (radians)

Expand Down Expand Up @@ -60,9 +55,6 @@ public static final class Wrist {
}

public static final class Elbow {
public static final MotorConfig MOTOR_CFG =
MotorConfig.base().withNeutralBehavior(NeutralBehavior.BRAKE).withCurrentLimit(50);

public static final double MOTOR_GEARING = 63.75 / 1.0;

public static final double ENCODER_RATIO = 12.0 / 72.0;
Expand Down Expand Up @@ -107,9 +99,6 @@ public static final class Elbow {
}

public static final class Elevator {
public static final MotorConfig MOTOR_CFG =
MotorConfig.base().withNeutralBehavior(NeutralBehavior.BRAKE).withCurrentLimit(35);

public static final double MOTOR_GEARING = 30.0 / 1.0;
// Gearing for motor : height (meters)

Expand Down
52 changes: 33 additions & 19 deletions src/main/java/org/sciborgs1155/robot/arm/RealElbow.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
import static org.sciborgs1155.robot.Ports.Elbow.*;

import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
import com.revrobotics.CANSparkMax.IdleMode;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.geometry.Rotation2d;
Expand All @@ -13,16 +13,41 @@
import io.github.oblarg.oblog.annotations.Log;
import java.util.List;
import org.sciborgs1155.lib.BetterArmFeedforward;
import org.sciborgs1155.lib.constants.MotorConfig;
import org.sciborgs1155.lib.constants.SparkUtils;
import org.sciborgs1155.lib.failure.FaultBuilder;
import org.sciborgs1155.lib.failure.HardwareFault;
import org.sciborgs1155.robot.Constants;
import org.sciborgs1155.robot.arm.ArmConstants.Elbow;

public class RealElbow implements JointIO {
private final CANSparkMax middleMotor;
private final CANSparkMax leftMotor;
private final CANSparkMax rightMotor;
private final CANSparkMax middleMotor =
SparkUtils.create(
MIDDLE_MOTOR,
s -> {
s.setIdleMode(IdleMode.kBrake);
s.setOpenLoopRampRate(0);
s.setSmartCurrentLimit(50);
});

private final CANSparkMax leftMotor =
SparkUtils.create(
LEFT_MOTOR,
s -> {
s.setIdleMode(IdleMode.kBrake);
s.setOpenLoopRampRate(0);
s.setSmartCurrentLimit(50);
s.follow(middleMotor);
});

private final CANSparkMax rightMotor =
SparkUtils.create(
RIGHT_MOTOR,
s -> {
s.setIdleMode(IdleMode.kBrake);
s.setOpenLoopRampRate(0);
s.setSmartCurrentLimit(50);
s.follow(middleMotor);
});

private final Encoder encoder;

Expand All @@ -36,20 +61,9 @@ public class RealElbow implements JointIO {
private double lastVoltage;

public RealElbow(JointConfig config) {
middleMotor = Elbow.MOTOR_CFG.build(null, MIDDLE_MOTOR);
leftMotor = Elbow.MOTOR_CFG.build(MotorType.kBrushless, LEFT_MOTOR);
rightMotor = Elbow.MOTOR_CFG.build(MotorType.kBrushless, RIGHT_MOTOR);

MotorConfig.disableFrames(middleMotor, 4, 5, 6);
MotorConfig.disableFrames(leftMotor, 1, 2, 3, 4, 5, 6);
MotorConfig.disableFrames(rightMotor, 1, 2, 3, 4, 5, 6);

leftMotor.follow(middleMotor);
rightMotor.follow(middleMotor);

middleMotor.burnFlash();
leftMotor.burnFlash();
rightMotor.burnFlash();
SparkUtils.disableFrames(middleMotor, 4, 5, 6);
SparkUtils.disableFrames(leftMotor, 1, 2, 3, 4, 5, 6);
SparkUtils.disableFrames(rightMotor, 1, 2, 3, 4, 5, 6);

encoder = new Encoder(ENCODER[0], ENCODER[1]);
encoder.setDistancePerPulse(Elbow.CONVERSION);
Expand Down
52 changes: 33 additions & 19 deletions src/main/java/org/sciborgs1155/robot/arm/RealElevator.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,25 +3,50 @@
import static org.sciborgs1155.robot.Ports.Elevator.*;

import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
import com.revrobotics.CANSparkMax.IdleMode;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.trajectory.TrapezoidProfile.State;
import edu.wpi.first.util.sendable.SendableBuilder;
import edu.wpi.first.wpilibj.Encoder;
import java.util.List;
import org.sciborgs1155.lib.BetterElevatorFeedforward;
import org.sciborgs1155.lib.constants.MotorConfig;
import org.sciborgs1155.lib.constants.SparkUtils;
import org.sciborgs1155.lib.failure.FaultBuilder;
import org.sciborgs1155.lib.failure.HardwareFault;
import org.sciborgs1155.robot.Constants;
import org.sciborgs1155.robot.arm.ArmConstants.Elevator;

public class RealElevator implements ElevatorIO {

private final CANSparkMax lead;
private final CANSparkMax left;
private final CANSparkMax right;
private final CANSparkMax lead =
SparkUtils.create(
RIGHT_MOTOR,
s -> {
s.setIdleMode(IdleMode.kBrake);
s.setOpenLoopRampRate(0);
s.setSmartCurrentLimit(35);
});

private final CANSparkMax left =
SparkUtils.create(
LEFT_MOTOR,
s -> {
s.setIdleMode(IdleMode.kBrake);
s.setOpenLoopRampRate(0);
s.setSmartCurrentLimit(35);
s.follow(lead);
});

private final CANSparkMax right =
SparkUtils.create(
MIDDLE_MOTOR,
s -> {
s.setIdleMode(IdleMode.kBrake);
s.setOpenLoopRampRate(0);
s.setSmartCurrentLimit(35);
s.follow(lead);
});

private final Encoder encoder;

Expand All @@ -35,20 +60,9 @@ public class RealElevator implements ElevatorIO {
private double lastVoltage;

public RealElevator(ElevatorConfig config) {
lead = Elevator.MOTOR_CFG.build(MotorType.kBrushless, RIGHT_MOTOR);
left = Elevator.MOTOR_CFG.build(MotorType.kBrushless, LEFT_MOTOR);
right = Elevator.MOTOR_CFG.build(MotorType.kBrushless, MIDDLE_MOTOR);

left.follow(lead);
right.follow(lead);

MotorConfig.disableFrames(lead, 4, 5, 6);
MotorConfig.disableFrames(left, 1, 2, 3, 4, 5, 6);
MotorConfig.disableFrames(right, 1, 2, 3, 4, 5, 6);

lead.burnFlash();
left.burnFlash();
right.burnFlash();
SparkUtils.disableFrames(lead, 4, 5, 6);
SparkUtils.disableFrames(left, 1, 2, 3, 4, 5, 6);
SparkUtils.disableFrames(right, 1, 2, 3, 4, 5, 6);

encoder = new Encoder(ENCODER[0], ENCODER[1]);
encoder.setDistancePerPulse(Elevator.CONVERSION_RELATIVE);
Expand Down
19 changes: 12 additions & 7 deletions src/main/java/org/sciborgs1155/robot/arm/RealWrist.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
import static org.sciborgs1155.robot.Ports.Wrist.*;

import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
import com.revrobotics.CANSparkMax.IdleMode;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.geometry.Rotation2d;
Expand All @@ -13,15 +13,23 @@
import edu.wpi.first.wpilibj.Encoder;
import java.util.List;
import org.sciborgs1155.lib.BetterArmFeedforward;
import org.sciborgs1155.lib.constants.MotorConfig;
import org.sciborgs1155.lib.constants.SparkUtils;
import org.sciborgs1155.lib.failure.FaultBuilder;
import org.sciborgs1155.lib.failure.HardwareFault;
import org.sciborgs1155.robot.Constants;
import org.sciborgs1155.robot.arm.ArmConstants.Wrist;

public class RealWrist implements JointIO {

private final CANSparkMax motor;
private final CANSparkMax motor =
SparkUtils.create(
MOTOR,
s -> {
s.setIdleMode(IdleMode.kBrake);
s.setOpenLoopRampRate(0);
s.setSmartCurrentLimit(80);
});

private final DutyCycleEncoder absolute;
private final Encoder relative;

Expand All @@ -37,7 +45,6 @@ public class RealWrist implements JointIO {
private double lastVoltage;

public RealWrist(JointConfig config) {
motor = Wrist.MOTOR_CFG.build(MotorType.kBrushless, MOTOR);
absolute = new DutyCycleEncoder(ABS_ENCODER);
relative = new Encoder(RELATIVE_ENCODER[0], RELATIVE_ENCODER[1]);

Expand All @@ -46,9 +53,7 @@ public RealWrist(JointConfig config) {
relative.setDistancePerPulse(Wrist.CONVERSION_RELATIVE);
relative.setReverseDirection(true);

MotorConfig.disableFrames(motor, 4, 5, 6);

motor.burnFlash();
SparkUtils.disableFrames(motor, 4, 5, 6);

ff = config.ff().createFeedforward();
pid = config.pid().createPIDController();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,9 @@
import com.pathplanner.lib.PathConstraints;
import edu.wpi.first.math.geometry.Translation2d;
import org.sciborgs1155.lib.constants.BasicFFConstants;
import org.sciborgs1155.lib.constants.MotorConfig;
import org.sciborgs1155.lib.constants.MotorConfig.NeutralBehavior;
import org.sciborgs1155.lib.constants.PIDConstants;

public final class DriveConstants {

public static final double MAX_SPEED = 4.8; // m / s
public static final double MAX_ANGULAR_SPEED = 2 * Math.PI; // rad / s
public static final double MAX_ACCEL = 6.5; // m / s^2
Expand Down Expand Up @@ -46,9 +43,6 @@ public final class DriveConstants {

public static final class SwerveModule {
public static final class Driving {
public static final MotorConfig MOTOR_CFG =
MotorConfig.base().withNeutralBehavior(NeutralBehavior.BRAKE).withCurrentLimit(50);

public static final double CIRCUMFERENCE = 2.0 * Math.PI * 0.0381;
// Diameter of the wheel in meters (2 * π * R)

Expand All @@ -61,9 +55,6 @@ public static final class Driving {
}

public static final class Turning {
public static final MotorConfig MOTOR_CFG =
MotorConfig.base().withNeutralBehavior(NeutralBehavior.BRAKE).withCurrentLimit(20);

public static final double MOTOR_GEARING = 1.0 / 4.0 / 3.0;

public static final double CONVERSION = 2.0 * Math.PI;
Expand Down
31 changes: 22 additions & 9 deletions src/main/java/org/sciborgs1155/robot/drive/MAXSwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
import com.revrobotics.AbsoluteEncoder;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMax.ControlType;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
import com.revrobotics.CANSparkMax.IdleMode;
import com.revrobotics.RelativeEncoder;
import com.revrobotics.SparkMaxAbsoluteEncoder.Type;
import com.revrobotics.SparkMaxPIDController;
Expand All @@ -12,8 +12,8 @@
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import java.util.List;
import org.sciborgs1155.lib.constants.MotorConfig;
import org.sciborgs1155.lib.constants.PIDConstants;
import org.sciborgs1155.lib.constants.SparkUtils;
import org.sciborgs1155.lib.failure.FaultBuilder;
import org.sciborgs1155.lib.failure.HardwareFault;
import org.sciborgs1155.robot.drive.DriveConstants.SwerveModule.Driving;
Expand Down Expand Up @@ -49,8 +49,24 @@ public class MAXSwerveModule implements ModuleIO {
public MAXSwerveModule(String name, int drivePort, int turnPort, double angularOffset) {
this.name = name;

driveMotor = Driving.MOTOR_CFG.build(MotorType.kBrushless, drivePort);
turnMotor = Turning.MOTOR_CFG.build(MotorType.kBrushless, turnPort);
driveMotor =
SparkUtils.create(
drivePort,
s -> {
s.setInverted(false);
s.setIdleMode(IdleMode.kBrake);
s.setOpenLoopRampRate(0);
s.setSmartCurrentLimit(50);
});
turnMotor =
SparkUtils.create(
turnPort,
s -> {
s.setInverted(false);
s.setIdleMode(IdleMode.kBrake);
s.setOpenLoopRampRate(0);
s.setSmartCurrentLimit(20);
});

driveEncoder = driveMotor.getEncoder();
turningEncoder = turnMotor.getAbsoluteEncoder(Type.kDutyCycle);
Expand All @@ -76,11 +92,8 @@ public MAXSwerveModule(String name, int drivePort, int turnPort, double angularO
turnFeedback.setPositionPIDWrappingMinInput(0);
turnFeedback.setPositionPIDWrappingMaxInput(Turning.CONVERSION);

MotorConfig.disableFrames(driveMotor, 4, 5, 6);
MotorConfig.disableFrames(turnMotor, 4, 6);

driveMotor.burnFlash();
turnMotor.burnFlash();
SparkUtils.disableFrames(driveMotor, 4, 5, 6);
SparkUtils.disableFrames(turnMotor, 4, 6);

driveEncoder.setPosition(0);
this.angularOffset = Rotation2d.fromRadians(angularOffset);
Expand Down
Loading

0 comments on commit 360f8d6

Please sign in to comment.