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

Commit 8e56beb

Browse files
committed
chore: Format.
1 parent edf8abf commit 8e56beb

24 files changed

+546
-500
lines changed

src/main/java/frc/lib/controller/PositionControllerIO.java

Lines changed: 84 additions & 79 deletions
Original file line numberDiff line numberDiff line change
@@ -7,85 +7,90 @@
77
/** Position controller interface. */
88
public interface PositionControllerIO {
99

10-
/** Position controller constants. */
11-
public static class PositionControllerIOConstants {
12-
/** Interpret counterclockwise rotation on the motor face as having positive velocity, if set to true. */
13-
public boolean ccwPositive = true;
14-
15-
/** Use the motor to brake the controlled mechanism on neutral output, if set to true. */
16-
public boolean neutralBrake = false;
17-
18-
/** Maximum amount of current, in amps, to provide to the motor. */
19-
public double currentLimitAmps = 40.0;
20-
21-
/** Ratio between the position sensor and the controlled mechanism. */
22-
public double sensorToMechanismRatio = 1.0;
23-
24-
/** Offset between absolute encoder reading and controlled mechanism position in rotations. */
25-
public double absoluteEncoderOffsetRotations = 0.0;
26-
}
27-
28-
/** Position controller values. */
29-
public static class PositionControllerIOValues {
30-
/** Position in rotations. */
31-
public double positionRotations = 0.0;
32-
33-
/** Velocity in rotations per second. */
34-
public double velocityRotationsPerSecond = 0.0;
35-
36-
/** Acceleration in rotations per second per second. */
37-
public double accelerationRotationsPerSecondPerSecond = 0.0;
38-
39-
/** Motor voltage in volts. */
40-
public double motorVolts = 0.0;
41-
42-
/** Motor current in amps. */
43-
public double motorAmps = 0.0;
44-
}
45-
46-
/**
47-
* Adds position controller values to Shuffleboard.
48-
*
49-
* @param tab
50-
* @param name
51-
* @param values
52-
*/
53-
public static void addToShuffleboard(ShuffleboardTab tab, String name, PositionControllerIOValues values) {
54-
ShuffleboardLayout positionController = Telemetry.addColumn(tab, name);
55-
56-
positionController.addDouble("Position (rot)", () -> values.positionRotations);
57-
positionController.addDouble("Velocity (rps)", () -> values.velocityRotationsPerSecond);
58-
positionController.addDouble("Acceleration (rpsps)", () -> values.accelerationRotationsPerSecondPerSecond);
59-
positionController.addDouble("Voltage (V)", () -> values.motorVolts);
60-
positionController.addDouble("Current (A)", () -> values.motorAmps);
61-
}
62-
63-
/**
64-
* Configures the position controller.
65-
*
66-
* @param constants
67-
*/
68-
public void configure(PositionControllerIOConstants constants);
69-
70-
/**
71-
* Updates the position controller's values.
72-
*
73-
* @param values
74-
*/
75-
public void update(PositionControllerIOValues values);
76-
77-
/**
78-
* Sets the mechanism position.
79-
*
80-
* @param positionRotations
81-
*/
82-
public void setPosition(double positionRotations);
83-
10+
/** Position controller constants. */
11+
public static class PositionControllerIOConstants {
8412
/**
85-
* Sets the position setpoint.
86-
*
87-
* @param positionRotations
88-
* @param velocityRotationsPerSecond
13+
* Interpret counterclockwise rotation on the motor face as having positive velocity, if set to
14+
* true.
8915
*/
90-
public void setSetpoint(double positionRotations, double velocityRotationsPerSecond);
16+
public boolean ccwPositive = true;
17+
18+
/** Use the motor to brake the controlled mechanism on neutral output, if set to true. */
19+
public boolean neutralBrake = false;
20+
21+
/** Maximum amount of current, in amps, to provide to the motor. */
22+
public double currentLimitAmps = 40.0;
23+
24+
/** Ratio between the position sensor and the controlled mechanism. */
25+
public double sensorToMechanismRatio = 1.0;
26+
27+
/** Offset between absolute encoder reading and controlled mechanism position in rotations. */
28+
public double absoluteEncoderOffsetRotations = 0.0;
29+
}
30+
31+
/** Position controller values. */
32+
public static class PositionControllerIOValues {
33+
/** Position in rotations. */
34+
public double positionRotations = 0.0;
35+
36+
/** Velocity in rotations per second. */
37+
public double velocityRotationsPerSecond = 0.0;
38+
39+
/** Acceleration in rotations per second per second. */
40+
public double accelerationRotationsPerSecondPerSecond = 0.0;
41+
42+
/** Motor voltage in volts. */
43+
public double motorVolts = 0.0;
44+
45+
/** Motor current in amps. */
46+
public double motorAmps = 0.0;
47+
}
48+
49+
/**
50+
* Adds position controller values to Shuffleboard.
51+
*
52+
* @param tab
53+
* @param name
54+
* @param values
55+
*/
56+
public static void addToShuffleboard(
57+
ShuffleboardTab tab, String name, PositionControllerIOValues values) {
58+
ShuffleboardLayout positionController = Telemetry.addColumn(tab, name);
59+
60+
positionController.addDouble("Position (rot)", () -> values.positionRotations);
61+
positionController.addDouble("Velocity (rps)", () -> values.velocityRotationsPerSecond);
62+
positionController.addDouble(
63+
"Acceleration (rpsps)", () -> values.accelerationRotationsPerSecondPerSecond);
64+
positionController.addDouble("Voltage (V)", () -> values.motorVolts);
65+
positionController.addDouble("Current (A)", () -> values.motorAmps);
66+
}
67+
68+
/**
69+
* Configures the position controller.
70+
*
71+
* @param constants
72+
*/
73+
public void configure(PositionControllerIOConstants constants);
74+
75+
/**
76+
* Updates the position controller's values.
77+
*
78+
* @param values
79+
*/
80+
public void update(PositionControllerIOValues values);
81+
82+
/**
83+
* Sets the mechanism position.
84+
*
85+
* @param positionRotations
86+
*/
87+
public void setPosition(double positionRotations);
88+
89+
/**
90+
* Sets the position setpoint.
91+
*
92+
* @param positionRotations
93+
* @param velocityRotationsPerSecond
94+
*/
95+
public void setSetpoint(double positionRotations, double velocityRotationsPerSecond);
9196
}

src/main/java/frc/lib/controller/PositionControllerIOSim.java

Lines changed: 19 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -3,28 +3,27 @@
33
/** Simulated position controller. */
44
public class PositionControllerIOSim implements PositionControllerIO {
55

6-
private double positionRotations = 0.0;
7-
8-
private double velocityRotationsPerSecond = 0.0;
6+
private double positionRotations = 0.0;
97

10-
@Override
11-
public void configure(PositionControllerIOConstants constants) {}
8+
private double velocityRotationsPerSecond = 0.0;
129

13-
@Override
14-
public void update(PositionControllerIOValues values) {
15-
values.positionRotations = positionRotations;
16-
values.velocityRotationsPerSecond = velocityRotationsPerSecond;
17-
}
10+
@Override
11+
public void configure(PositionControllerIOConstants constants) {}
1812

19-
@Override
20-
public void setPosition(double positionRotations) {
21-
this.positionRotations = positionRotations;
22-
}
13+
@Override
14+
public void update(PositionControllerIOValues values) {
15+
values.positionRotations = positionRotations;
16+
values.velocityRotationsPerSecond = velocityRotationsPerSecond;
17+
}
2318

24-
@Override
25-
public void setSetpoint(double positionRotations, double velocityRotationsPerSecond) {
26-
this.positionRotations = positionRotations;
27-
this.velocityRotationsPerSecond = velocityRotationsPerSecond;
28-
}
29-
19+
@Override
20+
public void setPosition(double positionRotations) {
21+
this.positionRotations = positionRotations;
22+
}
23+
24+
@Override
25+
public void setSetpoint(double positionRotations, double velocityRotationsPerSecond) {
26+
this.positionRotations = positionRotations;
27+
this.velocityRotationsPerSecond = velocityRotationsPerSecond;
28+
}
3029
}

0 commit comments

Comments
 (0)