Skip to content

Commit

Permalink
Browse files Browse the repository at this point in the history
  • Loading branch information
dbadb committed Feb 28, 2020
2 parents 0cce606 + a6d6cbc commit 6e617fe
Show file tree
Hide file tree
Showing 21 changed files with 263 additions and 414 deletions.
24 changes: 10 additions & 14 deletions src/main/java/com/spartronics4915/frc2020/ButtonFactory.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@

public class ButtonFactory
{

private Constants.OI.DeviceSpec[] mDeviceList;
private HashSet<ButtonSpec> mInUse;

Expand All @@ -23,10 +22,10 @@ public class ButtonFactory
/* our job is to configure Constants.OI.deviceList according
* to runtime configuration inputs
*/
String config;
String config;
mDeviceList = Constants.OI.deviceList;
mInUse = new HashSet<>();
if(!RobotBase.isReal())
if (!RobotBase.isReal())
{
config = "noOI";
Logger.notice("ButtonFactory: configuring buttons for no OI");
Expand All @@ -50,7 +49,7 @@ public class ButtonFactory
case "robot2020":
case "default":
// here we trust in Constants.OI values
for(int i=0;i<mDeviceList.length;i++)
for (int i = 0; i < mDeviceList.length; i++)
mDeviceList[i].joystick = new Joystick(mDeviceList[i].portId);
break;
}
Expand All @@ -75,17 +74,16 @@ Joystick getJoystick(int port)
Button create(int deviceId, int buttonId)
{
var spec = new ButtonSpec(deviceId, buttonId);
if(mInUse.contains(spec))
if (mInUse.contains(spec))
{
Logger.warning("ButtonFactory button collision " +
deviceId + " " + buttonId);
Logger.warning("ButtonFactory button collision " + deviceId + " " + buttonId);
}
mInUse.add(spec);
if(deviceId < this.mDeviceList.length)
if (deviceId < this.mDeviceList.length)
{
var dev = this.mDeviceList[deviceId];
// buttonIds indexOrigin is 1
if(dev.joystick != null && buttonId <= dev.numButtons)
if (dev.joystick != null && buttonId <= dev.numButtons)
return new JoystickButton(dev.joystick, buttonId);
}
return new InvalidButton(0, buttonId);
Expand All @@ -96,7 +94,7 @@ Button create(int deviceId, int buttonId)
*/
private static class InvalidButton extends Button
{
public InvalidButton(int port, int button)
public InvalidButton(int port, int button)
{
}

Expand Down Expand Up @@ -144,7 +142,6 @@ public Button cancelWhenActive(final Command toRun)
// no-op
return this;
}

}

private static class ButtonSpec
Expand All @@ -169,7 +166,7 @@ public boolean equals(Object o)
return false;
if (!(o instanceof ButtonSpec))
return false;
return port == ((ButtonSpec) o).port &&
return port == ((ButtonSpec) o).port &&
bId == ((ButtonSpec) o).bId;
}

Expand All @@ -178,6 +175,5 @@ public int hashCode()
{
return (port << 8) + bId;
}

}
}
}
42 changes: 19 additions & 23 deletions src/main/java/com/spartronics4915/frc2020/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,7 @@ public final class Constants
static // check our machine id so subsystems can support multiple configs
{
sConfig = "default";
Path machineIDPath = FileSystems.getDefault().getPath(System.getProperty("user.home"),
"machineid");
Path machineIDPath = FileSystems.getDefault().getPath(System.getProperty("user.home"), "machineid");
try
{
sConfig = Files.readString(machineIDPath).trim().toLowerCase();
Expand All @@ -50,7 +49,7 @@ public static final class Climber
public static final int kLiftMotorId = 5;
public static final int kWinchMotorId = 6;
public static final double kExtendSpeed = 1.0; // XXX: test
public static final double kWinchSpeed = -0.85; // XXX: test
public static final double kWinchSpeed = -0.85; // TODO: test! (this shouldn't have to be negative)
public static final double kRetractSpeed = -1.0; // XXX: test
public static final double kReverseWinchSpeed = 1.0; // XXX: test
public static final double kStallThreshold = 90.0; // FIXME: stand-in value
Expand All @@ -69,7 +68,7 @@ public static final class Spinner
public static final double kVelocityD = 0;
public static final double kPositionP = 0.005;
public static final double kPositionD = 0;
public static final double kConversionRatio = 1.0 / (187.0/20.0*9.0);
public static final double kConversionRatio = 1.0 / (187.0 / 20.0 * 9.0);
public static final double kMaxVelocity = 1.5;
public static final double kMaxAcceleration = 2;
public static final double kStallThreshold = 90.0; // FIXME: stand-in values
Expand Down Expand Up @@ -103,26 +102,24 @@ public static final class Intake
public static final int kHarvestMotorId = 12;
public static final int kProximitySensorId = 5; // Digital

public static final double kHarvestSpeed = 0.8; // XXX: test
public static final double kEjectSpeed = -0.8; // XXX: test
public static final double kHarvestSpeed = 0.8;
public static final double kEjectSpeed = -0.8;
}

public static final class Launcher
{
public static final int kFlywheelMasterId = 7; // CHANGE TO 7
public static final int kFlywheelMasterId = 7;
public static final int kFlywheelFollowerId = -1; // Solid brass
public static final int kAngleAdjusterMasterId = 0; // PWM
public static final int kAngleAdjusterFollowerId = 1; // PWM
public static final int kTurretId = 8;
public static final int kTurretPotentiometerId = 0; // Analog

// XXX: consider whether to adopt CamToField2020, we currently have
// XXX: consider whether to adopt CamToField2020, we currently have
// competing implementations.
public static final Pose2d kRobotToTurret = new Pose2d(Units.inchesToMeters(-3.72),
Units.inchesToMeters(5.264),
// z =
Rotation2d.fromDegrees(180.0));

public static final Pose2d kRobotToTurret = new Pose2d(Units.inchesToMeters(-3.72),
Units.inchesToMeters(5.264), Rotation2d.fromDegrees(180.0));

// https://docs.wpilib.org/en/latest/docs/software/advanced-control/controllers/feedforward.html#simplemotorfeedforward
public static final double kP = 0.05;
public static final double kS = 0.0286; // 0.0654;
Expand All @@ -149,11 +146,11 @@ public static final class Launcher
public static final Rotation2d kHoodMaxAngle = Rotation2d.fromDegrees(35.0);

public static Pose2d goalLocation = null;
//unit is feet
/** Feet */
public static final double MaxShootingDistance = 100;// FIXME: Figure out max distance
//unit is feet
/** Feet */
public static final double MinShootingDistance = 0;// FIXME: Figure out min distance
public static double kTurretStallAmps = 2.0;//Stand in Value
public static double kTurretStallAmps = 2.0; // Stand in Value
}

public static final class OI
Expand Down Expand Up @@ -308,21 +305,20 @@ public static final class Trajectory
public static final class Estimator
{
// XXX: consider whether to adopt CamToField2020, we currently
// have competing implementations.
// have competing implementations.
// If new measurements for Vision or Turret mounting are obtained,
// please also update CoordSysMgr20202.java.
public static final double kT265InternalMeasurementCovariance = 0.001;
public static final Pose2d kSlamraToRobot = new Pose2d(Units.inchesToMeters(-11.75),
Units.inchesToMeters(-4.75),
new Rotation2d());
public static final Pose2d kSlamraToRobot = new Pose2d(Units.inchesToMeters(-11.75),
Units.inchesToMeters(-4.75), new Rotation2d());

public static final Matrix<N3, N1> kStateStdDevs = new MatBuilder<>(Nat.N3(), Nat.N1())
.fill(0.02, 0.02, 0.01);
public static final Matrix<N6, N1> measurementStdDevs = new MatBuilder<>(Nat.N6(), Nat.N1())
.fill(0.1, 0.1, 0.1, 0.005,
0.005, 0.002);
.fill(0.1, 0.1, 0.1, 0.005, 0.005, 0.002);
public static final double kSlamStdDevsPerMeter = 3;
public static final Pose2d kApproximateStartingPose = new Pose2d(Units.inchesToMeters(508), 0, Rotation2d.fromDegrees(180));
public static final Pose2d kApproximateStartingPose = new Pose2d(Units.inchesToMeters(508), 0,
Rotation2d.fromDegrees(180));
}

public static final class Vision
Expand Down
25 changes: 12 additions & 13 deletions src/main/java/com/spartronics4915/frc2020/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,17 +28,16 @@ public class Robot extends TimedRobot
// PDP is used to detect total-current-draw, in 2019 we had spurious
// CAN errors. If this happens in 2020, we can live without it.
// See more notes in robotPeriodic below.
private PowerDistributionPanel mPDP;
private PowerDistributionPanel mPDP;

private static final String kRobotLogVerbosity = "Robot/Verbosity";

@Override
public void robotInit()
{
Logger.logRobotInit();

try (InputStream manifest =
getClass().getClassLoader().getResourceAsStream("META-INF/MANIFEST.MF"))

try (InputStream manifest = getClass().getClassLoader().getResourceAsStream("META-INF/MANIFEST.MF"))
{
// build a version string
Attributes attributes = new Manifest(manifest).getMainAttributes();
Expand Down Expand Up @@ -67,7 +66,7 @@ public void robotInit()
shed.onCommandInterrupt((c) -> Logger.info(c.getName() + " interrupted"));

// if CAN bus spews, delete (see notes at top)
this.mPDP = new PowerDistributionPanel();
this.mPDP = new PowerDistributionPanel();

// Instantiate our RobotContainer. This will perform all our button bindings,
// and put our autonomous chooser on the dashboard.
Expand All @@ -87,14 +86,14 @@ public void robotInit()
@Override
public void robotPeriodic()
{
// robotPeriodic runs in all "match epochs".
// Oddly, the scheduler is *not* operational during "disabled epoch"
// because it follows the LiveWindow disabled state.
// robotPeriodic runs in all "match epochs".
// Oddly, the scheduler is *not* operational during "disabled epoch"
// because it follows the LiveWindow disabled state.
// The scheduler is responsible for invoking all Subsystem's periodic
// method so we don't expect dashboard updates without this running.
// IterativeRobotBase is the one that controls the LiveWindow state
// and it explicitly disables LiveWindow traffic when the robot is
// disabled. Contrast this with the "test epoch". In this mode, the
// IterativeRobotBase is the one that controls the LiveWindow state
// and it explicitly disables LiveWindow traffic when the robot is
// disabled. Contrast this with the "test epoch". In this mode, the
// scheduler does run as do all LiveWindow functions.
CommandScheduler.getInstance().run();

Expand All @@ -105,7 +104,7 @@ public void robotPeriodic()
// Dashboard can rely on LiveWindow but then we don't receive
// updates when robot is disabled.
SmartDashboard.putNumber("Robot/TotalCurrent", this.mPDP.getTotalCurrent());
}
}

/**
* This function is called once each time the robot enters Disabled mode.
Expand Down Expand Up @@ -168,7 +167,7 @@ public void teleopPeriodic()
public void testInit()
{
CommandScheduler.getInstance().cancelAll();
LED.getInstance().setBlingState(Bling.kDriveSlow);
LED.getInstance().setBlingState(Bling.kDriveSlow); // TODO: cycle through bling animations?
}

/**
Expand Down
Loading

0 comments on commit 6e617fe

Please sign in to comment.