Skip to content

Commit

Permalink
Rev flex update (#47)
Browse files Browse the repository at this point in the history
* Make it possible to sim rev flex

* Make more generic

* Fix bazel
  • Loading branch information
pjreiniger committed Feb 22, 2024
1 parent 560d55d commit 18e0884
Show file tree
Hide file tree
Showing 5 changed files with 47 additions and 6 deletions.
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
package org.snobotv2.module_wrappers.rev;

import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkBase;
import edu.wpi.first.hal.SimDouble;
import edu.wpi.first.wpilibj.simulation.SimDeviceSim;
import org.snobotv2.module_wrappers.BaseEncoderWrapper;

public final class RevEncoderSimWrapper extends BaseEncoderWrapper
{
public static RevEncoderSimWrapper create(CANSparkMax motorController)
public static RevEncoderSimWrapper create(CANSparkBase motorController)
{
SimDeviceSim deviceSim = new SimDeviceSim("SPARK MAX [" + motorController.getDeviceId() + "]");
SimDouble position = deviceSim.getDouble("Position");
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
package org.snobotv2.module_wrappers.rev;

import com.revrobotics.CANSparkBase;
import com.revrobotics.SimableRevDevice;
import edu.wpi.first.hal.SimDouble;
import edu.wpi.first.wpilibj.RobotController;
Expand All @@ -12,15 +13,19 @@ public class RevMotorControllerSimWrapper extends BaseMotorControllerWrapper
private final SimDouble mBusVoltage;
private final SimDouble mMotorCurrent;

public RevMotorControllerSimWrapper(SimableRevDevice motorController)
public RevMotorControllerSimWrapper(CANSparkBase motorController)
{
super(motorController.getDeviceId(), motorController::getAppliedOutput);
if (!(motorController instanceof SimableRevDevice))
{
throw new IllegalArgumentException("The provided motor controller is not simmable!");
}

SimDeviceSim deviceSim = new SimDeviceSim("SPARK MAX [" + motorController.getDeviceId() + "]");
mBusVoltage = deviceSim.getDouble("Bus Voltage");
mMotorCurrent = deviceSim.getDouble("Motor Current");

mMotorController = motorController;
mMotorController = (SimableRevDevice) motorController;
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ snobot_sim_java_test(
srcs = glob(["*.java"]),
deps = [
"//examples/test_robot_rev/src/main/java/org/snobotv2/examples/rev/subsystems",
"//snobot_sim_java_base/src/main/java/org/snobotv2/sim_wrappers",
"//snobot_sim_java_revlib/src/main/java/com/revrobotics:simmable_rev",
"//snobot_sim_java_revlib/src/main/java/org/snobotv2/module_wrappers/rev",
"//snobot_sim_java_test_utils/src/main/java/org/snobotv2/test_utils",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,10 @@ public void testBasicMax()
@Test
public void testBasicFlex()
{
try (SimableCANSparkFlex sparkMax = new SimableCANSparkFlex(1, CANSparkLowLevel.MotorType.kBrushless);
try (SimableCANSparkFlex sparkFlex = new SimableCANSparkFlex(1, CANSparkLowLevel.MotorType.kBrushless);
SimableCANSparkFlex follower = new SimableCANSparkFlex(11, CANSparkLowLevel.MotorType.kBrushless))
{
runTest(sparkMax, follower);
runTest(sparkFlex, follower);
}
}

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
package org.snobotv2.module_wrappers.rev;

import com.revrobotics.CANSparkLowLevel;
import com.revrobotics.RelativeEncoder;
import com.revrobotics.SimableCANSparkFlex;
import org.junit.jupiter.api.Test;
import org.snobotv2.sim_wrappers.InstantaneousMotorSim;

import static org.junit.jupiter.api.Assertions.assertEquals;

public class TestRevFlexEncoder
{
@Test
public void testEncoder()
{
try (SimableCANSparkFlex sparkFlex = new SimableCANSparkFlex(1, CANSparkLowLevel.MotorType.kBrushless))
{
RelativeEncoder encoder = sparkFlex.getEncoder();

InstantaneousMotorSim motorSim = new InstantaneousMotorSim(
new RevMotorControllerSimWrapper(sparkFlex),
RevEncoderSimWrapper.create(sparkFlex),
10);

for (int i = 0; i < 100; ++i)
{
sparkFlex.set(0.5);
motorSim.update();
}

assertEquals(10, encoder.getPosition(), 0.001);
assertEquals(5, encoder.getVelocity(), 0.001);
}
}
}

0 comments on commit 18e0884

Please sign in to comment.