Skip to content

Commit 90708be

Browse files
committed
Add methods for wrapping a Motor with a simulated motor
1 parent 8becf38 commit 90708be

1 file changed

Lines changed: 154 additions & 0 deletions

File tree

Lines changed: 154 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,154 @@
1+
/*
2+
Copyright 2026 Prospect Robotics SWENext Club
3+
4+
Licensed under the Apache License, Version 2.0 (the "License");
5+
you may not use this file except in compliance with the License.
6+
You may obtain a copy of the License at
7+
8+
http://www.apache.org/licenses/LICENSE-2.0
9+
10+
Unless required by applicable law or agreed to in writing, software
11+
distributed under the License is distributed on an "AS IS" BASIS,
12+
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+
See the License for the specific language governing permissions and
14+
limitations under the License.
15+
*/
16+
package com.team2813.lib2813.control.motors;
17+
18+
import com.team2813.lib2813.control.ControlMode;
19+
import com.team2813.lib2813.control.Motor;
20+
import com.team2813.lib2813.control.PIDMotor;
21+
import com.team2813.lib2813.robot.PeriodicRegistry;
22+
import com.team2813.lib2813.robot.RobotState;
23+
import edu.wpi.first.math.numbers.N1;
24+
import edu.wpi.first.units.measure.Angle;
25+
import edu.wpi.first.units.measure.Current;
26+
import edu.wpi.first.wpilibj.RobotController;
27+
import edu.wpi.first.wpilibj.simulation.LinearSystemSim;
28+
29+
/** Helper methods for working with simulation for motors. */
30+
public class MotorSimulation {
31+
32+
/**
33+
* Wraps a motor and a simulated motor. The simulated motor will be updated when the motor is
34+
* updated.
35+
*
36+
* @param motor Motor to wrap
37+
* @param periodicRegistry Registry that will be used to register periodic functions
38+
* @param sim Simulation to associate with the motor
39+
* @return Wrapped motor
40+
*/
41+
public static Motor wrap(
42+
Motor motor, PeriodicRegistry periodicRegistry, LinearSystemSim<?, N1, ?> sim) {
43+
if (motor instanceof PIDMotor pidMotor) {
44+
return new PIDMotorWrapper(pidMotor, periodicRegistry, sim);
45+
}
46+
return new MotorWrapper<>(motor, periodicRegistry, sim);
47+
}
48+
49+
/**
50+
* Wraps a pid motor and a simulated motor. The simulated motor will be updated when the motor is
51+
* updated.
52+
*
53+
* @param motor Motor to wrap
54+
* @param periodicRegistry Registry that will be used to register periodic functions
55+
* @param sim Simulation to associate with the motor
56+
* @return Wrapped motor
57+
*/
58+
public static PIDMotor wrap(
59+
PIDMotor motor, PeriodicRegistry periodicRegistry, LinearSystemSim<?, N1, ?> sim) {
60+
return new PIDMotorWrapper(motor, periodicRegistry, sim);
61+
}
62+
63+
private static class MotorWrapper<M extends Motor> implements Motor {
64+
protected final M motor;
65+
private final LinearSystemSim<?, N1, ?> sim;
66+
private long lastSimUpdateTimeMillis = 0;
67+
68+
MotorWrapper(M motor, PeriodicRegistry periodicRegistry, LinearSystemSim<?, N1, ?> sim) {
69+
this.motor = motor;
70+
this.sim = sim;
71+
periodicRegistry.addSimulationPeriodic(this::simulationPeriodic);
72+
}
73+
74+
private void simulationPeriodic(RobotState robotState) {
75+
long currentTimeMicros = RobotController.getFPGATime();
76+
sim.update((currentTimeMicros - lastSimUpdateTimeMillis) / 1000.0);
77+
lastSimUpdateTimeMillis = currentTimeMicros;
78+
}
79+
80+
@Override
81+
public void set(ControlMode mode, double demand) {
82+
motor.set(mode, demand);
83+
sim.setInput(demand);
84+
}
85+
86+
@Override
87+
public void set(ControlMode mode, double demand, double feedForward) {
88+
motor.set(mode, demand, feedForward);
89+
sim.setInput(demand);
90+
}
91+
92+
@Override
93+
public Current getAppliedCurrent() {
94+
return motor.getAppliedCurrent();
95+
}
96+
97+
@Override
98+
public void disable() {
99+
motor.disable();
100+
}
101+
}
102+
103+
private static class PIDMotorWrapper extends MotorWrapper<PIDMotor> implements PIDMotor {
104+
105+
PIDMotorWrapper(
106+
PIDMotor motor, PeriodicRegistry periodicRegistry, LinearSystemSim<?, N1, ?> sim) {
107+
super(motor, periodicRegistry, sim);
108+
}
109+
110+
@Override
111+
public void configPIDF(int slot, double p, double i, double d, double f) {
112+
motor.configPIDF(slot, p, i, d, f);
113+
}
114+
115+
@Override
116+
public void configPIDF(double p, double i, double d, double f) {
117+
motor.configPIDF(p, i, d, f);
118+
}
119+
120+
@Override
121+
public void configPID(int slot, double p, double i, double d) {
122+
motor.configPID(slot, p, i, d);
123+
}
124+
125+
@Override
126+
public void configPID(double p, double i, double d) {
127+
motor.configPID(p, i, d);
128+
}
129+
130+
@Override
131+
public double position() {
132+
return motor.position();
133+
}
134+
135+
@Override
136+
public Angle getPositionMeasure() {
137+
return motor.getPositionMeasure();
138+
}
139+
140+
@Override
141+
public void setPosition(double position) {
142+
motor.setPosition(position);
143+
}
144+
145+
@Override
146+
public double getVelocity() {
147+
return motor.getVelocity();
148+
}
149+
}
150+
151+
private MotorSimulation() {
152+
throw new AssertionError("Not instantiable");
153+
}
154+
}

0 commit comments

Comments
 (0)