Skip to content

Commit

Permalink
Merge pull request #101 from blair-robot-project/cleanup
Browse files Browse the repository at this point in the history
Clean up code
  • Loading branch information
Noah Gleason authored Oct 26, 2017
2 parents 9a5b20b + 9641a82 commit eef7021
Show file tree
Hide file tree
Showing 350 changed files with 45,855 additions and 4,730 deletions.
53 changes: 27 additions & 26 deletions Pathgen/src/main/java/org/usfirst/frc/team449/pathgen/Pathgen.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,23 +14,24 @@
* Generates a motion profile that hits any number of waypoints.
*/
public class Pathgen {

public static void main(String[] args) throws IOException {

final double CENTER_TO_FRONT = 27./2.;
final double CENTER_TO_BACK = 27./2. + 3.25;
final double CENTER_TO_SIDE = 29./2. + 3.25;
final double CENTER_TO_FRONT = 27. / 2.;
final double CENTER_TO_BACK = 27. / 2. + 3.25;
final double CENTER_TO_SIDE = 29. / 2. + 3.25;
final double BACK_FROM_PEG = -5;
//DO NOT TOUCH THE ONES BELOW
final double CARRIAGE_LEN = 3.63;
final double BLUE_WALL_TO_CENTER_PEG = 114.;
final double BLUE_WALL_TO_SIDE_PEG = 130.5;
final double BLUE_BACK_CORNER_TO_SIDE_PEG = 89.;
final double BLUE_HALF_KEY_LENGTH = 152./2.;
final double BLUE_HALF_KEY_LENGTH = 152. / 2.;
final double BLUE_KEY_CORNER_TO_SIDE_PEG = 16.;
final double RED_WALL_TO_CENTER_PEG = 113.5;
final double RED_WALL_TO_SIDE_PEG = 131.;
final double RED_BACK_CORNER_TO_SIDE_PEG = 97.;
final double RED_HALF_KEY_LENGTH = 152./2.;
final double RED_HALF_KEY_LENGTH = 152. / 2.;
final double RED_KEY_CORNER_TO_SIDE_PEG = 21.;
final double AIRSHIP_PARALLEL_OFFSET_BLUE = 1.;
final double AIRSHIP_PARALLEL_OFFSET_RED = 2.;
Expand All @@ -44,64 +45,64 @@ public static void main(String[] args) throws IOException {

Waypoint[] blueLeft = new Waypoint[]{
new Waypoint(0, 0, 0),
new Waypoint((BLUE_WALL_TO_SIDE_PEG-CENTER_TO_BACK - 0.5*PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_BLUE*Math.cos(5.*Math.PI/6.))/12.
,-(BLUE_BACK_CORNER_TO_SIDE_PEG - CENTER_TO_SIDE - (Math.sqrt(3.)/2.)*PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_BLUE*Math.sin(5.*Math.PI/6.))/12.,-Math.PI/3.)
new Waypoint((BLUE_WALL_TO_SIDE_PEG - CENTER_TO_BACK - 0.5 * PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_BLUE * Math.cos(5. * Math.PI / 6.)) / 12.
, -(BLUE_BACK_CORNER_TO_SIDE_PEG - CENTER_TO_SIDE - (Math.sqrt(3.) / 2.) * PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_BLUE * Math.sin(5. * Math.PI / 6.)) / 12., -Math.PI / 3.)
};

Waypoint[] blueRight = new Waypoint[]{
new Waypoint(0, 0, 0),
new Waypoint((BLUE_WALL_TO_SIDE_PEG-CENTER_TO_BACK - 0.5*PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_BLUE*Math.cos(5.*Math.PI/6.))/12.
,(BLUE_BACK_CORNER_TO_SIDE_PEG - CENTER_TO_SIDE - (Math.sqrt(3.)/2.)*PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_BLUE*Math.sin(5.*Math.PI/6.))/12.,Math.PI/3.)
new Waypoint((BLUE_WALL_TO_SIDE_PEG - CENTER_TO_BACK - 0.5 * PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_BLUE * Math.cos(5. * Math.PI / 6.)) / 12.
, (BLUE_BACK_CORNER_TO_SIDE_PEG - CENTER_TO_SIDE - (Math.sqrt(3.) / 2.) * PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_BLUE * Math.sin(5. * Math.PI / 6.)) / 12., Math.PI / 3.)
};

Waypoint[] blueCenter = new Waypoint[]{
new Waypoint(0, 0, 0),
new Waypoint((BLUE_WALL_TO_CENTER_PEG - CENTER_TO_BACK - PEG_BASE_TO_CENTER)/12., 0, 0)
new Waypoint((BLUE_WALL_TO_CENTER_PEG - CENTER_TO_BACK - PEG_BASE_TO_CENTER) / 12., 0, 0)
};

Waypoint[] redLeft = new Waypoint[]{
new Waypoint(0, 0, 0),
new Waypoint((RED_WALL_TO_SIDE_PEG-CENTER_TO_BACK - 0.5*PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_RED*Math.cos(5.*Math.PI/6.))/12.
,-(RED_BACK_CORNER_TO_SIDE_PEG - CENTER_TO_SIDE - (Math.sqrt(3.)/2.)*PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_RED*Math.sin(5.*Math.PI/6.))/12.,-Math.PI/3.)
new Waypoint((RED_WALL_TO_SIDE_PEG - CENTER_TO_BACK - 0.5 * PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_RED * Math.cos(5. * Math.PI / 6.)) / 12.
, -(RED_BACK_CORNER_TO_SIDE_PEG - CENTER_TO_SIDE - (Math.sqrt(3.) / 2.) * PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_RED * Math.sin(5. * Math.PI / 6.)) / 12., -Math.PI / 3.)
};

Waypoint[] redRight = new Waypoint[]{
new Waypoint(0, 0, 0),
new Waypoint((RED_WALL_TO_SIDE_PEG-CENTER_TO_BACK - 0.5*PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_RED*Math.cos(5.*Math.PI/6.))/12.
,(RED_BACK_CORNER_TO_SIDE_PEG - CENTER_TO_SIDE - (Math.sqrt(3.)/2.)*PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_RED*Math.sin(5.*Math.PI/6.))/12.,Math.PI/3.)
new Waypoint((RED_WALL_TO_SIDE_PEG - CENTER_TO_BACK - 0.5 * PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_RED * Math.cos(5. * Math.PI / 6.)) / 12.
, (RED_BACK_CORNER_TO_SIDE_PEG - CENTER_TO_SIDE - (Math.sqrt(3.) / 2.) * PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_RED * Math.sin(5. * Math.PI / 6.)) / 12., Math.PI / 3.)
};

Waypoint[] redCenter = new Waypoint[]{
new Waypoint(0, 0, 0),
new Waypoint((RED_WALL_TO_CENTER_PEG - CENTER_TO_BACK - PEG_BASE_TO_CENTER)/12., 0, 0)
new Waypoint((RED_WALL_TO_CENTER_PEG - CENTER_TO_BACK - PEG_BASE_TO_CENTER) / 12., 0, 0)
};

Waypoint[] redPegToKey = new Waypoint[]{
new Waypoint(0, 0, 0),
new Waypoint((PEG_BASE_TO_CENTER*Math.cos(Math.toRadians(180)) + RED_WALL_TO_SIDE_PEG*Math.cos(Math.toRadians(-60)) + RED_KEY_CORNER_TO_SIDE_PEG*Math.cos(Math.toRadians(30))
+ RED_HALF_KEY_LENGTH*Math.cos(Math.toRadians(75)) + CENTER_TO_BACK*Math.cos(Math.toRadians(165)))/12.,
(RED_WALL_TO_SIDE_PEG*Math.sin(Math.toRadians(-60)) + RED_KEY_CORNER_TO_SIDE_PEG*Math.sin(Math.toRadians(30))
+ RED_HALF_KEY_LENGTH*Math.sin(Math.toRadians(75)) + CENTER_TO_BACK*Math.sin(Math.toRadians(165)))/12.,
new Waypoint((PEG_BASE_TO_CENTER * Math.cos(Math.toRadians(180)) + RED_WALL_TO_SIDE_PEG * Math.cos(Math.toRadians(-60)) + RED_KEY_CORNER_TO_SIDE_PEG * Math.cos(Math.toRadians(30))
+ RED_HALF_KEY_LENGTH * Math.cos(Math.toRadians(75)) + CENTER_TO_BACK * Math.cos(Math.toRadians(165))) / 12.,
(RED_WALL_TO_SIDE_PEG * Math.sin(Math.toRadians(-60)) + RED_KEY_CORNER_TO_SIDE_PEG * Math.sin(Math.toRadians(30))
+ RED_HALF_KEY_LENGTH * Math.sin(Math.toRadians(75)) + CENTER_TO_BACK * Math.sin(Math.toRadians(165))) / 12.,
-Math.toRadians(16))
};

Waypoint[] bluePegToKey = new Waypoint[]{
new Waypoint(0, 0, 0),
new Waypoint((PEG_BASE_TO_CENTER*Math.cos(Math.toRadians(180)) + BLUE_WALL_TO_SIDE_PEG*Math.cos(Math.toRadians(60)) + BLUE_KEY_CORNER_TO_SIDE_PEG*Math.cos(Math.toRadians(-30))
+ BLUE_HALF_KEY_LENGTH*Math.cos(Math.toRadians(-75)) + CENTER_TO_BACK*Math.cos(Math.toRadians(-165)))/12.,
(BLUE_WALL_TO_SIDE_PEG*Math.sin(Math.toRadians(60)) + BLUE_KEY_CORNER_TO_SIDE_PEG*Math.sin(Math.toRadians(-30))
+ BLUE_HALF_KEY_LENGTH*Math.sin(Math.toRadians(-75)) + CENTER_TO_BACK*Math.sin(Math.toRadians(-165)))/12.,
new Waypoint((PEG_BASE_TO_CENTER * Math.cos(Math.toRadians(180)) + BLUE_WALL_TO_SIDE_PEG * Math.cos(Math.toRadians(60)) + BLUE_KEY_CORNER_TO_SIDE_PEG * Math.cos(Math.toRadians(-30))
+ BLUE_HALF_KEY_LENGTH * Math.cos(Math.toRadians(-75)) + CENTER_TO_BACK * Math.cos(Math.toRadians(-165))) / 12.,
(BLUE_WALL_TO_SIDE_PEG * Math.sin(Math.toRadians(60)) + BLUE_KEY_CORNER_TO_SIDE_PEG * Math.sin(Math.toRadians(-30))
+ BLUE_HALF_KEY_LENGTH * Math.sin(Math.toRadians(-75)) + CENTER_TO_BACK * Math.sin(Math.toRadians(-165))) / 12.,
Math.toRadians(16))
};

Waypoint[] backupRed = new Waypoint[]{
new Waypoint(0, 0, 0),
new Waypoint(3, 1, Math.PI/3)
new Waypoint(3, 1, Math.PI / 3)
};

Waypoint[] backupBlue = new Waypoint[]{
new Waypoint(0, 0, 0),
new Waypoint(3, -1, -Math.PI/3)
new Waypoint(3, -1, -Math.PI / 3)
};

Waypoint[] blueLoadingToLoading = new Waypoint[]{
Expand Down Expand Up @@ -155,7 +156,7 @@ public static void main(String[] args) throws IOException {
//50 in: 34.2

//433.415
double calciferWheelbase = 26./12.;
double calciferWheelbase = 26. / 12.;

Trajectory.Config config = new Trajectory.Config(Trajectory.FitMethod.HERMITE_CUBIC, Trajectory.Config.SAMPLES_HIGH,
0.05, 5., 4.5, 9.); //Units are seconds, feet/second, feet/(second^2), and feet/(second^3)
Expand Down
10 changes: 5 additions & 5 deletions RoboRIO/src/main/java/org/usfirst/frc/team449/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -180,7 +180,7 @@ public void robotInit() {
@Override
public void teleopInit() {
//Run startup command if we start in teleop.
if(!enabled){
if (!enabled) {
if (robotMap.getStartupCommand() != null) {
robotMap.getStartupCommand().start();
}
Expand Down Expand Up @@ -218,7 +218,7 @@ public void teleopPeriodic() {
@Override
public void autonomousInit() {
//Run startup command if we start in auto.
if(!enabled){
if (!enabled) {
if (robotMap.getStartupCommand() != null) {
robotMap.getStartupCommand().start();
}
Expand Down Expand Up @@ -266,9 +266,9 @@ public void disabledInit() {
* Run when we first enable in test mode.
*/
@Override
public void testInit(){
public void testInit() {
//Run startup command if we start in test mode.
if(!enabled){
if (!enabled) {
if (robotMap.getStartupCommand() != null) {
robotMap.getStartupCommand().start();
}
Expand All @@ -280,7 +280,7 @@ public void testInit(){
* Run every tic while disabled
*/
@Override
public void disabledPeriodic(){
public void disabledPeriodic() {
Clock.updateTime();
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,6 @@
import org.usfirst.frc.team449.robot.oi.unidirectional.OIUnidirectional;
import org.usfirst.frc.team449.robot.other.Logger;
import org.usfirst.frc.team449.robot.other.MotionProfileData;
import org.usfirst.frc.team449.robot.other.UnidirectionalPoseEstimator;
import org.usfirst.frc.team449.robot.subsystem.complex.climber.ClimberCurrentLimited;
import org.usfirst.frc.team449.robot.subsystem.complex.intake.IntakeFixedAndActuated;
import org.usfirst.frc.team449.robot.subsystem.complex.shooter.LoggingShooter;
Expand Down Expand Up @@ -211,47 +210,47 @@ public class RobotMap2017 {
/**
* Default constructor.
*
* @param buttons The buttons for controlling this robot. Can be null for an empty list.
* @param oi The OI for controlling this robot's drive.
* @param logger The logger for recording events and telemetry data.
* @param drive The drive.
* @param defaultDriveCommand The command for the drive to run during the teleoperated period.
* @param climber The climber for boarding the airship. Can be null.
* @param shooter The multiSubsystem for shooting fuel. Can be null.
* @param camera The cameras on this robot. Can be null.
* @param intake The intake for picking up and agitating balls. Can be null.
* @param pneumatics The pneumatics on this robot. Can be null.
* @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 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 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.
* @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.
* @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 autoStartupCommand The command to be run when first enabled in autonomous mode.
* @param teleopStartupCommand The command to be run when first enabled in teleoperated mode.
* @param startupCommand The command to be run when first enabled.
* @param testMP Whether to run the test or real motion profile during autonomous. Defaults to false.
* @param doMP Whether to run a motion profile during autonomous. Defaults to true.
* @param buttons The buttons for controlling this robot. Can be null for an empty list.
* @param oi The OI for controlling this robot's drive.
* @param logger The logger for recording events and telemetry data.
* @param drive The drive.
* @param defaultDriveCommand The command for the drive to run during the teleoperated period.
* @param climber The climber for boarding the airship. Can be null.
* @param shooter The multiSubsystem for shooting fuel. Can be null.
* @param camera The cameras on this robot. Can be null.
* @param intake The intake for picking up and agitating balls. Can be null.
* @param pneumatics The pneumatics on this robot. Can be null.
* @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 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 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.
* @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.
* @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 autoStartupCommand The command to be run when first enabled in autonomous mode.
* @param teleopStartupCommand The command to be run when first enabled in teleoperated mode.
* @param startupCommand The command to be run when first enabled.
* @param testMP Whether to run the test or real motion profile during autonomous. Defaults to false.
* @param doMP Whether to run a motion profile during autonomous. Defaults to true.
*/
@JsonCreator
public RobotMap2017(@Nullable List<CommandButton> buttons,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ protected void initialize() {
*/
@Override
protected void execute() {
for (Runnable runnable : runnables){
for (Runnable runnable : runnables) {
runnable.run();
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -178,8 +178,8 @@ protected void usePIDOutput(double output) {
output = processPIDOutput(output);

//Deadband if we're stationary
if(oi.getLeftOutput() == 0 || oi.getRightOutput() == 0){
output=deadbandOutput(output);
if (oi.getLeftOutput() == 0 || oi.getRightOutput() == 0) {
output = deadbandOutput(output);
}

//Adjust the heading according to the PID output, it'll be positive if we want to go right.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@
import org.jetbrains.annotations.NotNull;
import org.jetbrains.annotations.Nullable;
import org.usfirst.frc.team449.robot.components.AutoshiftComponent;
import org.usfirst.frc.team449.robot.components.NavXRumbleComponent;
import org.usfirst.frc.team449.robot.drive.shifting.DriveShiftable;
import org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectional;
import org.usfirst.frc.team449.robot.generalInterfaces.shiftable.Shiftable;
Expand Down Expand Up @@ -62,7 +61,7 @@ public class UnidirectionalNavXShiftingDefaultDrive <T extends YamlSubsystem & D
* @param subsystem The drive to execute this command on.
* @param oi The OI controlling the robot.
* @param autoshiftComponent The helper object for autoshifting.
* @param highGearAngularCoefficient The coefficient to multiply the loop output by in high gear. Defaults to 1.
* @param highGearAngularCoefficient The coefficient to multiply the loop output by in high gear. Defaults to 1.
*/
@JsonCreator
public UnidirectionalNavXShiftingDefaultDrive(@JsonProperty(required = true) double absoluteTolerance,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
import com.fasterxml.jackson.annotation.ObjectIdGenerators;
import com.kauailabs.navx.frc.AHRS;
import org.jetbrains.annotations.NotNull;
import org.usfirst.frc.team449.robot.Robot;
import org.usfirst.frc.team449.robot.generalInterfaces.rumbleable.Rumbleable;
import org.usfirst.frc.team449.robot.jacksonWrappers.MappedAHRS;
import org.usfirst.frc.team449.robot.jacksonWrappers.MappedRunnable;
Expand All @@ -18,7 +17,7 @@
* A component to rumble controllers based off the jerk measurements from a NavX.
*/
@JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class)
public class NavXRumbleComponent implements MappedRunnable{
public class NavXRumbleComponent implements MappedRunnable {

/**
* The factor to multiply feet/(sec^3) by to get Gs/millisecond, according to WolframAlpha.
Expand Down
Loading

0 comments on commit eef7021

Please sign in to comment.