Skip to content

Commit

Permalink
Merge pull request #68 from DeepBlueRobotics/fix-use-lib199-with-comp…
Browse files Browse the repository at this point in the history
…liant-sim-names

Use lib199 with compliant names for sim devices and data.
  • Loading branch information
brettle authored Jun 20, 2024
2 parents 336ca7c + 85ae2c3 commit 18e49bf
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 9 deletions.
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ dependencies {
simulationRelease wpi.sim.enableRelease()

testImplementation 'org.junit.jupiter:junit-jupiter:5.10.1'
implementation "com.github.deepbluerobotics:lib199:3170c4433a775e90d6110334bc5658e573317ab6"
implementation "com.github.deepbluerobotics:lib199:400693b52180c82a1f26c08025bc12f144b930f9"
}

test {
Expand Down
17 changes: 9 additions & 8 deletions src/main/java/org/carlmontrobotics/subsystems/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ public class Arm extends SubsystemBase {
private ShuffleboardTab sysIdTab = Shuffleboard.getTab("arm SysID");
private boolean setPIDOff;

private SimDouble positionSim;
private SimDouble rotationsSim;

public Arm() {
// weird math stuff
Expand Down Expand Up @@ -162,8 +162,8 @@ public Arm() {
armProfile = new TrapezoidProfile(TRAP_CONSTRAINTS);
SmartDashboard.putBoolean("arm is at pos", false);
if (RobotBase.isSimulation()) {
positionSim = new SimDeviceSim("SparkMax[%d]_AbsoluteEncoder".formatted(ARM_MOTOR_PORT_MASTER))
.getDouble("Position");
rotationsSim = new SimDeviceSim("CANDutyCycle:CANSparkMax",
ARM_MOTOR_PORT_MASTER).getDouble("position");
}

}
Expand Down Expand Up @@ -469,11 +469,12 @@ public void setDefaultCommand(TeleopArm teleopArm, Object object) {

@Override
public void simulationPeriodic() {
// Fake goaling to the goal instantaneously
if (positionSim != null) {
positionSim.set((goalState.position - armMasterEncoder.getZeroOffset())
* (armMasterEncoder.getInverted() ? -1.0 : 1.0)
/ armMasterEncoder.getPositionConversionFactor() * MockedEncoder.NEO_BUILTIN_ENCODER_CPR);
// Fake going to the goal instantaneously
if (rotationsSim != null) {
rotationsSim
.set((goalState.position - armMasterEncoder.getZeroOffset())
* (armMasterEncoder.getInverted() ? -1.0 : 1.0)
/ armMasterEncoder.getPositionConversionFactor());
}
}
}

0 comments on commit 18e49bf

Please sign in to comment.