Skip to content

Commit 8a28576

Browse files
author
Noah Gleason
authored
Merge pull request #73 from blair-robot-project/jackson_everything
Jackson everything
2 parents 0357b72 + 17f4018 commit 8a28576

23 files changed

+242
-157
lines changed

RoboRIO/src/main/java/org/usfirst/frc/team449/robot/RobotMap.java

Lines changed: 12 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,6 @@
77
import org.jetbrains.annotations.Nullable;
88
import org.usfirst.frc.team449.robot.components.MappedDigitalInput;
99
import org.usfirst.frc.team449.robot.drive.talonCluster.TalonClusterDrive;
10-
import org.usfirst.frc.team449.robot.drive.talonCluster.commands.UnidirectionalNavXDefaultDrive;
1110
import org.usfirst.frc.team449.robot.mechanism.activegear.ActiveGearSubsystem;
1211
import org.usfirst.frc.team449.robot.mechanism.climber.ClimberSubsystem;
1312
import org.usfirst.frc.team449.robot.mechanism.intake.Intake2017.Intake2017;
@@ -119,18 +118,24 @@ public class RobotMap {
119118
* testMP is true, but otherwise must have a value.
120119
* @param dropGearSwitch The switch for deciding whether or not to drop the gear. Can be null if doMP is false
121120
* or testMP is true, but otherwise must have a value.
122-
* @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.
123-
* @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.
121+
* @param locationDial The dial for selecting which side of the field the robot is on. Can be null if doMP is
122+
* false or testMP is true, but otherwise must have a value.
123+
* @param boilerAuto The command to run in autonomous on the boiler side of the field. Can be null if doMP
124+
* is false or testMP is true, but otherwise must have a value.
124125
* @param centerAuto The command to run in autonomous on the center of the field. Can be null if doMP is
125126
* false or testMP is true, but otherwise must have a value.
126-
* @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.
127+
* @param feederAuto The command to run in autonomous on the feeding station side of the field. Can be null
128+
* if doMP is false or testMP is true, but otherwise must have a value.
127129
* @param leftTestProfile The profile for the left side of the drive to run in test mode. Can be null if either
128130
* testMP or doMP are false, but otherwise must have a value.
129-
* @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.
131+
* @param rightTestProfile The profile for the right side of the drive to run in test mode. Can be null if either
132+
* testMP or doMP are false, but otherwise must have a value.
130133
* @param leftProfiles The starting position to peg profiles for the left side. Should have options for
131-
* "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.
134+
* "red_right", "red_center", "red_left", "blue_right", "blue_center", and "blue_left".
135+
* Can be null if doMP is false or testMP is true, but otherwise must have a value.
132136
* @param rightProfiles The starting position to peg profiles for the right side. Should have options for
133-
* "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.
137+
* "red_right", "red_center", "red_left", "blue_right", "blue_center", and "blue_left".
138+
* Can be null if doMP is false or testMP is true, but otherwise must have a value.
134139
* @param nonMPAutoCommand The command to run during autonomous if doMP is false. Can be null, and if it is, no
135140
* command is run during autonomous.
136141
* @param testMP Whether to run the test or real motion profile during autonomous. Defaults to false.

RoboRIO/src/main/java/org/usfirst/frc/team449/robot/components/MappedThrottle.java

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -47,10 +47,12 @@ public MappedThrottle(@NotNull @JsonProperty(required = true) MappedJoystick sti
4747
}
4848

4949
/**
50-
* 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.
50+
* Gets the raw value from the stick and inverts it if necessary. This is private so it's not overriden, allowing it
51+
* to be used by both getValue and pidGet without causing a circular reference.
52+
*
5153
* @return The raw joystick output, on [-1, 1].
5254
*/
53-
private double getValuePrivate(){
55+
private double getValuePrivate() {
5456
return (inverted ? -1 : 1) * stick.getRawAxis(axis);
5557
}
5658

RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/talonCluster/commands/ShiftingUnidirectionalNavXDefaultDrive.java

Lines changed: 23 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88
import org.usfirst.frc.team449.robot.interfaces.oi.UnidirectionalOI;
99
import org.usfirst.frc.team449.robot.interfaces.subsystem.NavX.NavxSubsystem;
1010
import org.usfirst.frc.team449.robot.util.AutoshiftProcessor;
11+
import org.usfirst.frc.team449.robot.util.BufferTimer;
1112
import org.usfirst.frc.team449.robot.util.Logger;
1213
import org.usfirst.frc.team449.robot.util.YamlSubsystem;
1314

@@ -34,27 +35,26 @@ public class ShiftingUnidirectionalNavXDefaultDrive <T extends YamlSubsystem & U
3435
/**
3536
* Default constructor
3637
*
37-
* @param toleranceBuffer How many consecutive loops have to be run while within tolerance to be
38-
* considered
39-
* on target. Multiply by loop period of ~20 milliseconds for time. Defaults to 0.
40-
* @param absoluteTolerance The maximum number of degrees off from the target at which we can be considered
41-
* within tolerance.
42-
* @param minimumOutput The minimum output of the loop. Defaults to zero.
43-
* @param maximumOutput The maximum output of the loop. Can be null, and if it is, no maximum output is
44-
* used.
45-
* @param deadband The deadband around the setpoint, in degrees, within which no output is given to
46-
* the motors. Defaults to zero.
47-
* @param maxAngularVelToEnterLoop The maximum angular velocity, in degrees/sec, at which the loop will be entered.
48-
* Defaults to 180.
49-
* @param inverted Whether the loop is inverted. Defaults to false.
50-
* @param kP Proportional gain. Defaults to zero.
51-
* @param kI Integral gain. Defaults to zero.
52-
* @param kD Derivative gain. Defaults to zero.
53-
* @param loopEntryDelay The delay to enter the loop after conditions for entry are met. Defaults to
54-
* zero.
55-
* @param subsystem The drive to execute this command on.
56-
* @param oi The OI controlling the robot.
57-
* @param autoshiftProcessor The helper object for autoshifting.
38+
* @param toleranceBuffer How many consecutive loops have to be run while within tolerance to be
39+
* considered on target. Multiply by loop period of ~20 milliseconds for time.
40+
* Defaults to 0.
41+
* @param absoluteTolerance The maximum number of degrees off from the target at which we can be
42+
* considered within tolerance.
43+
* @param minimumOutput The minimum output of the loop. Defaults to zero.
44+
* @param maximumOutput The maximum output of the loop. Can be null, and if it is, no maximum output
45+
* is used.
46+
* @param deadband The deadband around the setpoint, in degrees, within which no output is given
47+
* to the motors. Defaults to zero.
48+
* @param maxAngularVelToEnterLoop The maximum angular velocity, in degrees/sec, at which the loop will be
49+
* entered. Defaults to 180.
50+
* @param inverted Whether the loop is inverted. Defaults to false.
51+
* @param kP Proportional gain. Defaults to zero.
52+
* @param kI Integral gain. Defaults to zero.
53+
* @param kD Derivative gain. Defaults to zero.
54+
* @param driveStraightLoopEntryTimer The buffer timer for starting to drive straight.
55+
* @param subsystem The drive to execute this command on.
56+
* @param oi The OI controlling the robot.
57+
* @param autoshiftProcessor The helper object for autoshifting.
5858
*/
5959
@JsonCreator
6060
public ShiftingUnidirectionalNavXDefaultDrive(@JsonProperty(required = true) double absoluteTolerance,
@@ -66,12 +66,12 @@ public ShiftingUnidirectionalNavXDefaultDrive(@JsonProperty(required = true) dou
6666
int kP,
6767
int kI,
6868
int kD,
69-
double loopEntryDelay,
69+
@NotNull @JsonProperty(required = true) BufferTimer driveStraightLoopEntryTimer,
7070
@NotNull @JsonProperty(required = true) T subsystem,
7171
@NotNull @JsonProperty(required = true) UnidirectionalOI oi,
7272
@NotNull @JsonProperty(required = true) AutoshiftProcessor autoshiftProcessor) {
7373
super(absoluteTolerance, toleranceBuffer, minimumOutput, maximumOutput, deadband, maxAngularVelToEnterLoop,
74-
inverted, kP, kI, kD, loopEntryDelay, subsystem, oi);
74+
inverted, kP, kI, kD, driveStraightLoopEntryTimer, subsystem, oi);
7575
this.autoshiftProcessor = autoshiftProcessor;
7676
this.subsystem = subsystem;
7777
}

RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/talonCluster/commands/UnidirectionalNavXDefaultDrive.java

Lines changed: 3 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,6 @@
11
package org.usfirst.frc.team449.robot.drive.talonCluster.commands;
22

33
import com.fasterxml.jackson.annotation.*;
4-
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
54
import org.jetbrains.annotations.NotNull;
65
import org.jetbrains.annotations.Nullable;
76
import org.usfirst.frc.team449.robot.interfaces.drive.unidirectional.UnidirectionalDrive;
@@ -66,8 +65,7 @@ public class UnidirectionalNavXDefaultDrive <T extends YamlSubsystem & Unidirect
6665
* @param kP Proportional gain. Defaults to zero.
6766
* @param kI Integral gain. Defaults to zero.
6867
* @param kD Derivative gain. Defaults to zero.
69-
* @param loopEntryDelay The delay to enter the loop after conditions for entry are met. Defaults to
70-
* zero.
68+
* @param driveStraightLoopEntryTimer The buffer timer for starting to drive straight.
7169
* @param subsystem The drive to execute this command on.
7270
* @param oi The OI controlling the robot.
7371
*/
@@ -81,15 +79,15 @@ public UnidirectionalNavXDefaultDrive(@JsonProperty(required = true) double abso
8179
int kP,
8280
int kI,
8381
int kD,
84-
double loopEntryDelay,
82+
@NotNull @JsonProperty(required = true) BufferTimer driveStraightLoopEntryTimer,
8583
@NotNull @JsonProperty(required = true) T subsystem,
8684
@NotNull @JsonProperty(required = true) UnidirectionalOI oi) {
8785
//Assign stuff
8886
super(absoluteTolerance, toleranceBuffer, minimumOutput, maximumOutput, deadband, inverted, subsystem, kP, kI, kD);
8987
this.oi = oi;
9088
this.subsystem = subsystem;
9189

92-
driveStraightLoopEntryTimer = new BufferTimer(loopEntryDelay);
90+
this.driveStraightLoopEntryTimer = driveStraightLoopEntryTimer;
9391
this.maxAngularVelToEnterLoop = maxAngularVelToEnterLoop != null ? maxAngularVelToEnterLoop : 180;
9492

9593
//Needs a requires because it's a default command.
@@ -138,9 +136,6 @@ else if (driveStraightLoopEntryTimer.get(!(subsystem.getOverrideNavX()) && !(dri
138136
this.getPIDController().enable();
139137
Logger.addEvent("Switching to DriveStraight.", this.getClass());
140138
}
141-
142-
//Log data and stuff
143-
SmartDashboard.putBoolean("driving straight?", drivingStraight);
144139
}
145140

146141
/**

RoboRIO/src/main/java/org/usfirst/frc/team449/robot/interfaces/oi/ArcadeOI.java

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,11 @@
11
package org.usfirst.frc.team449.robot.interfaces.oi;
22

3+
import com.fasterxml.jackson.annotation.JsonTypeInfo;
4+
35
/**
46
* An arcade-style dual joystick OI.
57
*/
8+
@JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class")
69
public abstract class ArcadeOI implements UnidirectionalOI {
710

811
/**
@@ -39,10 +42,11 @@ public double getRightOutput() {
3942

4043
/**
4144
* Whether the driver is trying to drive straight.
45+
*
4246
* @return True if the driver is trying to drive straight, false otherwise.
4347
*/
4448
@Override
45-
public boolean commandingStraight(){
49+
public boolean commandingStraight() {
4650
return getRot() == 0;
4751
}
4852
}

RoboRIO/src/main/java/org/usfirst/frc/team449/robot/interfaces/oi/TankOI.java

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,11 @@
11
package org.usfirst.frc.team449.robot.interfaces.oi;
22

3+
import com.fasterxml.jackson.annotation.JsonTypeInfo;
4+
35
/**
46
* A tank-style dual joystick OI.
57
*/
8+
@JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class")
69
public abstract class TankOI implements UnidirectionalOI {
710

811
/**

RoboRIO/src/main/java/org/usfirst/frc/team449/robot/interfaces/oi/UnidirectionalOI.java

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@ public interface UnidirectionalOI {
2525

2626
/**
2727
* Whether the driver is trying to drive straight.
28+
*
2829
* @return True if the driver is trying to drive straight, false otherwise.
2930
*/
3031
boolean commandingStraight();

RoboRIO/src/main/java/org/usfirst/frc/team449/robot/interfaces/subsystem/NavX/commands/PIDAngleCommand.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ public abstract class PIDAngleCommand extends PIDCommand implements YamlCommand
5454
* @param kP Proportional gain. Defaults to zero.
5555
* @param kI Integral gain. Defaults to zero.
5656
* @param kD Derivative gain. Defaults to zero.
57-
* @param subsystem The subsystem to execute this command on.
57+
* @param subsystem The subsystem to execute this command on.
5858
*/
5959
@JsonCreator
6060
public PIDAngleCommand(@JsonProperty(required = true) double absoluteTolerance,

RoboRIO/src/main/java/org/usfirst/frc/team449/robot/mechanism/climber/ClimberSubsystem.java

Lines changed: 12 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -39,10 +39,10 @@ public class ClimberSubsystem extends YamlSubsystem implements Loggable, BinaryM
3939
private final double maxPower;
4040

4141
/**
42-
* The bufferTimer controlling how long we can be above the current limit before we stop climbing.
42+
* The bufferTimer controlling how long we can be above the power limit before we stop climbing.
4343
*/
4444
@NotNull
45-
private final BufferTimer currentLimitTimer;
45+
private final BufferTimer powerLimitTimer;
4646

4747
/**
4848
* Whether or not the motor is currently spinning.
@@ -53,23 +53,22 @@ public class ClimberSubsystem extends YamlSubsystem implements Loggable, BinaryM
5353
/**
5454
* Default constructor
5555
*
56-
* @param talonSRX The CANTalon controlling one of the climber motors.
57-
* @param maxPower The maximum power at which the motor won't shut off.
58-
* @param victor The VictorSP controlling the other climber motor. Can be null.
59-
* @param millisAboveMaxPower The number of milliseconds it takes to shut off the climber after being above the
60-
* current limit. Defaults to 0.
56+
* @param talonSRX The CANTalon controlling one of the climber motors.
57+
* @param maxPower The maximum power at which the motor won't shut off.
58+
* @param victor The VictorSP controlling the other climber motor. Can be null.
59+
* @param powerLimitTimer The buffer timer for the power-limited shutoff.
6160
*/
6261
@JsonCreator
6362
public ClimberSubsystem(@NotNull @JsonProperty(required = true) RotPerSecCANTalonSRX talonSRX,
6463
@JsonProperty(required = true) double maxPower,
6564
@Nullable MappedVictor victor,
66-
int millisAboveMaxPower) {
65+
@NotNull @JsonProperty(required = true) BufferTimer powerLimitTimer) {
6766
//Instantiate things
68-
canTalonSRX = talonSRX;
67+
this.canTalonSRX = talonSRX;
6968
this.maxPower = maxPower;
70-
currentLimitTimer = new BufferTimer(millisAboveMaxPower);
71-
motorSpinning = false;
69+
this.powerLimitTimer = powerLimitTimer;
7270
this.victor = victor;
71+
this.motorSpinning = false;
7372
}
7473

7574
/**
@@ -163,12 +162,12 @@ public boolean isMotorOn() {
163162
}
164163

165164
/**
166-
* Whether or not the current limit has been exceeded
165+
* Whether or not the power limit has been exceeded
167166
*
168167
* @return true if exceeded, false otherwise
169168
*/
170169
@Override
171170
public boolean isConditionTrue() {
172-
return currentLimitTimer.get(Math.abs(canTalonSRX.getPower()) > maxPower);
171+
return powerLimitTimer.get(Math.abs(canTalonSRX.getPower()) > maxPower);
173172
}
174173
}

RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/SimpleArcadeOI.java

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,6 @@
55
import com.fasterxml.jackson.annotation.JsonProperty;
66
import com.fasterxml.jackson.annotation.ObjectIdGenerators;
77
import org.jetbrains.annotations.NotNull;
8-
import org.usfirst.frc.team449.robot.components.MappedSmoothedThrottle;
98
import org.usfirst.frc.team449.robot.components.MappedThrottle;
109
import org.usfirst.frc.team449.robot.interfaces.oi.ArcadeOI;
1110

0 commit comments

Comments
 (0)