Skip to content

Commit

Permalink
Merge pull request #6 from BHSSFRC/feature/pressure-sensitive
Browse files Browse the repository at this point in the history
Add pressure sensor
  • Loading branch information
c-x-berger authored Feb 2, 2019
2 parents 2997acf + 62692d6 commit 9458e07
Show file tree
Hide file tree
Showing 3 changed files with 46 additions and 1 deletion.
9 changes: 8 additions & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
@@ -1,10 +1,12 @@
package frc.robot;

import edu.wpi.first.wpilibj.Compressor;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.command.Command;
import edu.wpi.first.wpilibj.command.Scheduler;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import frc.robot.sensors.PressureSensor;
import frc.robot.subsystems.Drivetrain;

/**
Expand All @@ -27,11 +29,13 @@ public void robotInit() {
// HACK: Singletons don't like working unless they're grabbed before use.
OI.getInstance();
Drivetrain.getInstance();
// Start compressor
new Compressor().start();
// chooser.setDefaultOption("Default Auto", new ExampleCommand());
// chooser.addOption("My Auto", new MyAutoCommand());
SmartDashboard.putData("Auto mode", chooser);

String[] displays = new String[]{"Display Drivetrain data?", "Display navX data?"};
String[] displays = new String[]{"Display Drivetrain data?", "Display navX data?", "Display pressure?"};
for (String display : displays) {
if (!SmartDashboard.containsKey(display)) {
SmartDashboard.putBoolean(display, false);
Expand All @@ -50,6 +54,9 @@ public void robotInit() {
*/
@Override
public void robotPeriodic() {
if (SmartDashboard.getBoolean("Display pressure?", false)) {
SmartDashboard.putNumber("Pnuematic pressure", PressureSensor.getInstance().getPressure());
}
}

/**
Expand Down
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/RobotMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -40,4 +40,6 @@ public class DRIVETRAIN {

public static final int LEFT_JOY = 0;
public static final int RIGHT_JOY = 1;

public static final int PRESSURE_SENSOR_PORT = 0;
}
36 changes: 36 additions & 0 deletions src/main/java/frc/robot/sensors/PressureSensor.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
package frc.robot.sensors;

import edu.wpi.first.wpilibj.AnalogInput;
import frc.robot.RobotMap;

public class PressureSensor {
private static final PressureSensor INSTANCE = new PressureSensor(RobotMap.PRESSURE_SENSOR_PORT);

private AnalogInput ai;
/**
* The voltage into the sensor.
*/
private static final double VCC = 5.0;

public PressureSensor(int inputPin) {
this.ai = new AnalogInput(inputPin);
}

private double getVoltageOut() {
return ai.getVoltage();
}

/**
* Return the pressure, in PSI. Has a tolerance of 1.5% according to REV.
*
* @return Measured pressure, in PSI.
* @see "http://www.revrobotics.com/content/docs/REV-11-1107-DS.pdf"
*/
public double getPressure() {
return (250 * (this.getVoltageOut() / VCC)) - 25;
}

public static PressureSensor getInstance() {
return INSTANCE;
}
}

0 comments on commit 9458e07

Please sign in to comment.