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

Commit d6124f3

Browse files
committed
wip
1 parent 5c246e0 commit d6124f3

File tree

3 files changed

+113
-0
lines changed

3 files changed

+113
-0
lines changed
Lines changed: 81 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,81 @@
1+
package frc.lib.controller;
2+
3+
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
4+
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
5+
import frc.lib.Telemetry;
6+
7+
/** Position controller interface. */
8+
public interface PositionControllerIO {
9+
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 velocity sensor and the controlled mechanism. */
22+
public double sensorToMechanismRatio = 1.0;
23+
}
24+
25+
/** Position controller values. */
26+
public static class PositionControllerIOValues {
27+
/** Position in rotations. */
28+
public double positionRotations = 0.0;
29+
30+
/** Velocity in rotations per second. */
31+
public double velocityRotationsPerSecond = 0.0;
32+
33+
/** Acceleration in rotations per second per second. */
34+
public double accelerationRotationsPerSecondPerSecond = 0.0;
35+
36+
/** Motor voltage in volts. */
37+
public double motorVolts = 0.0;
38+
39+
/** Motor current in amps. */
40+
public double motorAmps = 0.0;
41+
}
42+
43+
/**
44+
* Adds position controller values to Shuffleboard.
45+
*
46+
* @param tab
47+
* @param name
48+
* @param values
49+
*/
50+
public static void addToShuffleboard(ShuffleboardTab tab, String name, PositionControllerIOValues values) {
51+
ShuffleboardLayout positionController = Telemetry.addColumn(tab, name);
52+
53+
positionController.addDouble("Position (rot)", () -> values.positionRotations);
54+
positionController.addDouble("Velocity (rps)", () -> values.velocityRotationsPerSecond);
55+
positionController.addDouble("Acceleration (rpsps)", () -> values.accelerationRotationsPerSecondPerSecond);
56+
positionController.addDouble("Voltage (V)", () -> values.motorVolts);
57+
positionController.addDouble("Current (A)", () -> values.motorAmps);
58+
}
59+
60+
/**
61+
* Configures the position controller.
62+
*
63+
* @param constants
64+
*/
65+
public void configure(PositionControllerIOConstants constants);
66+
67+
/**
68+
* Updates the position controller's values.
69+
*
70+
* @param values
71+
*/
72+
public void update(PositionControllerIOValues values);
73+
74+
/**
75+
* Sets the position setpoint.
76+
*
77+
* @param positionRotations
78+
* @param velocityRotationsPerSecond
79+
*/
80+
public void setSetpoint(double positionRotations, double velocityRotationsPerSecond);
81+
}
Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
package frc.lib.controller;
2+
3+
/** Simulated position controller. */
4+
public class PositionControllerIOSim implements PositionControllerIO {
5+
6+
private double positionRotations = 0.0;
7+
8+
private double velocityRotationsPerSecond = 0.0;
9+
10+
@Override
11+
public void configure(PositionControllerIOConstants constants) {}
12+
13+
@Override
14+
public void update(PositionControllerIOValues values) {
15+
values.positionRotations = positionRotations;
16+
values.velocityRotationsPerSecond = velocityRotationsPerSecond;
17+
}
18+
19+
@Override
20+
public void setSetpoint(double positionRotations, double velocityRotationsPerSecond) {
21+
this.positionRotations = positionRotations;
22+
this.velocityRotationsPerSecond = velocityRotationsPerSecond;
23+
}
24+
25+
}

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

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,13 @@ public static class VelocityControllerIOValues {
3737
public double motorAmps = 0.0;
3838
}
3939

40+
/**
41+
* Adds velocity controller values to Shuffleboard.
42+
*
43+
* @param tab
44+
* @param name
45+
* @param values
46+
*/
4047
public static void addToShuffleboard(ShuffleboardTab tab, String name, VelocityControllerIOValues values) {
4148
ShuffleboardLayout velocityController = Telemetry.addColumn(tab, name);
4249

0 commit comments

Comments
 (0)