From 6985233eb2306b34c98f3ca22e8001e28ce00cb3 Mon Sep 17 00:00:00 2001 From: Evan Pratten Date: Mon, 11 Jan 2021 17:16:07 -0500 Subject: [PATCH] failing tests --- gradle5k/gradle5k.gradle | 4 ++-- .../bases/drivetrain/AbstractDriveTrain.java | 4 ++-- .../control_loops/models/DCBrushedMotor.java | 16 ++++++++-------- 3 files changed, 12 insertions(+), 12 deletions(-) diff --git a/gradle5k/gradle5k.gradle b/gradle5k/gradle5k.gradle index aadfed7c8..d327bf701 100644 --- a/gradle5k/gradle5k.gradle +++ b/gradle5k/gradle5k.gradle @@ -17,7 +17,7 @@ def versions = [ // Core FRC libraries // Using a "+" here will allow you to use beta versions of libraries - wpilib: "2021.1.1-alpha-1" // See: https://github.com/wpilibsuite/allwpilib/releases + wpilib: "2021.1.2" // See: https://github.com/wpilibsuite/allwpilib/releases // ctre "5.+" // See: http://devsite.ctr-electronics.com/maven/release/com/ctre/phoenix/wpiapi-java/ // navx "3.+" // See: https://www.kauailabs.com/dist/frc/2020/navx_frc.json (Check ["javaDependencies"][0]["version"]) // rev_color "1.+" // See: https://github.com/REVrobotics/Color-Sensor-v3/releases @@ -139,4 +139,4 @@ tasks.withType(Test) { } } } -} \ No newline at end of file +} diff --git a/lib5k/src/main/java/io/github/frc5024/lib5k/bases/drivetrain/AbstractDriveTrain.java b/lib5k/src/main/java/io/github/frc5024/lib5k/bases/drivetrain/AbstractDriveTrain.java index 53824c3ad..b7121734c 100644 --- a/lib5k/src/main/java/io/github/frc5024/lib5k/bases/drivetrain/AbstractDriveTrain.java +++ b/lib5k/src/main/java/io/github/frc5024/lib5k/bases/drivetrain/AbstractDriveTrain.java @@ -3,7 +3,7 @@ import edu.wpi.first.wpilibj.geometry.Pose2d; import edu.wpi.first.wpilibj.geometry.Rotation2d; import edu.wpi.first.wpilibj.geometry.Translation2d; -import edu.wpi.first.wpilibj.simulation.Field2d; +import edu.wpi.first.wpilibj.smartdashboard.Field2d; import edu.wpi.first.wpilibj2.command.SubsystemBase; import io.github.frc5024.common_drive.gearing.Gear; import io.github.frc5024.lib5k.bases.drivetrain.commands.PathFollowerCommand; @@ -283,4 +283,4 @@ public void close() throws Exception { } -} \ No newline at end of file +} diff --git a/lib5k/src/main/java/io/github/frc5024/lib5k/control_loops/models/DCBrushedMotor.java b/lib5k/src/main/java/io/github/frc5024/lib5k/control_loops/models/DCBrushedMotor.java index 622206695..7a5c0b6bf 100644 --- a/lib5k/src/main/java/io/github/frc5024/lib5k/control_loops/models/DCBrushedMotor.java +++ b/lib5k/src/main/java/io/github/frc5024/lib5k/control_loops/models/DCBrushedMotor.java @@ -25,11 +25,11 @@ public class DCBrushedMotor extends DCMotor { */ private DCBrushedMotor(double nominalVoltage, double stallTorque, double stallCurrent, double freeCurrent, double freeSpeed) { - super(nominalVoltage, stallCurrent, stallCurrent, freeCurrent, freeSpeed); + super(nominalVoltage, stallTorque, stallCurrent, freeCurrent, freeSpeed, 1); // Add a few extra fields - this.Kv = Units.radiansPerSecondToRotationsPerMinute(super.m_KvRadPerSecPerVolt); - this.freeSpeedRPM = Units.radiansPerSecondToRotationsPerMinute(super.m_freeSpeedRadPerSec); + this.Kv = Units.radiansPerSecondToRotationsPerMinute(super.KvRadPerSecPerVolt); + this.freeSpeedRPM = Units.radiansPerSecondToRotationsPerMinute(super.freeSpeedRadPerSec); } @@ -38,8 +38,8 @@ private DCBrushedMotor(double nominalVoltage, double stallTorque, double stallCu * @param motor DCMotor */ public DCBrushedMotor(DCMotor motor) { - this(motor.m_nominalVoltageVolts, motor.m_stallTorqueNewtonMeters, motor.m_stallCurrentAmps, - motor.m_freeCurrentAmps, motor.m_freeSpeedRadPerSec); + this(motor.nominalVoltageVolts, motor.stallTorqueNewtonMeters, motor.stallCurrentAmps, + motor.freeCurrentAmps, motor.freeSpeedRadPerSec); } /** @@ -49,7 +49,7 @@ public DCBrushedMotor(DCMotor motor) { */ public double getFreeSpeedRPM() { if (this.freeSpeedRPM == null) { - this.freeSpeedRPM = Units.radiansPerSecondToRotationsPerMinute(super.m_freeSpeedRadPerSec); + this.freeSpeedRPM = Units.radiansPerSecondToRotationsPerMinute(super.freeSpeedRadPerSec); } return this.freeSpeedRPM.doubleValue(); } @@ -61,7 +61,7 @@ public double getFreeSpeedRPM() { */ public double getKv() { if (this.Kv == null) { - this.Kv = Units.radiansPerSecondToRotationsPerMinute(super.m_KvRadPerSecPerVolt); + this.Kv = Units.radiansPerSecondToRotationsPerMinute(super.KvRadPerSecPerVolt); } return this.Kv.doubleValue(); } @@ -75,4 +75,4 @@ public DCMotor toDCMotor() { return (DCMotor) this; } -} \ No newline at end of file +}