Skip to content

Commit

Permalink
Merge pull request #72 from blair-robot-project/oneline_defaults
Browse files Browse the repository at this point in the history
Oneline defaults
  • Loading branch information
Noah Gleason authored Jun 28, 2017
2 parents 1a52c46 + 39768d2 commit 0357b72
Show file tree
Hide file tree
Showing 15 changed files with 63 additions and 86 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -230,11 +230,11 @@ public void robotInit() {
robotMap.getRightProfiles().get(allianceString + "_" + position));
//Set the autonomousCommand to be the correct command for the current position and alliance.
if (position.equals("center")) {
autonomousCommand = robotMap.getCenterAuto().getCommand();
autonomousCommand = robotMap.getCenterAuto();
} else if ((position.equals("right") && redAlliance) || (position.equals("left") && !redAlliance)) {
autonomousCommand = robotMap.getBoilerAuto().getCommand();
autonomousCommand = robotMap.getBoilerAuto();
} else {
autonomousCommand = robotMap.getFeederAuto().getCommand();
autonomousCommand = robotMap.getFeederAuto();
}
}
} else {
Expand Down
60 changes: 22 additions & 38 deletions RoboRIO/src/main/java/org/usfirst/frc/team449/robot/RobotMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ public class RobotMap {
private final TalonClusterDrive drive;

@NotNull
private final UnidirectionalNavXDefaultDrive defaultDriveCommand;
private final Command defaultDriveCommand;

@Nullable
private final ClimberSubsystem climber;
Expand Down Expand Up @@ -71,13 +71,13 @@ public class RobotMap {
private final MappedDigitalInput locationDial;

@Nullable
private final YamlCommand boilerAuto;
private final Command boilerAuto;

@Nullable
private final YamlCommand centerAuto;
private final Command centerAuto;

@Nullable
private final YamlCommand feederAuto;
private final Command feederAuto;

@Nullable
private final MotionProfileData leftTestProfile;
Expand Down Expand Up @@ -116,37 +116,21 @@ public class RobotMap {
* @param gearHandler The gear handler on this robot. Can be null.
* @param RIOduinoPort The I2C port of the RIOduino plugged into this robot. Can be null.
* @param allianceSwitch The switch for selecting which alliance we're on. Can be null if doMP is false or
* testMP
* is true, but otherwise must have a value.
* @param dropGearSwitch The switch for deciding whether or not to drop the gear. Can be null if doMP is false
* or
* testMP is true, but otherwise must have a value.
* @param locationDial The dial for selecting which side of the field the robot is on. Can be null if doMP
* is
* false or testMP is true, but otherwise must have a value.
* @param boilerAuto The command to run in autonomous on the boiler side of the field. Can be null if doMP
* is
* false or testMP is true, but otherwise must have a value.
* @param centerAuto The command to run in autonomous on the center of the field. Can be null if doMP is
* false
* @param dropGearSwitch The switch for deciding whether or not to drop the gear. Can be null if doMP is false
* or testMP is true, but otherwise must have a value.
* @param feederAuto The command to run in autonomous on the feeding station side of the field. Can be
* null
* if
* doMP is false or testMP is true, but otherwise must have a value.
* @param locationDial The dial for selecting which side of the field the robot is on. Can be null if doMP is false or testMP is true, but otherwise must have a value.
* @param boilerAuto The command to run in autonomous on the boiler side of the field. Can be null if doMP is false or testMP is true, but otherwise must have a value.
* @param centerAuto The command to run in autonomous on the center of the field. Can be null if doMP is
* false or testMP is true, but otherwise must have a value.
* @param feederAuto The command to run in autonomous on the feeding station side of the field. Can be null if doMP is false or testMP is true, but otherwise must have a value.
* @param leftTestProfile The profile for the left side of the drive to run in test mode. Can be null if either
* testMP or doMP are false, but otherwise must have a value.
* @param rightTestProfile The profile for the right side of the drive to run in test mode. Can be null if
* either
* testMP or doMP are false, but otherwise must have a value.
* @param rightTestProfile The profile for the right side of the drive to run in test mode. Can be null if either testMP or doMP are false, but otherwise must have a value.
* @param leftProfiles The starting position to peg profiles for the left side. Should have options for
* "red_right", "red_center", "red_left", "blue_right", "blue_center", and "blue_left".
* Can
* be null if doMP is false or testMP is true, but otherwise must have a value.
* "red_right", "red_center", "red_left", "blue_right", "blue_center", and "blue_left". Can be null if doMP is false or testMP is true, but otherwise must have a value.
* @param rightProfiles The starting position to peg profiles for the right side. Should have options for
* "red_right", "red_center", "red_left", "blue_right", "blue_center", and "blue_left".
* Can
* be null if doMP is false or testMP is true, but otherwise must have a value.
* "red_right", "red_center", "red_left", "blue_right", "blue_center", and "blue_left". Can be null if doMP is false or testMP is true, but otherwise must have a value.
* @param nonMPAutoCommand The command to run during autonomous if doMP is false. Can be null, and if it is, no
* command is run during autonomous.
* @param testMP Whether to run the test or real motion profile during autonomous. Defaults to false.
Expand All @@ -157,7 +141,7 @@ public RobotMap(@NotNull @JsonProperty(required = true) List<CommandButton> butt
@NotNull @JsonProperty(required = true) ArcadeOIWithDPad arcadeOI,
@NotNull @JsonProperty(required = true) Logger logger,
@NotNull @JsonProperty(required = true) TalonClusterDrive drive,
@NotNull @JsonProperty(required = true) UnidirectionalNavXDefaultDrive defaultDriveCommand,
@NotNull @JsonProperty(required = true) YamlCommand defaultDriveCommand,
@Nullable ClimberSubsystem climber,
@Nullable SingleFlywheelShooter shooter,
@Nullable CameraSubsystem camera,
Expand Down Expand Up @@ -190,14 +174,14 @@ public RobotMap(@NotNull @JsonProperty(required = true) List<CommandButton> butt
this.allianceSwitch = allianceSwitch;
this.dropGearSwitch = dropGearSwitch;
this.locationDial = locationDial;
this.boilerAuto = boilerAuto;
this.centerAuto = centerAuto;
this.feederAuto = feederAuto;
this.boilerAuto = boilerAuto != null ? boilerAuto.getCommand() : null;
this.centerAuto = centerAuto != null ? centerAuto.getCommand() : null;
this.feederAuto = feederAuto != null ? feederAuto.getCommand() : null;
this.leftTestProfile = leftTestProfile;
this.rightTestProfile = rightTestProfile;
this.leftProfiles = leftProfiles;
this.rightProfiles = rightProfiles;
this.defaultDriveCommand = defaultDriveCommand;
this.defaultDriveCommand = defaultDriveCommand.getCommand();
if (nonMPAutoCommand != null) {
this.nonMPAutoCommand = nonMPAutoCommand.getCommand();
} else {
Expand Down Expand Up @@ -299,17 +283,17 @@ public Map<String, MotionProfileData> getRightProfiles() {
}

@Nullable
public YamlCommand getBoilerAuto() {
public Command getBoilerAuto() {
return boilerAuto;
}

@Nullable
public YamlCommand getCenterAuto() {
public Command getCenterAuto() {
return centerAuto;
}

@Nullable
public YamlCommand getFeederAuto() {
public Command getFeederAuto() {
return feederAuto;
}

Expand All @@ -319,7 +303,7 @@ public Command getNonMPAutoCommand() {
}

@NotNull
public UnidirectionalNavXDefaultDrive getDefaultDriveCommand() {
public Command getDefaultDriveCommand() {
return defaultDriveCommand;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,12 +11,25 @@
@JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class)
public class MappedSmoothedThrottle extends MappedThrottle {

/**
* The value below which the joystick input is considered 0.
*/
protected final double deadband;

/**
* The smoothing filter for the joystick input.
*/
@NotNull
private final LinearDigitalFilter filter;

/**
* The input from the joystick. Declared outside of getValue to avoid garbage collection.
*/
private double input;

/**
* The sign of the input from the joystick. Declared outside of getValue to avoid garbage collection.
*/
private double sign;

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -213,20 +213,12 @@ public RotPerSecCANTalonSRX(@JsonProperty(required = true) int port,
//Set high/only gear nominal voltages
this.highGearFwdNominalOutputVoltage = highGearFwdNominalOutputVoltage;
//If no reverse nominal voltage is given, assume symmetry.
if (highGearRevNominalOutputVoltage == null) {
this.highGearRevNominalOutputVoltage = highGearFwdNominalOutputVoltage;
} else {
this.highGearRevNominalOutputVoltage = highGearRevNominalOutputVoltage;
}
this.highGearRevNominalOutputVoltage = highGearRevNominalOutputVoltage != null ? highGearRevNominalOutputVoltage : highGearFwdNominalOutputVoltage;

//Set low gear nominal voltages
this.lowGearFwdNominalOutputVoltage = lowGearFwdNominalOutputVoltage;
//If no reverse nominal voltage is given, assume symmetry.
if (lowGearRevNominalOutputVoltage == null) {
this.lowGearRevNominalOutputVoltage = lowGearFwdNominalOutputVoltage;
} else {
this.lowGearRevNominalOutputVoltage = lowGearRevNominalOutputVoltage;
}
this.lowGearRevNominalOutputVoltage = lowGearRevNominalOutputVoltage != null ? lowGearRevNominalOutputVoltage : lowGearFwdNominalOutputVoltage;

//Set to high gear by default.
canTalon.configNominalOutputVoltage(this.highGearFwdNominalOutputVoltage, -this.highGearRevNominalOutputVoltage);
Expand Down Expand Up @@ -269,17 +261,10 @@ public RotPerSecCANTalonSRX(@JsonProperty(required = true) int port,
}

//postEncoderGearing defaults to 1
if (postEncoderGearing == null) {
this.postEncoderGearing = 1.;
} else {
this.postEncoderGearing = postEncoderGearing;
}
this.postEncoderGearing = postEncoderGearing != null ? postEncoderGearing : 1.;

//Configure the maximum output voltage. If only forward voltage was given, use it for both forward and reverse.
if (revPeakOutputVoltage == null) {
revPeakOutputVoltage = fwdPeakOutputVoltage;
}
canTalon.configPeakOutputVoltage(fwdPeakOutputVoltage, -revPeakOutputVoltage);
canTalon.configPeakOutputVoltage(fwdPeakOutputVoltage, revPeakOutputVoltage != null ? -revPeakOutputVoltage : -fwdPeakOutputVoltage);

//Set the current limit if it was given
if (currentLimit != null) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,11 +67,7 @@ public ShiftingTalonClusterDrive(@NotNull @JsonProperty(required = true) RotPerS
this.shifter = shifter;

//Default to low
if (startingGear == null) {
this.startingGear = gear.LOW;
} else {
this.startingGear = startingGear;
}
this.startingGear = startingGear != null ? startingGear : gear.LOW;
currentGear = this.startingGear;

// Initialize shifting constants, assuming robot is stationary.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,10 +75,7 @@ public TalonClusterDrive(@NotNull @JsonProperty(required = true) RotPerSecCANTal
@Nullable Double PIDScale) {
super();
//Initialize stuff
if (PIDScale == null) {
PIDScale = 1.;
}
PID_SCALE = PIDScale;
this.PID_SCALE = PIDScale != null ? PIDScale : 1.;
this.rightMaster = rightMaster;
this.leftMaster = leftMaster;
this.mpHandler = MPHandler;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -90,10 +90,7 @@ public UnidirectionalNavXDefaultDrive(@JsonProperty(required = true) double abso
this.subsystem = subsystem;

driveStraightLoopEntryTimer = new BufferTimer(loopEntryDelay);
if (maxAngularVelToEnterLoop == null) {
maxAngularVelToEnterLoop = 180.;
}
this.maxAngularVelToEnterLoop = maxAngularVelToEnterLoop;
this.maxAngularVelToEnterLoop = maxAngularVelToEnterLoop != null ? maxAngularVelToEnterLoop : 180;

//Needs a requires because it's a default command.
requires(this.subsystem);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ public PIDAngleCommand(@JsonProperty(required = true) double absoluteTolerance,
//This caps the output we can give. One way to set up closed-loop is to make P large and then use this to
// prevent overshoot.
if (maximumOutput != null) {
this.getPIDController().setOutputRange(-minimumOutput, maximumOutput);
this.getPIDController().setOutputRange(-maximumOutput, maximumOutput);
}

//Set a deadband around the setpoint, in degrees, within which don't move, to avoid "dancing"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,6 @@ public class RunMotorWhileConditonMet <T extends YamlSubsystem & BinaryMotorSubs
public RunMotorWhileConditonMet(@NotNull @JsonProperty(required = true) T subsystem) {
requires(subsystem);
this.subsystem = subsystem;
Logger.addEvent("RunMotorWhileConditonMet constructed", this.getClass());
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,6 @@ public class PneumaticsSubsystem extends YamlSubsystem implements Loggable {
@JsonCreator
public PneumaticsSubsystem(@JsonProperty(required = true) int nodeID,
@Nullable PressureSensor pressureSensor) {
super();
compressor = new Compressor(nodeID);
this.pressureSensor = pressureSensor;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@ public class StartCompressor extends YamlCommandWrapper {
*/
@JsonCreator
public StartCompressor(@NotNull @JsonProperty(required = true) PneumaticsSubsystem subsystem) {
super();
this.subsystem = subsystem;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,6 @@ public SingleFlywheelShooter(@NotNull @JsonProperty(required = true) RotPerSecCA
@NotNull @JsonProperty(required = true) MappedVictor feederVictor,
@JsonProperty(required = true) double feederThrottle,
double spinUpTimeSecs) {
super();
this.shooterTalon = shooterTalon;
this.shooterThrottle = shooterThrottle;
this.feederVictor = feederVictor;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,17 +42,24 @@ public class ArcadeOIWithDPad extends ArcadeOI {
@Nullable
private final Joystick gamepad;

/**
* The polynomial to scale the forwards throttle output by before using it to scale the rotational throttle. Can be
* null, and if it is, rotational throttle is not scaled by forwards throttle.
*/
@Nullable
private final Polynomial scaleRotByFwdPoly;

/**
* Default constructor
*
* @param gamepad The gamepad containing the joysticks and buttons. Can be null if not using the D-pad.
* @param rotThrottle The throttle for rotating the robot.
* @param fwdThrottle The throttle for driving the robot straight.
* @param invertDPad Whether or not to invert the D-pad. Defaults to false.
* @param dPadShift How fast the dPad should turn the robot, on [0, 1]. Defaults to 0.
* @param gamepad The gamepad containing the joysticks and buttons. Can be null if not using the D-pad.
* @param rotThrottle The throttle for rotating the robot.
* @param fwdThrottle The throttle for driving the robot straight.
* @param invertDPad Whether or not to invert the D-pad. Defaults to false.
* @param dPadShift How fast the dPad should turn the robot, on [0, 1]. Defaults to 0.
* @param scaleRotByFwdPoly The polynomial to scale the forwards throttle output by before using it to scale the
* rotational throttle. Can be null, and if it is, rotational throttle is not scaled by
* forwards throttle.
*/
@JsonCreator
public ArcadeOIWithDPad(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@ public abstract class FactoryButton extends Button {
* {@link dPadButton}.
* @return A Button constructed from the given parameters.
*/
@NotNull
@JsonCreator
public static FactoryButton constructButton(@NotNull @JsonProperty(required = true) MappedJoystick joystick,
@Nullable Integer buttonNumber,
Expand Down
7 changes: 4 additions & 3 deletions RoboRIO/src/main/resources/calcifer_map.yml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
---
doMP: false
doMP: true
testMP: false
leftTestProfile:
&leftTest
Expand Down Expand Up @@ -83,12 +83,13 @@ arcadeOI:
axis: 0
smoothingTimeConstantSecs: 0.04
deadband: 0.05
inverted: true
inverted: false
fwdThrottle:
org.usfirst.frc.team449.robot.components.MappedSmoothedThrottle:
<<: *rotThrottle
'@id': fwdThrottle
axis: 5
inverted: true
invertDPad: true
dPadShift: 0.1
drive:
Expand Down Expand Up @@ -156,7 +157,7 @@ drive:
module: 15
forward: 2
reverse: 3
startingGear: HIGH
startingGear: LOW
defaultDriveCommand:
org.usfirst.frc.team449.robot.drive.talonCluster.commands.ShiftingUnidirectionalNavXDefaultDrive:
'@id': defaultDriveCommand
Expand Down

0 comments on commit 0357b72

Please sign in to comment.