Skip to content

Commit

Permalink
Merge pull request #73 from blair-robot-project/jackson_everything
Browse files Browse the repository at this point in the history
Jackson everything
  • Loading branch information
Noah Gleason authored Jun 28, 2017
2 parents 0357b72 + 17f4018 commit 8a28576
Show file tree
Hide file tree
Showing 23 changed files with 242 additions and 157 deletions.
19 changes: 12 additions & 7 deletions RoboRIO/src/main/java/org/usfirst/frc/team449/robot/RobotMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
import org.jetbrains.annotations.Nullable;
import org.usfirst.frc.team449.robot.components.MappedDigitalInput;
import org.usfirst.frc.team449.robot.drive.talonCluster.TalonClusterDrive;
import org.usfirst.frc.team449.robot.drive.talonCluster.commands.UnidirectionalNavXDefaultDrive;
import org.usfirst.frc.team449.robot.mechanism.activegear.ActiveGearSubsystem;
import org.usfirst.frc.team449.robot.mechanism.climber.ClimberSubsystem;
import org.usfirst.frc.team449.robot.mechanism.intake.Intake2017.Intake2017;
Expand Down Expand Up @@ -119,18 +118,24 @@ public class RobotMap {
* 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 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 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 Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,10 +47,12 @@ public MappedThrottle(@NotNull @JsonProperty(required = true) MappedJoystick sti
}

/**
* Gets the raw value from the stick and inverts it if necessary. This is private so it's not overriden, allowing it to be used by both getValue and pidGet without causing a circular reference.
* Gets the raw value from the stick and inverts it if necessary. This is private so it's not overriden, allowing it
* to be used by both getValue and pidGet without causing a circular reference.
*
* @return The raw joystick output, on [-1, 1].
*/
private double getValuePrivate(){
private double getValuePrivate() {
return (inverted ? -1 : 1) * stick.getRawAxis(axis);
}

Expand Down
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 @@ -66,8 +65,7 @@ public class UnidirectionalNavXDefaultDrive <T extends YamlSubsystem & Unidirect
* @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 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.
*/
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
@@ -1,8 +1,11 @@
package org.usfirst.frc.team449.robot.interfaces.oi;

import com.fasterxml.jackson.annotation.JsonTypeInfo;

/**
* An arcade-style dual joystick OI.
*/
@JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class")
public abstract class ArcadeOI implements UnidirectionalOI {

/**
Expand Down Expand Up @@ -39,10 +42,11 @@ public double getRightOutput() {

/**
* Whether the driver is trying to drive straight.
*
* @return True if the driver is trying to drive straight, false otherwise.
*/
@Override
public boolean commandingStraight(){
public boolean commandingStraight() {
return getRot() == 0;
}
}
Original file line number Diff line number Diff line change
@@ -1,8 +1,11 @@
package org.usfirst.frc.team449.robot.interfaces.oi;

import com.fasterxml.jackson.annotation.JsonTypeInfo;

/**
* A tank-style dual joystick OI.
*/
@JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class")
public abstract class TankOI implements UnidirectionalOI {

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ public interface UnidirectionalOI {

/**
* Whether the driver is trying to drive straight.
*
* @return True if the driver is trying to drive straight, false otherwise.
*/
boolean commandingStraight();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ public abstract class PIDAngleCommand extends PIDCommand implements YamlCommand
* @param kP Proportional gain. Defaults to zero.
* @param kI Integral gain. Defaults to zero.
* @param kD Derivative gain. Defaults to zero.
* @param subsystem The subsystem to execute this command on.
* @param subsystem The subsystem to execute this command on.
*/
@JsonCreator
public PIDAngleCommand(@JsonProperty(required = true) double absoluteTolerance,
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 @@ -5,7 +5,6 @@
import com.fasterxml.jackson.annotation.JsonProperty;
import com.fasterxml.jackson.annotation.ObjectIdGenerators;
import org.jetbrains.annotations.NotNull;
import org.usfirst.frc.team449.robot.components.MappedSmoothedThrottle;
import org.usfirst.frc.team449.robot.components.MappedThrottle;
import org.usfirst.frc.team449.robot.interfaces.oi.ArcadeOI;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@
import com.fasterxml.jackson.annotation.JsonProperty;
import com.fasterxml.jackson.annotation.ObjectIdGenerators;
import org.jetbrains.annotations.NotNull;
import org.usfirst.frc.team449.robot.components.MappedSmoothedThrottle;
import org.usfirst.frc.team449.robot.components.MappedThrottle;
import org.usfirst.frc.team449.robot.interfaces.oi.TankOI;

Expand Down Expand Up @@ -35,9 +34,10 @@ public class SimpleTankOI extends TankOI {
/**
* Default constructor
*
* @param leftThrottle The throttle for controlling the velocity of the left side of the drive.
* @param rightThrottle The throttle for controlling the velocity of the right side of the drive.
* @param commandingStraightTolerance The difference between left and right input within which the driver is considered to be trying to drive straight. Defaults to 0.
* @param leftThrottle The throttle for controlling the velocity of the left side of the drive.
* @param rightThrottle The throttle for controlling the velocity of the right side of the drive.
* @param commandingStraightTolerance The difference between left and right input within which the driver is
* considered to be trying to drive straight. Defaults to 0.
*/
@JsonCreator
public SimpleTankOI(@NotNull @JsonProperty(required = true) MappedThrottle leftThrottle,
Expand All @@ -56,8 +56,8 @@ public SimpleTankOI(@NotNull @JsonProperty(required = true) MappedThrottle leftT
@Override
public double getLeftThrottle() {
//If the driver is trying to drive straight, use the average of the two sticks.
if (commandingStraight()){
return (leftThrottle.getValue()+rightThrottle.getValue())/2.;
if (commandingStraight()) {
return (leftThrottle.getValue() + rightThrottle.getValue()) / 2.;
}
return leftThrottle.getValue();
}
Expand All @@ -70,8 +70,8 @@ public double getLeftThrottle() {
@Override
public double getRightThrottle() {
//If the driver is trying to drive straight, use the average of the two sticks.
if (commandingStraight()){
return (leftThrottle.getValue()+rightThrottle.getValue())/2.;
if (commandingStraight()) {
return (leftThrottle.getValue() + rightThrottle.getValue()) / 2.;
}
return rightThrottle.getValue();
}
Expand All @@ -83,6 +83,6 @@ public double getRightThrottle() {
*/
@Override
public boolean commandingStraight() {
return Math.abs(leftThrottle.getValue()-rightThrottle.getValue()) <= commandingStraightTolerance;
return Math.abs(leftThrottle.getValue() - rightThrottle.getValue()) <= commandingStraightTolerance;
}
}
Loading

0 comments on commit 8a28576

Please sign in to comment.