Skip to content

Commit 0507f44

Browse files
committed
feat: create generic roller subsystem for lib
Signed-off-by: Dasun Abeykoon <[email protected]>
1 parent 8db4a09 commit 0507f44

File tree

3 files changed

+170
-0
lines changed

3 files changed

+170
-0
lines changed
Lines changed: 89 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,89 @@
1+
// Copyright (c) 2025 FRC 6423 - Ward Melville Iron Patriots
2+
// https://github.com/wmironpatriots
3+
//
4+
// Open Source Software; you can modify and/or share it under the terms of
5+
// MIT license file in the root directory of this project
6+
7+
package org.frc6423.lib.subsystems;
8+
9+
import edu.wpi.first.epilogue.Logged;
10+
import edu.wpi.first.math.filter.LinearFilter;
11+
import edu.wpi.first.wpilibj2.command.Command;
12+
import edu.wpi.first.wpilibj2.command.SubsystemBase;
13+
import java.util.function.DoubleSupplier;
14+
15+
/** Generic Roller Subsystem */
16+
public class Roller extends SubsystemBase {
17+
@Logged(name = "Roller Hardware Loggables")
18+
private final RollerIO hardware;
19+
20+
// TODO check value
21+
private LinearFilter currentFilter = LinearFilter.movingAverage(3);
22+
23+
@Logged(name = "Filtered Roller Motor Current (Amps)")
24+
private double filteredCurrent = 0.0;
25+
26+
public Roller(String name, RollerIO hardware) {
27+
this.setName(name);
28+
this.hardware = hardware;
29+
}
30+
31+
@Override
32+
public void periodic() {
33+
hardware.periodic();
34+
35+
filteredCurrent = currentFilter.calculate(hardware.getStatorCurrentAmps());
36+
}
37+
38+
/**
39+
* @param minStallAmps minimum roller motor stator current considered stalling in amps
40+
* @return true if roller motor is stalling
41+
*/
42+
private boolean isStalling(double minStallAmps) {
43+
return Math.abs(filteredCurrent) > 30.0;
44+
}
45+
46+
private void setCurrentFilterTaps(int taps) {
47+
currentFilter = LinearFilter.movingAverage(taps);
48+
}
49+
50+
/**
51+
* Run roller at specified volts
52+
*
53+
* @param volts desired volts
54+
* @return {@link Command}
55+
*/
56+
private Command runVolts(DoubleSupplier volts) {
57+
return this.run(() -> hardware.setVolts(volts.getAsDouble()));
58+
}
59+
60+
/**
61+
* Run roller at specified volts
62+
*
63+
* @param volts desired volts
64+
* @return {@link Command}
65+
*/
66+
private Command runVolts(double volts) {
67+
return runVolts(() -> volts);
68+
}
69+
70+
/**
71+
* Run roller at specified speed
72+
*
73+
* @param speedRpm desired speed in revs per minute
74+
* @return {@link Command}
75+
*/
76+
private Command runSpeed(DoubleSupplier speedRpm) {
77+
return this.run(() -> hardware.setSpeed(speedRpm.getAsDouble()));
78+
}
79+
80+
/**
81+
* Run roller at specified speed
82+
*
83+
* @param speedRpm desired speed in revs per minute
84+
* @return {@link Command}
85+
*/
86+
private Command runSpeed(double speedRpm) {
87+
return runSpeed(() -> speedRpm);
88+
}
89+
}
Lines changed: 44 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,44 @@
1+
// Copyright (c) 2025 FRC 6423 - Ward Melville Iron Patriots
2+
// https://github.com/wmironpatriots
3+
//
4+
// Open Source Software; you can modify and/or share it under the terms of
5+
// MIT license file in the root directory of this project
6+
7+
package org.frc6423.lib.subsystems;
8+
9+
import edu.wpi.first.epilogue.Logged;
10+
11+
/** Generalized hardware methods for {@link Arm} subsystem */
12+
public interface RollerIO extends AutoCloseable {
13+
/** Run periodic hardware logic */
14+
public void periodic();
15+
16+
@Logged(name = "Roller Applied Voltage")
17+
public double getAppliedVolts();
18+
19+
/**
20+
* @return speed of roller motor in revs per minute
21+
*/
22+
@Logged(name = "Roller Motor Speed (Revs Per Minute)")
23+
public double getSpeedRpm();
24+
25+
/**
26+
* @return stator current of roller motor in amps
27+
*/
28+
@Logged(name = "Roller Motor Stator Current (Amps)")
29+
public double getStatorCurrentAmps();
30+
31+
/**
32+
* Set roller motor voltage setpoint
33+
*
34+
* @param volts desired voltage setpoint
35+
*/
36+
public void setVolts(double volts);
37+
38+
/**
39+
* Set roller motor speed setpoint
40+
*
41+
* @param speedRpm desired speed setpoint in revs per minute
42+
*/
43+
public void setSpeed(double speedRpm);
44+
}
Lines changed: 37 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,37 @@
1+
// Copyright (c) 2025 FRC 6423 - Ward Melville Iron Patriots
2+
// https://github.com/wmironpatriots
3+
//
4+
// Open Source Software; you can modify and/or share it under the terms of
5+
// MIT license file in the root directory of this project
6+
7+
package org.frc6423.lib.subsystems;
8+
9+
/** Null {@link RollerIO} */
10+
public class RollerIONone implements RollerIO {
11+
@Override
12+
public void periodic() {}
13+
14+
@Override
15+
public double getAppliedVolts() {
16+
return 0.0;
17+
}
18+
19+
@Override
20+
public double getSpeedRpm() {
21+
return 0.0;
22+
}
23+
24+
@Override
25+
public double getStatorCurrentAmps() {
26+
return 0.0;
27+
}
28+
29+
@Override
30+
public void setVolts(double volts) {}
31+
32+
@Override
33+
public void setSpeed(double speedRpm) {}
34+
35+
@Override
36+
public void close() throws Exception {}
37+
}

0 commit comments

Comments
 (0)