Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Untested example of using distance sensor sims #78

Draft
wants to merge 6 commits into
base: master
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions simgui.json
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,11 @@
"open": true
}
},
"PlayingWithFusionTimeOfFlight[11]": {
"header": {
"open": true
}
},
"SparkMax[15]": {
"header": {
"open": true
Expand Down Expand Up @@ -84,6 +89,9 @@
"open": true
},
"SmartDashboard": {
"Arm": {
"open": true
},
"BL": {
"open": true
},
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

import org.carlmontrobotics.lib199.MotorConfig;
import org.carlmontrobotics.lib199.MotorControllerFactory;
import org.carlmontrobotics.lib199.SensorFactory;

import com.playingwithfusion.TimeOfFlight;
import com.playingwithfusion.TimeOfFlight.RangingMode;
Expand All @@ -14,12 +15,15 @@
import com.revrobotics.RelativeEncoder;
import com.revrobotics.SparkPIDController;

import edu.wpi.first.hal.SimDouble;
import edu.wpi.first.hal.SimEnum;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.util.datalog.DataLogEntry;
import edu.wpi.first.util.datalog.StringLogEntry;
import edu.wpi.first.util.sendable.SendableBuilder;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.simulation.SimDeviceSim;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

Expand All @@ -44,12 +48,19 @@ public class IntakeShooter extends SubsystemBase {

private double goalOutakeRPM = outtakeEncoder.getVelocity();

private TimeOfFlight intakeDistanceSensor = new TimeOfFlight(INTAKE_DISTANCE_SENSOR_PORT);
private TimeOfFlight outtakeDistanceSensor = new TimeOfFlight(OUTAKE_DISTANCE_SENSOR_PORT);
private TimeOfFlight intakeDistanceSensor = SensorFactory
.createPlayingWithFusionTimeOfFlight(INTAKE_DISTANCE_SENSOR_PORT);
private TimeOfFlight outtakeDistanceSensor = SensorFactory
.createPlayingWithFusionTimeOfFlight(OUTAKE_DISTANCE_SENSOR_PORT);

private double lastValidDistanceIntake = Double.POSITIVE_INFINITY;
private double lastValidDistanceOuttake = Double.POSITIVE_INFINITY;

private SimDouble intakeDistanceSensorRangeSim,
outtakeDistanceSensorRangeSim;
private SimEnum intakeDistanceSensorStatusSim,
outtakeDistanceSensorStatusSim;

public IntakeShooter() {
// Figure out which ones to set inverted
intakeMotor.setInverted(INTAKE_MOTOR_INVERSION);
Expand All @@ -73,6 +84,22 @@ public IntakeShooter() {
outtakeMotorVortex.setSmartCurrentLimit(60);
// SmartDashboard.putNumber("Intake target RPM", 0);
// SmartDashboard.putNumber("Vortex volts", 0);

SimDeviceSim intakeDistanceSensorSim = new SimDeviceSim(
"CANAIn:PlayingWithFusionTimeOfFlight[%d]-rangeVoltsIsMM"
.formatted(INTAKE_DISTANCE_SENSOR_PORT));
intakeDistanceSensorRangeSim =
intakeDistanceSensorSim.getDouble("voltage");
intakeDistanceSensorStatusSim =
intakeDistanceSensorSim.getEnum("status");

SimDeviceSim outtakeDistanceSensorSim = new SimDeviceSim(
"CANAIn:PlayingWithFusionTimeOfFlight[%d]-rangeVoltsIsMM"
.formatted(OUTAKE_DISTANCE_SENSOR_PORT));
outtakeDistanceSensorRangeSim =
outtakeDistanceSensorSim.getDouble("voltage");
outtakeDistanceSensorStatusSim =
outtakeDistanceSensorSim.getEnum("status");
}

public boolean intakeIsOverTemp() {
Expand Down Expand Up @@ -262,6 +289,23 @@ public void initSendable(SendableBuilder sendableBuilder) {
sendableBuilder.addBooleanProperty("Intake distance sensor length", this::intakeDetectsNote, null);
sendableBuilder.addDoubleProperty("Period time", this::countPeridoic, null);
}

public void simulationPeriodic() {
if (intakeMotor.get() > 0.0) {
intakeDistanceSensorRangeSim.set(
Units.inchesToMeters(DETECT_DISTANCE_INCHES / 2) * 1000);
outtakeDistanceSensorRangeSim.set(
Units.inchesToMeters(DETECT_DISTANCE_INCHES / 2) * 1000);
} else if (intakeMotor.get() < 0.0 || outtakeMotorVortex.get() > 0.0) {
intakeDistanceSensorRangeSim.set(
Units.inchesToMeters(DETECT_DISTANCE_INCHES * 2) * 1000);
outtakeDistanceSensorRangeSim.set(
Units.inchesToMeters(DETECT_DISTANCE_INCHES * 2) * 1000);
}
intakeDistanceSensorStatusSim.set(TimeOfFlight.Status.Valid.ordinal());
outtakeDistanceSensorStatusSim.set(TimeOfFlight.Status.Valid.ordinal());
}

/*
* public double calculateRPMAtDistance() {
*
Expand Down
Loading