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

Commit b019ae8

Browse files
committed
refactor(swerve): Use generic velocity controller.
1 parent 5b9c574 commit b019ae8

15 files changed

+60
-333
lines changed

Diff for: src/main/java/frc/lib/controller/PositionControllerIO.java

+4-8
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,5 @@
11
package frc.lib.controller;
22

3-
import edu.wpi.first.math.util.Units;
43
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
54
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
65
import frc.lib.Telemetry;
@@ -37,13 +36,10 @@ public static void addToShuffleboard(
3736
ShuffleboardTab tab, String name, PositionControllerIOValues values) {
3837
ShuffleboardLayout positionController = Telemetry.addColumn(tab, name);
3938

39+
positionController.addDouble("Position (rot)", () -> values.positionRotations);
40+
positionController.addDouble("Velocity (rps)", () -> values.velocityRotationsPerSecond);
4041
positionController.addDouble(
41-
"Position (deg)", () -> Units.rotationsToDegrees(values.positionRotations));
42-
positionController.addDouble(
43-
"Velocity (dps)", () -> Units.rotationsToDegrees(values.velocityRotationsPerSecond));
44-
positionController.addDouble(
45-
"Acceleration (dpsps)",
46-
() -> Units.rotationsToDegrees(values.accelerationRotationsPerSecondPerSecond));
42+
"Acceleration (rpsps)", () -> values.accelerationRotationsPerSecondPerSecond);
4743
positionController.addDouble("Voltage (V)", () -> values.motorVolts);
4844
positionController.addDouble("Current (A)", () -> values.motorAmps);
4945
}
@@ -63,7 +59,7 @@ public static void addToShuffleboard(
6359
public void update(PositionControllerIOValues values);
6460

6561
/**
66-
* Sets the mechanism position.
62+
* Sets the position controller position.
6763
*
6864
* @param positionRotations
6965
*/

Diff for: src/main/java/frc/lib/controller/VelocityControllerIO.java

+11-9
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,5 @@
11
package frc.lib.controller;
22

3-
import edu.wpi.first.math.util.Units;
43
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
54
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
65
import frc.lib.Telemetry;
@@ -10,6 +9,9 @@ public interface VelocityControllerIO {
109

1110
/** Velocity controller values. */
1211
public static class VelocityControllerIOValues {
12+
/** Position in rotations. */
13+
public double positionRotations = 0.0;
14+
1315
/** Velocity in rotations per second. */
1416
public double velocityRotationsPerSecond = 0.0;
1517

@@ -34,17 +36,10 @@ public static void addToShuffleboard(
3436
ShuffleboardTab tab, String name, VelocityControllerIOValues values) {
3537
ShuffleboardLayout velocityController = Telemetry.addColumn(tab, name);
3638

37-
velocityController.addDouble(
38-
"Velocity (dps)", () -> Units.rotationsToDegrees(values.velocityRotationsPerSecond));
39-
velocityController.addDouble(
40-
"Acceleration (dpsps)",
41-
() -> Units.rotationsToDegrees(values.accelerationRotationsPerSecondPerSecond));
39+
velocityController.addDouble("Position (rot)", () -> values.positionRotations);
4240
velocityController.addDouble("Velocity (rps)", () -> values.velocityRotationsPerSecond);
4341
velocityController.addDouble(
4442
"Acceleration (rpsps)", () -> values.accelerationRotationsPerSecondPerSecond);
45-
velocityController.addDouble("Velocity (rpm)", () -> values.velocityRotationsPerSecond * 60);
46-
velocityController.addDouble(
47-
"Acceleration (rpmpm)", () -> values.accelerationRotationsPerSecondPerSecond * 60);
4843
velocityController.addDouble("Voltage (V)", () -> values.motorVolts);
4944
velocityController.addDouble("Current (A)", () -> values.motorAmps);
5045
}
@@ -63,6 +58,13 @@ public static void addToShuffleboard(
6358
*/
6459
public void update(VelocityControllerIOValues values);
6560

61+
/**
62+
* Sets the velocity controller position.
63+
*
64+
* @param positionRotations
65+
*/
66+
public void setPosition(double positionRotations);
67+
6668
/**
6769
* Sets the velocity setpoint.
6870
*

Diff for: src/main/java/frc/lib/controller/VelocityControllerIOSim.java

+12
Original file line numberDiff line numberDiff line change
@@ -1,18 +1,30 @@
11
package frc.lib.controller;
22

3+
import frc.robot.RobotConstants;
4+
35
/** Simulated velocity controller. */
46
public class VelocityControllerIOSim implements VelocityControllerIO {
57

8+
private double positionRotations = 0.0;
9+
610
private double velocityRotationsPerSecond = 0.0;
711

812
@Override
913
public void configure() {}
1014

1115
@Override
1216
public void update(VelocityControllerIOValues values) {
17+
positionRotations += velocityRotationsPerSecond * RobotConstants.PERIODIC_DURATION;
18+
19+
values.positionRotations = positionRotations;
1320
values.velocityRotationsPerSecond = velocityRotationsPerSecond;
1421
}
1522

23+
@Override
24+
public void setPosition(double positionRotations) {
25+
this.positionRotations = positionRotations;
26+
}
27+
1628
@Override
1729
public void setSetpoint(double velocityRotationsPerSecond) {
1830
this.velocityRotationsPerSecond = velocityRotationsPerSecond;

Diff for: src/main/java/frc/lib/controller/VelocityControllerIOTalonFX.java

+10-3
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@ public abstract class VelocityControllerIOTalonFX implements VelocityControllerI
1515

1616
protected final TalonFX motor;
1717

18-
protected final StatusSignal<Double> velocity, acceleration, volts, amps;
18+
protected final StatusSignal<Double> position, velocity, acceleration, volts, amps;
1919

2020
/**
2121
* Creates a new velocity controller using TalonFX.
@@ -27,6 +27,7 @@ protected VelocityControllerIOTalonFX(CAN can, MechanismConfig config) {
2727

2828
motor = new TalonFX(can.id(), can.bus());
2929

30+
position = motor.getPosition();
3031
velocity = motor.getVelocity();
3132
acceleration = motor.getAcceleration();
3233
volts = motor.getMotorVoltage();
@@ -35,7 +36,7 @@ protected VelocityControllerIOTalonFX(CAN can, MechanismConfig config) {
3536

3637
@Override
3738
public void configure() {
38-
BaseStatusSignal.setUpdateFrequencyForAll(100.0, velocity, acceleration, volts, amps);
39+
BaseStatusSignal.setUpdateFrequencyForAll(100.0, position, velocity, acceleration, volts, amps);
3940

4041
ParentDevice.optimizeBusUtilizationForAll(motor);
4142

@@ -45,14 +46,20 @@ public void configure() {
4546

4647
@Override
4748
public void update(VelocityControllerIOValues values) {
48-
BaseStatusSignal.refreshAll(velocity, acceleration, volts, amps);
49+
BaseStatusSignal.refreshAll(position, velocity, acceleration, volts, amps);
4950

51+
values.positionRotations = position.getValue();
5052
values.velocityRotationsPerSecond = velocity.getValue();
5153
values.accelerationRotationsPerSecondPerSecond = acceleration.getValue();
5254
values.motorVolts = volts.getValue();
5355
values.motorAmps = amps.getValue();
5456
}
5557

58+
@Override
59+
public void setPosition(double positionRotations) {
60+
motor.setPosition(positionRotations);
61+
}
62+
5663
@Override
5764
public abstract void setSetpoint(double velocityRotationsPerSecond);
5865
}

Diff for: src/main/java/frc/robot/Robot.java

-13
Original file line numberDiff line numberDiff line change
@@ -3,24 +3,15 @@
33
import edu.wpi.first.wpilibj.TimedRobot;
44
import edu.wpi.first.wpilibj2.command.Command;
55
import edu.wpi.first.wpilibj2.command.CommandScheduler;
6-
import edu.wpi.first.wpilibj2.command.Commands;
7-
import edu.wpi.first.wpilibj2.command.button.Trigger;
8-
import frc.robot.swerve.Swerve;
96

107
public class Robot extends TimedRobot {
118
private Command autonomousCommand;
129

1310
private RobotContainer robotContainer;
14-
private Swerve swerve;
1511

1612
@Override
1713
public void robotInit() {
1814
robotContainer = RobotContainer.getInstance();
19-
swerve = Swerve.getInstance();
20-
21-
new Trigger(this::isDisabled)
22-
.debounce(RobotConstants.DISABLE_COAST_DELAY)
23-
.onTrue(Commands.runOnce(() -> swerve.setBrake(false), swerve).ignoringDisable(true));
2415
}
2516

2617
@Override
@@ -39,8 +30,6 @@ public void disabledExit() {}
3930

4031
@Override
4132
public void autonomousInit() {
42-
swerve.setBrake(true);
43-
4433
autonomousCommand = robotContainer.getAutonomousCommand();
4534

4635
if (autonomousCommand != null) {
@@ -56,8 +45,6 @@ public void autonomousExit() {}
5645

5746
@Override
5847
public void teleopInit() {
59-
swerve.setBrake(true);
60-
6148
if (autonomousCommand != null) {
6249
autonomousCommand.cancel();
6350
}

Diff for: src/main/java/frc/robot/RobotConstants.java

-6
Original file line numberDiff line numberDiff line change
@@ -16,12 +16,6 @@ public class RobotConstants {
1616
/** Voltage of the robot's battery, */
1717
public static final double BATTERY_VOLTAGE = 12.0;
1818

19-
/**
20-
* Duration between the robot being disabled and the swerve subsystem is allowed to coast in
21-
* seconds.
22-
*/
23-
public static final double DISABLE_COAST_DELAY = 3.0;
24-
2519
/** Distance from the frame perimeter to the origin in meters. */
2620
public static final double FRAME_PERIMETER_TO_ORIGIN_DISTANCE = Units.inchesToMeters(14);
2721

Diff for: src/main/java/frc/robot/swerve/DriveMotorIO.java

-45
This file was deleted.

Diff for: src/main/java/frc/robot/swerve/DriveMotorIOSim.java

-37
This file was deleted.

Diff for: src/main/java/frc/robot/swerve/DriveMotorIOTalonFX.java

-75
This file was deleted.

0 commit comments

Comments
 (0)