Skip to content
This repository was archived by the owner on May 19, 2024. It is now read-only.

Commit 2dd37bb

Browse files
committed
chore: Format.
1 parent d2fdf81 commit 2dd37bb

File tree

5 files changed

+8
-13
lines changed

5 files changed

+8
-13
lines changed

src/main/java/frc/robot/arm/Arm.java

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,5 @@
11
package frc.robot.arm;
22

3-
import java.util.function.DoubleSupplier;
4-
53
import edu.wpi.first.math.trajectory.TrapezoidProfile;
64
import edu.wpi.first.math.trajectory.TrapezoidProfile.State;
75
import edu.wpi.first.math.util.Units;
@@ -12,6 +10,7 @@
1210
import frc.lib.Subsystem;
1311
import frc.lib.Telemetry;
1412
import frc.robot.arm.ShoulderMotorIO.ShoulderMotorIOValues;
13+
import java.util.function.DoubleSupplier;
1514

1615
/** Subsystem class for the arm subsystem. */
1716
public class Arm extends Subsystem {
Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
11
package frc.robot.arm;
22

33
/** Constants for the arm subsystem. */
4-
public class ArmConstants {}
4+
public class ArmConstants {}

src/main/java/frc/robot/arm/ShoulderMotorIOTalonFX.java

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,6 @@
44
import com.ctre.phoenix6.hardware.TalonFX;
55
import com.ctre.phoenix6.signals.InvertedValue;
66
import com.ctre.phoenix6.signals.NeutralModeValue;
7-
87
import edu.wpi.first.math.controller.ArmFeedforward;
98
import edu.wpi.first.math.controller.PIDController;
109
import edu.wpi.first.math.util.Units;
@@ -50,7 +49,8 @@ public void configure() {
5049
public void update(ShoulderMotorIOValues values) {
5150
values.positionRotations = getAbsolutePositionRotations();
5251
values.velocityRotationsPerSecond = westTalonFX.getVelocity().refresh().getValue();
53-
values.accelerationRotationsPerSecondPerSecond = westTalonFX.getAcceleration().refresh().getValue();
52+
values.accelerationRotationsPerSecondPerSecond =
53+
westTalonFX.getAcceleration().refresh().getValue();
5454

5555
values.currentAmps = westTalonFX.getStatorCurrent().refresh().getValue();
5656
values.inputVoltage = westTalonFX.getMotorVoltage().refresh().getValue();
@@ -69,7 +69,8 @@ public void setSetpoint(double positionRotations, double velocityRotationsPerSec
6969
double feedbackVolts = feedback.calculate(measuredPositionRotations, positionRotations);
7070

7171
double feedforwardVolts =
72-
feedforward.calculate(Units.rotationsToRadians(measuredPositionRotations), velocityRotationsPerSecond);
72+
feedforward.calculate(
73+
Units.rotationsToRadians(measuredPositionRotations), velocityRotationsPerSecond);
7374

7475
setVoltage(feedbackVolts + feedforwardVolts);
7576
}

src/main/java/frc/robot/intake/RollerMotorIOTalonFX.java

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,16 +1,15 @@
11
package frc.robot.intake;
22

3-
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
43
import com.ctre.phoenix6.configs.TalonFXConfiguration;
54
import com.ctre.phoenix6.hardware.TalonFX;
65
import com.ctre.phoenix6.signals.NeutralModeValue;
6+
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
77
import frc.lib.Configurator;
88

99
/** Roller motor using a TalonFX. */
1010
public class RollerMotorIOTalonFX implements RollerMotorIO {
1111

1212
private final TalonFX topTalonFX, bottomTalonFX;
13-
1413
private final SimpleMotorFeedforward topFeedforward, bottomFeedforward;
1514

1615
public RollerMotorIOTalonFX() {

src/main/java/frc/robot/superstructure/SuperstructureMechanism.java

Lines changed: 1 addition & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -78,11 +78,7 @@ private SuperstructureMechanism() {
7878
shoulder =
7979
shoulderBase.append(
8080
new MechanismLigament2d(
81-
"shoulder",
82-
Units.inchesToMeters(16.775),
83-
0,
84-
armThickness,
85-
DEFAULT_COLOR));
81+
"shoulder", Units.inchesToMeters(16.775), 0, armThickness, DEFAULT_COLOR));
8682

8783
flywheel =
8884
shoulder.append(

0 commit comments

Comments
 (0)