Skip to content

Commit

Permalink
Update map.
Browse files Browse the repository at this point in the history
  • Loading branch information
Noah Gleason committed Jun 28, 2017
1 parent e60db91 commit e8e2f03
Show file tree
Hide file tree
Showing 6 changed files with 152 additions and 139 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
import org.usfirst.frc.team449.robot.interfaces.oi.UnidirectionalOI;
import org.usfirst.frc.team449.robot.interfaces.subsystem.NavX.NavxSubsystem;
import org.usfirst.frc.team449.robot.util.AutoshiftProcessor;
import org.usfirst.frc.team449.robot.util.BufferTimer;
import org.usfirst.frc.team449.robot.util.Logger;
import org.usfirst.frc.team449.robot.util.YamlSubsystem;

Expand All @@ -34,27 +35,26 @@ public class ShiftingUnidirectionalNavXDefaultDrive <T extends YamlSubsystem & U
/**
* Default constructor
*
* @param toleranceBuffer How many consecutive loops have to be run while within tolerance to be
* considered
* on target. Multiply by loop period of ~20 milliseconds for time. Defaults to 0.
* @param absoluteTolerance The maximum number of degrees off from the target at which we can be considered
* within tolerance.
* @param minimumOutput The minimum output of the loop. Defaults to zero.
* @param maximumOutput The maximum output of the loop. Can be null, and if it is, no maximum output is
* used.
* @param deadband The deadband around the setpoint, in degrees, within which no output is given to
* the motors. Defaults to zero.
* @param maxAngularVelToEnterLoop The maximum angular velocity, in degrees/sec, at which the loop will be entered.
* Defaults to 180.
* @param inverted Whether the loop is inverted. Defaults to false.
* @param kP Proportional gain. Defaults to zero.
* @param kI Integral gain. Defaults to zero.
* @param kD Derivative gain. Defaults to zero.
* @param loopEntryDelay The delay to enter the loop after conditions for entry are met. Defaults to
* zero.
* @param subsystem The drive to execute this command on.
* @param oi The OI controlling the robot.
* @param autoshiftProcessor The helper object for autoshifting.
* @param toleranceBuffer How many consecutive loops have to be run while within tolerance to be
* considered on target. Multiply by loop period of ~20 milliseconds for time.
* Defaults to 0.
* @param absoluteTolerance The maximum number of degrees off from the target at which we can be
* considered within tolerance.
* @param minimumOutput The minimum output of the loop. Defaults to zero.
* @param maximumOutput The maximum output of the loop. Can be null, and if it is, no maximum output
* is used.
* @param deadband The deadband around the setpoint, in degrees, within which no output is given
* to the motors. Defaults to zero.
* @param maxAngularVelToEnterLoop The maximum angular velocity, in degrees/sec, at which the loop will be
* entered. Defaults to 180.
* @param inverted Whether the loop is inverted. Defaults to false.
* @param kP Proportional gain. Defaults to zero.
* @param kI Integral gain. Defaults to zero.
* @param kD Derivative gain. Defaults to zero.
* @param driveStraightLoopEntryTimer The buffer timer for starting to drive straight.
* @param subsystem The drive to execute this command on.
* @param oi The OI controlling the robot.
* @param autoshiftProcessor The helper object for autoshifting.
*/
@JsonCreator
public ShiftingUnidirectionalNavXDefaultDrive(@JsonProperty(required = true) double absoluteTolerance,
Expand All @@ -66,12 +66,12 @@ public ShiftingUnidirectionalNavXDefaultDrive(@JsonProperty(required = true) dou
int kP,
int kI,
int kD,
double loopEntryDelay,
@NotNull @JsonProperty(required = true) BufferTimer driveStraightLoopEntryTimer,
@NotNull @JsonProperty(required = true) T subsystem,
@NotNull @JsonProperty(required = true) UnidirectionalOI oi,
@NotNull @JsonProperty(required = true) AutoshiftProcessor autoshiftProcessor) {
super(absoluteTolerance, toleranceBuffer, minimumOutput, maximumOutput, deadband, maxAngularVelToEnterLoop,
inverted, kP, kI, kD, loopEntryDelay, subsystem, oi);
inverted, kP, kI, kD, driveStraightLoopEntryTimer, subsystem, oi);
this.autoshiftProcessor = autoshiftProcessor;
this.subsystem = subsystem;
}
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
package org.usfirst.frc.team449.robot.drive.talonCluster.commands;

import com.fasterxml.jackson.annotation.*;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import org.jetbrains.annotations.NotNull;
import org.jetbrains.annotations.Nullable;
import org.usfirst.frc.team449.robot.interfaces.drive.unidirectional.UnidirectionalDrive;
Expand Down Expand Up @@ -50,26 +49,25 @@ public class UnidirectionalNavXDefaultDrive <T extends YamlSubsystem & Unidirect
/**
* Default constructor
*
* @param toleranceBuffer How many consecutive loops have to be run while within tolerance to be
* considered on target. Multiply by loop period of ~20 milliseconds for time.
* Defaults to 0.
* @param absoluteTolerance The maximum number of degrees off from the target at which we can be
* considered within tolerance.
* @param minimumOutput The minimum output of the loop. Defaults to zero.
* @param maximumOutput The maximum output of the loop. Can be null, and if it is, no maximum output
* is used.
* @param deadband The deadband around the setpoint, in degrees, within which no output is given
* to the motors. Defaults to zero.
* @param maxAngularVelToEnterLoop The maximum angular velocity, in degrees/sec, at which the loop will be
* entered. Defaults to 180.
* @param inverted Whether the loop is inverted. Defaults to false.
* @param kP Proportional gain. Defaults to zero.
* @param kI Integral gain. Defaults to zero.
* @param kD Derivative gain. Defaults to zero.
* @param loopEntryDelay The delay to enter the loop after conditions for entry are met. Defaults to
* zero.
* @param subsystem The drive to execute this command on.
* @param oi The OI controlling the robot.
* @param toleranceBuffer How many consecutive loops have to be run while within tolerance to be
* considered on target. Multiply by loop period of ~20 milliseconds for time.
* Defaults to 0.
* @param absoluteTolerance The maximum number of degrees off from the target at which we can be
* considered within tolerance.
* @param minimumOutput The minimum output of the loop. Defaults to zero.
* @param maximumOutput The maximum output of the loop. Can be null, and if it is, no maximum output
* is used.
* @param deadband The deadband around the setpoint, in degrees, within which no output is given
* to the motors. Defaults to zero.
* @param maxAngularVelToEnterLoop The maximum angular velocity, in degrees/sec, at which the loop will be
* entered. Defaults to 180.
* @param inverted Whether the loop is inverted. Defaults to false.
* @param kP Proportional gain. Defaults to zero.
* @param kI Integral gain. Defaults to zero.
* @param kD Derivative gain. Defaults to zero.
* @param driveStraightLoopEntryTimer The buffer timer for starting to drive straight.
* @param subsystem The drive to execute this command on.
* @param oi The OI controlling the robot.
*/
@JsonCreator
public UnidirectionalNavXDefaultDrive(@JsonProperty(required = true) double absoluteTolerance,
Expand All @@ -81,15 +79,15 @@ public UnidirectionalNavXDefaultDrive(@JsonProperty(required = true) double abso
int kP,
int kI,
int kD,
double loopEntryDelay,
@NotNull @JsonProperty(required = true) BufferTimer driveStraightLoopEntryTimer,
@NotNull @JsonProperty(required = true) T subsystem,
@NotNull @JsonProperty(required = true) UnidirectionalOI oi) {
//Assign stuff
super(absoluteTolerance, toleranceBuffer, minimumOutput, maximumOutput, deadband, inverted, subsystem, kP, kI, kD);
this.oi = oi;
this.subsystem = subsystem;

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

//Needs a requires because it's a default command.
Expand Down Expand Up @@ -138,9 +136,6 @@ else if (driveStraightLoopEntryTimer.get(!(subsystem.getOverrideNavX()) && !(dri
this.getPIDController().enable();
Logger.addEvent("Switching to DriveStraight.", this.getClass());
}

//Log data and stuff
SmartDashboard.putBoolean("driving straight?", drivingStraight);
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,10 +39,10 @@ public class ClimberSubsystem extends YamlSubsystem implements Loggable, BinaryM
private final double maxPower;

/**
* The bufferTimer controlling how long we can be above the current limit before we stop climbing.
* The bufferTimer controlling how long we can be above the power limit before we stop climbing.
*/
@NotNull
private final BufferTimer currentLimitTimer;
private final BufferTimer powerLimitTimer;

/**
* Whether or not the motor is currently spinning.
Expand All @@ -53,23 +53,22 @@ public class ClimberSubsystem extends YamlSubsystem implements Loggable, BinaryM
/**
* Default constructor
*
* @param talonSRX The CANTalon controlling one of the climber motors.
* @param maxPower The maximum power at which the motor won't shut off.
* @param victor The VictorSP controlling the other climber motor. Can be null.
* @param millisAboveMaxPower The number of milliseconds it takes to shut off the climber after being above the
* current limit. Defaults to 0.
* @param talonSRX The CANTalon controlling one of the climber motors.
* @param maxPower The maximum power at which the motor won't shut off.
* @param victor The VictorSP controlling the other climber motor. Can be null.
* @param powerLimitTimer The buffer timer for the power-limited shutoff.
*/
@JsonCreator
public ClimberSubsystem(@NotNull @JsonProperty(required = true) RotPerSecCANTalonSRX talonSRX,
@JsonProperty(required = true) double maxPower,
@Nullable MappedVictor victor,
int millisAboveMaxPower) {
@NotNull @JsonProperty(required = true) BufferTimer powerLimitTimer) {
//Instantiate things
canTalonSRX = talonSRX;
this.canTalonSRX = talonSRX;
this.maxPower = maxPower;
currentLimitTimer = new BufferTimer(millisAboveMaxPower);
motorSpinning = false;
this.powerLimitTimer = powerLimitTimer;
this.victor = victor;
this.motorSpinning = false;
}

/**
Expand Down Expand Up @@ -163,12 +162,12 @@ public boolean isMotorOn() {
}

/**
* Whether or not the current limit has been exceeded
* Whether or not the power limit has been exceeded
*
* @return true if exceeded, false otherwise
*/
@Override
public boolean isConditionTrue() {
return currentLimitTimer.get(Math.abs(canTalonSRX.getPower()) > maxPower);
return powerLimitTimer.get(Math.abs(canTalonSRX.getPower()) > maxPower);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -61,35 +61,32 @@ public class AutoshiftProcessor {
/**
* Default constructor
*
* @param upshiftSpeed The minimum speed both sides the drive must be going at to shift to high
* gear.
* @param downshiftSpeed The maximum speed both sides must be going at to shift to low gear.
* @param delayAfterUpshiftConditionsMet How long, in seconds, the conditions to upshift have to be met for before
* upshifting happens. Defaults to 0.
* @param delayAfterDownshiftConditionsMet How long, in seconds, the conditions to downshift have to be met for
* before downshifting happens. Defaults to 0.
* @param cooldownAfterDownshift The minimum time, in seconds, between downshifting and then upshifting
* again. Defaults to 0.
* @param cooldownAfterUpshift The minimum time, in seconds, between upshifting and then downshifting
* again. Defaults to 0.
* @param upshiftFwdThresh The minimum amount the forward joystick must be pushed forward in order
* to upshift, on [0, 1]. Defaults to 0.
* @param upshiftSpeed The minimum speed both sides the drive must be going at to shift to high gear.
* @param downshiftSpeed The maximum speed both sides must be going at to shift to low gear.
* @param upshiftBufferTimer Buffer timer for upshifting.
* @param downshiftBufferTimer Buffer timer for downshifting.
* @param cooldownAfterDownshift The minimum time, in seconds, between downshifting and then upshifting again.
* Defaults to 0.
* @param cooldownAfterUpshift The minimum time, in seconds, between upshifting and then downshifting again.
* Defaults to 0.
* @param upshiftFwdThresh The minimum amount the forward joystick must be pushed forward in order to upshift,
* on [0, 1]. Defaults to 0.
*/
@JsonCreator
public AutoshiftProcessor(@JsonProperty(required = true) double upshiftSpeed,
@JsonProperty(required = true) double downshiftSpeed,
@NotNull @JsonProperty(required = true) BufferTimer upshiftBufferTimer,
@NotNull @JsonProperty(required = true) BufferTimer downshiftBufferTimer,
double upshiftFwdThresh,
double cooldownAfterUpshift,
double cooldownAfterDownshift,
double delayAfterUpshiftConditionsMet,
double delayAfterDownshiftConditionsMet) {
double cooldownAfterDownshift) {
this.upshiftSpeed = upshiftSpeed;
this.downshiftSpeed = downshiftSpeed;
this.upshiftFwdThresh = upshiftFwdThresh;
this.cooldownAfterUpshift = (long) (cooldownAfterUpshift * 1000.);
this.cooldownAfterDownshift = (long) (cooldownAfterDownshift * 1000.);
this.upshiftBufferTimer = new BufferTimer(delayAfterUpshiftConditionsMet);
this.downshiftBufferTimer = new BufferTimer(delayAfterDownshiftConditionsMet);
this.upshiftBufferTimer = upshiftBufferTimer;
this.downshiftBufferTimer = downshiftBufferTimer;
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@

import com.fasterxml.jackson.annotation.JsonCreator;
import com.fasterxml.jackson.annotation.JsonIdentityInfo;
import com.fasterxml.jackson.annotation.JsonProperty;
import com.fasterxml.jackson.annotation.ObjectIdGenerators;
import org.usfirst.frc.team449.robot.Robot;

Expand Down Expand Up @@ -30,10 +29,10 @@ public class BufferTimer {
/**
* Constructor for a time given in seconds.
*
* @param bufferTimeSeconds The amount of time the condition has to be true for, in seconds.
* @param bufferTimeSeconds The amount of time the condition has to be true for, in seconds. Defaults to 0.
*/
@JsonCreator
public BufferTimer(@JsonProperty(required = true) double bufferTimeSeconds) {
public BufferTimer(double bufferTimeSeconds) {
bufferTime = (long) (bufferTimeSeconds * 1000.);
}

Expand Down
Loading

0 comments on commit e8e2f03

Please sign in to comment.