From 1103ba8475c86f461b775a1fa7856cb7078b16fa Mon Sep 17 00:00:00 2001 From: Adam S Date: Wed, 22 Jun 2022 22:15:51 -0500 Subject: [PATCH 01/12] start work on the neo driver --- common | 2 +- .../java/frc/robot/drivers/NeoDriver.java | 39 +++++++++++++++++++ .../subsystems/SwerveDriveSubsystem.java | 2 +- .../frc/robot/threads/SwerveDriveThread.java | 25 ++++++++++++ 4 files changed, 66 insertions(+), 2 deletions(-) create mode 100644 src/main/java/frc/robot/drivers/NeoDriver.java create mode 100644 src/main/java/frc/robot/threads/SwerveDriveThread.java diff --git a/common b/common index 8c5893d..867b8b5 160000 --- a/common +++ b/common @@ -1 +1 @@ -Subproject commit 8c5893df5c6779e3803e6e458ff7f3051f74be71 +Subproject commit 867b8b5e9b78c610ee32ceaf783a814409ccc764 diff --git a/src/main/java/frc/robot/drivers/NeoDriver.java b/src/main/java/frc/robot/drivers/NeoDriver.java new file mode 100644 index 0000000..76fd945 --- /dev/null +++ b/src/main/java/frc/robot/drivers/NeoDriver.java @@ -0,0 +1,39 @@ +package frc.robot.drivers; + +import com.revrobotics.CANSparkMax; +import com.revrobotics.CANSparkMaxLowLevel.MotorType; +import com.revrobotics.RelativeEncoder; +import org.frc4607.common.swerve.SwerveMotorBase; + +/** + * Extends the {@link org.frc4607.common.swerve.SwerveMotorBase} for REV Neo brushless motors. + */ +public class NeoDriver extends SwerveMotorBase { + private final CANSparkMax m_motor; + private RelativeEncoder m_neoEncoder; + + public NeoDriver(int id) { + m_motor = new CANSparkMax(id, MotorType.kBrushless); + m_neoEncoder = m_motor.getEncoder(); + } + + public boolean isConnected() { + return m_motor.getFaults() == 0 && m_motor.getStickyFaults() == 0; + } + + public double getEncoderPosition() { + return m_neoEncoder.getPosition(); + } + + public double getEncoderVelocity() { + return m_neoEncoder.getVelocity(); + } + + public void setEncoder(double target) { + m_neoEncoder.setPosition(target); + } + + public void setTarget(double target) { + + } +} diff --git a/src/main/java/frc/robot/subsystems/SwerveDriveSubsystem.java b/src/main/java/frc/robot/subsystems/SwerveDriveSubsystem.java index 3bfa21f..b7f2ca7 100644 --- a/src/main/java/frc/robot/subsystems/SwerveDriveSubsystem.java +++ b/src/main/java/frc/robot/subsystems/SwerveDriveSubsystem.java @@ -7,7 +7,7 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase; /** - * Manages the drivetrain of the robot. + * Manages the drivetrain of the robot by talking to the thread containing the swerve drive handler. */ public class SwerveDriveSubsystem extends SubsystemBase { diff --git a/src/main/java/frc/robot/threads/SwerveDriveThread.java b/src/main/java/frc/robot/threads/SwerveDriveThread.java new file mode 100644 index 0000000..b9c5289 --- /dev/null +++ b/src/main/java/frc/robot/threads/SwerveDriveThread.java @@ -0,0 +1,25 @@ +package frc.robot.threads; + +import org.frc4607.common.swerve.SwerveDrive; + +/** + * Holds a {@link org.frc4607.common.swerve.SwerveDrive} in a separate thread from the main + * program and updates it. + */ +public class SwerveDriveThread implements Runnable { + private boolean m_initialized = false; + + private SwerveDrive m_drivetrain; + + private SwerveDriveThread() { + + } + + public void periodic() { + + } + + public void run() { + m_drivetrain = new SwerveDrive(modules) + } +} From c38f164bc899db4e5ea91b6fc56e10c5dbd985e4 Mon Sep 17 00:00:00 2001 From: Adam S Date: Sat, 25 Jun 2022 22:30:19 -0500 Subject: [PATCH 02/12] work on neo driver a bit more --- .../java/frc/robot/drivers/NeoDriver.java | 35 ++++++++++++++++--- 1 file changed, 31 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/drivers/NeoDriver.java b/src/main/java/frc/robot/drivers/NeoDriver.java index 76fd945..11b7f7a 100644 --- a/src/main/java/frc/robot/drivers/NeoDriver.java +++ b/src/main/java/frc/robot/drivers/NeoDriver.java @@ -1,8 +1,16 @@ package frc.robot.drivers; import com.revrobotics.CANSparkMax; -import com.revrobotics.CANSparkMaxLowLevel.MotorType; import com.revrobotics.RelativeEncoder; +import com.revrobotics.CANSparkMaxLowLevel.MotorType; +import com.revrobotics.SparkMaxPIDController.AccelStrategy; +import com.revrobotics.SparkMaxPIDController.ArbFFUnits; +import com.revrobotics.SparkMaxPIDController; +import com.revrobotics.CANSparkMax.ControlType; + +import edu.wpi.first.wpilibj.DutyCycleEncoder; +import edu.wpi.first.wpilibj.Encoder; +import org.frc4607.common.swerve.SwerveDriverConfig; import org.frc4607.common.swerve.SwerveMotorBase; /** @@ -10,11 +18,30 @@ */ public class NeoDriver extends SwerveMotorBase { private final CANSparkMax m_motor; - private RelativeEncoder m_neoEncoder; + private final RelativeEncoder m_neoEncoder; + private final SparkMaxPIDController m_pidController; + + /** + * Constructs a new instance of this class. + * + * @param config The settings for this module. + */ + public NeoDriver(SwerveDriverConfig config) { + super(config); + + m_motor = new CANSparkMax(m_config.m_id, MotorType.kBrushless); + m_motor.setInverted(m_config.m_invertMotor); - public NeoDriver(int id) { - m_motor = new CANSparkMax(id, MotorType.kBrushless); m_neoEncoder = m_motor.getEncoder(); + m_neoEncoder.setPositionConversionFactor(config.m_positionCoefficient); + m_neoEncoder.setVelocityConversionFactor(config.m_velocityCoefficient); + + m_pidController = m_motor.getPIDController(); + m_pidController.setP(m_config.m_kp, 0); + m_pidController.setI(m_config.m_ki, 0); + m_pidController.setD(m_config.m_kd, 0); + m_pidController.setIMaxAccum(m_config.m_maxI, 0); + m_pidController.setIZone(m_config.m_kiZone, 0); } public boolean isConnected() { From 17d469d7b3268bd0370fe117d7b030f12b62bdd6 Mon Sep 17 00:00:00 2001 From: Adam S Date: Mon, 27 Jun 2022 16:53:20 -0500 Subject: [PATCH 03/12] get a first draft of the neo driver done --- common | 2 +- .../java/frc/robot/drivers/NeoDriver.java | 32 ++++++++++++------- 2 files changed, 22 insertions(+), 12 deletions(-) diff --git a/common b/common index 867b8b5..2e90045 160000 --- a/common +++ b/common @@ -1 +1 @@ -Subproject commit 867b8b5e9b78c610ee32ceaf783a814409ccc764 +Subproject commit 2e9004538b5d85095f154fadd5554e2496346889 diff --git a/src/main/java/frc/robot/drivers/NeoDriver.java b/src/main/java/frc/robot/drivers/NeoDriver.java index 11b7f7a..0d089aa 100644 --- a/src/main/java/frc/robot/drivers/NeoDriver.java +++ b/src/main/java/frc/robot/drivers/NeoDriver.java @@ -1,15 +1,11 @@ package frc.robot.drivers; import com.revrobotics.CANSparkMax; -import com.revrobotics.RelativeEncoder; +import com.revrobotics.CANSparkMax.ControlType; import com.revrobotics.CANSparkMaxLowLevel.MotorType; -import com.revrobotics.SparkMaxPIDController.AccelStrategy; -import com.revrobotics.SparkMaxPIDController.ArbFFUnits; +import com.revrobotics.RelativeEncoder; import com.revrobotics.SparkMaxPIDController; -import com.revrobotics.CANSparkMax.ControlType; - -import edu.wpi.first.wpilibj.DutyCycleEncoder; -import edu.wpi.first.wpilibj.Encoder; +import com.revrobotics.SparkMaxPIDController.ArbFFUnits; import org.frc4607.common.swerve.SwerveDriverConfig; import org.frc4607.common.swerve.SwerveMotorBase; @@ -49,18 +45,32 @@ public boolean isConnected() { } public double getEncoderPosition() { - return m_neoEncoder.getPosition(); + if (m_config.m_motorType == SwerveDriverConfig.MotorType.TURNING) { + return m_quadEncoder.getDistance() + m_offset; + } else { + return m_neoEncoder.getPosition(); + } } public double getEncoderVelocity() { - return m_neoEncoder.getVelocity(); + if (m_config.m_motorType == SwerveDriverConfig.MotorType.TURNING) { + return m_quadEncoder.getRate(); + } else { + return m_neoEncoder.getVelocity(); + } } public void setEncoder(double target) { m_neoEncoder.setPosition(target); } - public void setTarget(double target) { - + public void setTarget(double target, double ffVolts) { + if (m_config.m_motorType == SwerveDriverConfig.MotorType.TURNING) { + m_pidController.setReference(target, + ControlType.kPosition, 0, ffVolts, ArbFFUnits.kVoltage); + } + else { + m_pidController.setReference(target, ControlType.kVelocity, 0, ffVolts, ArbFFUnits.kVoltage); + } } } From 0922577b6b686563ec5bd506669da515169ce0a3 Mon Sep 17 00:00:00 2001 From: Adam S Date: Mon, 27 Jun 2022 16:56:16 -0500 Subject: [PATCH 04/12] update target commit of common --- common | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common b/common index 2e90045..ce75f61 160000 --- a/common +++ b/common @@ -1 +1 @@ -Subproject commit 2e9004538b5d85095f154fadd5554e2496346889 +Subproject commit ce75f61321d6cc25915b507ef6785c536a582bc6 From d3db3cb4ec28e01464240f19e6d6b9bab6474c59 Mon Sep 17 00:00:00 2001 From: Adam S Date: Thu, 30 Jun 2022 13:47:58 -0500 Subject: [PATCH 05/12] pass code analysis --- common | 2 +- .../java/frc/robot/drivers/NeoDriver.java | 29 +++++++++++++++++-- .../frc/robot/threads/SwerveDriveThread.java | 11 ++----- 3 files changed, 30 insertions(+), 12 deletions(-) diff --git a/common b/common index ce75f61..b8a8ed3 160000 --- a/common +++ b/common @@ -1 +1 @@ -Subproject commit ce75f61321d6cc25915b507ef6785c536a582bc6 +Subproject commit b8a8ed3edad723ff314d746fbcb69843f30d89f4 diff --git a/src/main/java/frc/robot/drivers/NeoDriver.java b/src/main/java/frc/robot/drivers/NeoDriver.java index 0d089aa..7270cb1 100644 --- a/src/main/java/frc/robot/drivers/NeoDriver.java +++ b/src/main/java/frc/robot/drivers/NeoDriver.java @@ -40,10 +40,18 @@ public NeoDriver(SwerveDriverConfig config) { m_pidController.setIZone(m_config.m_kiZone, 0); } + @Override public boolean isConnected() { return m_motor.getFaults() == 0 && m_motor.getStickyFaults() == 0; } + /** + * Gets the position of the motor. + * + * @return The distance in meters if this is a drive motor or the rotation in CCW + postive degrees if this is a turning motor. + */ + @Override public double getEncoderPosition() { if (m_config.m_motorType == SwerveDriverConfig.MotorType.TURNING) { return m_quadEncoder.getDistance() + m_offset; @@ -52,6 +60,13 @@ public double getEncoderPosition() { } } + /** + * Gets the velocity of the motor. + * + * @return The velocity in meters per second if this is a drive motor or the velocity in CCW + postive degrees per second if this is a turning motor. + */ + @Override public double getEncoderVelocity() { if (m_config.m_motorType == SwerveDriverConfig.MotorType.TURNING) { return m_quadEncoder.getRate(); @@ -60,17 +75,25 @@ public double getEncoderVelocity() { } } + @Override public void setEncoder(double target) { m_neoEncoder.setPosition(target); } + /** + * Sets the target of the motor to a setpoint. + * + * @param target The target to set the motor to. Will be in meters per second for the drive + motor and degrees or the turning motor. + */ + @Override public void setTarget(double target, double ffVolts) { if (m_config.m_motorType == SwerveDriverConfig.MotorType.TURNING) { m_pidController.setReference(target, ControlType.kPosition, 0, ffVolts, ArbFFUnits.kVoltage); - } - else { - m_pidController.setReference(target, ControlType.kVelocity, 0, ffVolts, ArbFFUnits.kVoltage); + } else { + m_pidController.setReference(target, + ControlType.kVelocity, 0, ffVolts, ArbFFUnits.kVoltage); } } } diff --git a/src/main/java/frc/robot/threads/SwerveDriveThread.java b/src/main/java/frc/robot/threads/SwerveDriveThread.java index b9c5289..51a92c5 100644 --- a/src/main/java/frc/robot/threads/SwerveDriveThread.java +++ b/src/main/java/frc/robot/threads/SwerveDriveThread.java @@ -1,11 +1,6 @@ -package frc.robot.threads; +/*package frc.robot.threads; import org.frc4607.common.swerve.SwerveDrive; - -/** - * Holds a {@link org.frc4607.common.swerve.SwerveDrive} in a separate thread from the main - * program and updates it. - */ public class SwerveDriveThread implements Runnable { private boolean m_initialized = false; @@ -20,6 +15,6 @@ public void periodic() { } public void run() { - m_drivetrain = new SwerveDrive(modules) + } -} +}*/ From f5de38c1b0c5c110de0a26e7bfb41357622e198a Mon Sep 17 00:00:00 2001 From: Adam S Date: Mon, 4 Jul 2022 18:22:05 -0500 Subject: [PATCH 06/12] update target commit of common library --- common | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common b/common index b8a8ed3..27f3b2a 160000 --- a/common +++ b/common @@ -1 +1 @@ -Subproject commit b8a8ed3edad723ff314d746fbcb69843f30d89f4 +Subproject commit 27f3b2ad2c22286b1776f2d75bfeaa633929e9fb From 89fedadb8afcc78365367a950ef86d33d34892ee Mon Sep 17 00:00:00 2001 From: Adam S Date: Mon, 17 Oct 2022 21:41:01 -0500 Subject: [PATCH 07/12] update target commit of common library --- common | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common b/common index 27f3b2a..1af7479 160000 --- a/common +++ b/common @@ -1 +1 @@ -Subproject commit 27f3b2ad2c22286b1776f2d75bfeaa633929e9fb +Subproject commit 1af7479c80dbd5e5e4b8b5f13c3febb17af6534d From 2209e7a1f3ee8781196545e9c43079ce05c33d5d Mon Sep 17 00:00:00 2001 From: Adam Sura Date: Tue, 18 Oct 2022 17:11:54 -0500 Subject: [PATCH 08/12] update spotbugs to fix assertion errors --- build.gradle | 2 +- common | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/build.gradle b/build.gradle index 616c6af..67ea788 100644 --- a/build.gradle +++ b/build.gradle @@ -1,7 +1,7 @@ plugins { id "java" id "edu.wpi.first.GradleRIO" version "2022.4.1" - id "com.github.spotbugs" version "5.0.8" + id "com.github.spotbugs" version "5.0.12" id "net.ltgt.errorprone" version "2.0.2" id "pmd" id 'checkstyle' diff --git a/common b/common index 1af7479..1c0a650 160000 --- a/common +++ b/common @@ -1 +1 @@ -Subproject commit 1af7479c80dbd5e5e4b8b5f13c3febb17af6534d +Subproject commit 1c0a650967fcd41e83f510deb51519a898e7759f From 54db988e9f1a4b089385e1a0d98d943ad1afb33c Mon Sep 17 00:00:00 2001 From: Adam Sura Date: Tue, 18 Oct 2022 19:58:48 -0500 Subject: [PATCH 09/12] work on robot side of swerve --- common | 2 +- src/main/java/frc/robot/Constants.java | 5 +++ src/main/java/frc/robot/commands/TeleOp.java | 17 +++++++++ .../java/frc/robot/drivers/NeoDriver.java | 2 + .../subsystems/SwerveDriveSubsystem.java | 28 ++++++++++++-- .../frc/robot/threads/SwerveDriveThread.java | 37 +++++++++++++++---- 6 files changed, 80 insertions(+), 11 deletions(-) create mode 100644 src/main/java/frc/robot/commands/TeleOp.java diff --git a/common b/common index 1c0a650..0cdc3fe 160000 --- a/common +++ b/common @@ -1 +1 @@ -Subproject commit 1c0a650967fcd41e83f510deb51519a898e7759f +Subproject commit 0cdc3feee132290b301e3ca4cf025e302eb4b7da diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 4bf01fc..7c83499 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -4,6 +4,8 @@ package frc.robot; +import org.frc4607.common.swerve.SwerveDriverConfig; + /** * The Constants class provides a convenient place for teams to hold robot-wide * numerical or boolean @@ -16,4 +18,7 @@ * constants are needed, to reduce verbosity. */ public final class Constants { + public static void getFrontLeftConfig() { + SwerveDriverConfig c = new SwerveDriverConfig(); + } } diff --git a/src/main/java/frc/robot/commands/TeleOp.java b/src/main/java/frc/robot/commands/TeleOp.java new file mode 100644 index 0000000..e580797 --- /dev/null +++ b/src/main/java/frc/robot/commands/TeleOp.java @@ -0,0 +1,17 @@ +package frc.robot.commands; + +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.subsystems.SwerveDriveSubsystem; + +/** + * Default command for the drivetrain that updates it from the controller. + */ +public class TeleOp extends CommandBase { + private final SwerveDriveSubsystem m_subsystem; + + public TeleOp(SwerveDriveSubsystem subsystem) { + m_subsystem = subsystem; + addRequirements(m_subsystem); + } + +} diff --git a/src/main/java/frc/robot/drivers/NeoDriver.java b/src/main/java/frc/robot/drivers/NeoDriver.java index 7270cb1..9d6c508 100644 --- a/src/main/java/frc/robot/drivers/NeoDriver.java +++ b/src/main/java/frc/robot/drivers/NeoDriver.java @@ -26,6 +26,8 @@ public NeoDriver(SwerveDriverConfig config) { super(config); m_motor = new CANSparkMax(m_config.m_id, MotorType.kBrushless); + m_motor.clearFaults(); + m_motor.setInverted(m_config.m_invertMotor); m_neoEncoder = m_motor.getEncoder(); diff --git a/src/main/java/frc/robot/subsystems/SwerveDriveSubsystem.java b/src/main/java/frc/robot/subsystems/SwerveDriveSubsystem.java index b7f2ca7..8aa41e1 100644 --- a/src/main/java/frc/robot/subsystems/SwerveDriveSubsystem.java +++ b/src/main/java/frc/robot/subsystems/SwerveDriveSubsystem.java @@ -4,16 +4,38 @@ package frc.robot.subsystems; +import edu.wpi.first.math.kinematics.ChassisSpeeds; +import edu.wpi.first.wpilibj.Notifier; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.threads.SwerveDriveThread; +import org.frc4607.common.swerve.SwerveDrive; /** * Manages the drivetrain of the robot by talking to the thread containing the swerve drive handler. */ public class SwerveDriveSubsystem extends SubsystemBase { - @Override - public void periodic() { - // This method will be called once per scheduler run + private final SwerveDriveThread m_thread; + private final Notifier m_notifier; + + /** + * Creates a new object and sets up the thread it uses. + + * @param swerveDrive The {@link org.frc4607.common.swerve.SwerveDrive} to operate on. + */ + public SwerveDriveSubsystem(SwerveDrive swerveDrive) { + m_thread = new SwerveDriveThread(swerveDrive); + m_notifier = new Notifier(m_thread); + m_notifier.startPeriodic(0.001); + } + + /** + * Sets the target {@link edu.wpi.first.math.kinematics.ChassisSpeeds} of the robot. + + * @param target The speeds for the drivetrain to target. + */ + public void setSpeeds(ChassisSpeeds target) { + m_thread.setSpeeds(target); } @Override diff --git a/src/main/java/frc/robot/threads/SwerveDriveThread.java b/src/main/java/frc/robot/threads/SwerveDriveThread.java index 51a92c5..2639e07 100644 --- a/src/main/java/frc/robot/threads/SwerveDriveThread.java +++ b/src/main/java/frc/robot/threads/SwerveDriveThread.java @@ -1,20 +1,43 @@ -/*package frc.robot.threads; +package frc.robot.threads; +import edu.wpi.first.math.kinematics.ChassisSpeeds; import org.frc4607.common.swerve.SwerveDrive; + +/** + * A class representing a separate thread running the swerve drive controller at a higher update + * rate than the main loop. Methods in this class should be thread safe. + */ public class SwerveDriveThread implements Runnable { - private boolean m_initialized = false; + private final SwerveDrive m_drivetrain; - private SwerveDrive m_drivetrain; + private volatile ChassisSpeeds m_lastSpeed = new ChassisSpeeds(0, 0, 0); + private final Object m_lastSpeedLock = new Object(); - private SwerveDriveThread() { + public SwerveDriveThread(SwerveDrive drive) { + m_drivetrain = drive; + } + private void periodic() { + synchronized (m_lastSpeedLock) { + m_drivetrain.update(m_lastSpeed); + } } - public void periodic() { + /** + * Sets the target {@link edu.wpi.first.math.kinematics.ChassisSpeeds} of the robot. + * @param target The speeds for the drivetrain to target. + */ + public void setSpeeds(ChassisSpeeds target) { + synchronized (m_lastSpeedLock) { + m_lastSpeed = target; + } } + /** + * Runs the periodic loop of the object. + */ public void run() { - + periodic(); } -}*/ +} From 5f42d8c6ba56d6b3a72b91fe778820e7b3e23ba9 Mon Sep 17 00:00:00 2001 From: Adam S Date: Sun, 11 Dec 2022 17:35:40 -0600 Subject: [PATCH 10/12] fix spotbugs due to failing assertError checks fix rebase error in build.gradle --- build.gradle | 2 +- common | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/build.gradle b/build.gradle index 67ea788..fa3d961 100644 --- a/build.gradle +++ b/build.gradle @@ -1,7 +1,7 @@ plugins { id "java" id "edu.wpi.first.GradleRIO" version "2022.4.1" - id "com.github.spotbugs" version "5.0.12" + id "com.github.spotbugs" version "5.0.13" id "net.ltgt.errorprone" version "2.0.2" id "pmd" id 'checkstyle' diff --git a/common b/common index 0cdc3fe..1de8b98 160000 --- a/common +++ b/common @@ -1 +1 @@ -Subproject commit 0cdc3feee132290b301e3ca4cf025e302eb4b7da +Subproject commit 1de8b98bf1bed6f0d02d34043b41cb698ac6b517 From fb373af9ca29f4912562c352648a9b867ccee072 Mon Sep 17 00:00:00 2001 From: Adam S Date: Sun, 11 Dec 2022 17:50:42 -0600 Subject: [PATCH 11/12] update targeted common library version --- common | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common b/common index 1de8b98..54ecfd0 160000 --- a/common +++ b/common @@ -1 +1 @@ -Subproject commit 1de8b98bf1bed6f0d02d34043b41cb698ac6b517 +Subproject commit 54ecfd0a9cb9a449ac8c21aa545639c2a7ea22fd From 7f295bf87f0b66b133fbf0cb8bad30a0923b203d Mon Sep 17 00:00:00 2001 From: Adam S Date: Sun, 11 Dec 2022 21:09:02 -0600 Subject: [PATCH 12/12] update target common library commit --- common | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common b/common index 54ecfd0..9cdd4e8 160000 --- a/common +++ b/common @@ -1 +1 @@ -Subproject commit 54ecfd0a9cb9a449ac8c21aa545639c2a7ea22fd +Subproject commit 9cdd4e8288657d97792ede16f7f98ada38272737