Skip to content

Commit

Permalink
Very hacky simulation support.
Browse files Browse the repository at this point in the history
  • Loading branch information
m10653 committed Jan 27, 2024
1 parent 121f664 commit 548c062
Show file tree
Hide file tree
Showing 2 changed files with 110 additions and 8 deletions.
Original file line number Diff line number Diff line change
@@ -1,11 +1,13 @@
package org.jmhsrobotics.frc2024.subsystems.arm;

import com.revrobotics.AbsoluteEncoder;
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.CANSparkMax;
import com.revrobotics.SparkAnalogSensor;
import com.revrobotics.SparkAbsoluteEncoder.Type;

import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.RobotBase;
import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim;
import edu.wpi.first.wpilibj.smartdashboard.Mechanism2d;
import edu.wpi.first.wpilibj.smartdashboard.MechanismLigament2d;
import edu.wpi.first.wpilibj.smartdashboard.MechanismRoot2d;
Expand All @@ -17,15 +19,17 @@ public class ArmSubsystem extends SubsystemBase {

private MechanismLigament2d m_arm;
private CANSparkMax armPivot = new CANSparkMax(9, MotorType.kBrushless);
private AbsoluteEncoder pitchEncoder;
private SimableAbsoluteEncoder pitchEncoder;
private Mechanism2d mech;

public ArmSubsystem() {
pitchEncoder = armPivot.getAbsoluteEncoder(Type.kDutyCycle);
pitchEncoder = new SimableAbsoluteEncoder(armPivot.getAbsoluteEncoder(Type.kDutyCycle));
armPivot.setSmartCurrentLimit(40);

armPivot.setIdleMode(IdleMode.kBrake);
init2d();
if (RobotBase.isSimulation()) {
initSim();
}
}

public void setArmPivot(double amount) {
Expand All @@ -37,8 +41,6 @@ public double getArmPitch() {
return this.pitchEncoder.getPosition();
}

private SparkAnalogSensor pitchencsim;

public void init2d() {
// TODO: finish sim
mech = new Mechanism2d(3, 3);
Expand All @@ -55,8 +57,22 @@ public void periodic() {
m_arm.setAngle(getArmPitch());
SmartDashboard.putData("ArmSubsystem/armSIM", mech);
SmartDashboard.putNumber("ArmSubsystem/velocity", this.pitchEncoder.getVelocity());
SmartDashboard.putString("ArmSubsystem/encoder", pitchEncoder.toString());
SmartDashboard.putNumber("ArmSubsystem/encoder", pitchEncoder.getPosition());

}
SingleJointedArmSim armSim;
public void initSim() {
double armGearRatio = 1;
double moi = 1;
armSim = new SingleJointedArmSim(DCMotor.getNEO(2), armGearRatio, moi, Units.inchesToMeters(23), 0,
Units.degreesToRadians(180), false, 0);
// simEncoder = new RevEncoderSimWrapper(null, null);
}
@Override
public void simulationPeriodic() {
double armVolts = armPivot.get() * 12;
armSim.setInputVoltage(armVolts);
pitchEncoder.setPosition(Units.radiansToDegrees(armSim.getAngleRads()));
}

}
Original file line number Diff line number Diff line change
@@ -0,0 +1,86 @@
package org.jmhsrobotics.frc2024.subsystems.arm;

import com.revrobotics.AbsoluteEncoder;
import com.revrobotics.REVLibError;

import edu.wpi.first.wpilibj.RobotBase;

public class SimableAbsoluteEncoder implements AbsoluteEncoder {

private AbsoluteEncoder enc;
private double position;

SimableAbsoluteEncoder(AbsoluteEncoder enc) {
this.enc = enc;
}

@Override
public double getPosition() {
if (RobotBase.isSimulation()) {
return position;
} else {
return enc.getPosition();
}

}

@Override
public double getVelocity() {
return enc.getVelocity();
}

@Override
public REVLibError setPositionConversionFactor(double factor) {
return enc.setPositionConversionFactor(factor);
}

@Override
public double getPositionConversionFactor() {
return enc.getPositionConversionFactor();
}

@Override
public REVLibError setVelocityConversionFactor(double factor) {
return enc.setVelocityConversionFactor(factor);
}

@Override
public double getVelocityConversionFactor() {
return enc.getVelocityConversionFactor();
}

@Override
public REVLibError setInverted(boolean inverted) {
return enc.setInverted(inverted);
}

@Override
public boolean getInverted() {
return enc.getInverted();
}

@Override
public REVLibError setAverageDepth(int depth) {
return enc.setAverageDepth(depth);
}

@Override
public int getAverageDepth() {
return enc.getAverageDepth();
}

@Override
public REVLibError setZeroOffset(double offset) {
return enc.setZeroOffset(offset);
}

@Override
public double getZeroOffset() {
return enc.getZeroOffset();
}

public void setPosition(double position) {
this.position = position;
}

}

0 comments on commit 548c062

Please sign in to comment.