diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/AutoGenerator.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/AutoGenerator.java index 171a0e5..9ac25f1 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/AutoGenerator.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/AutoGenerator.java @@ -5,22 +5,36 @@ import org.usfirst.frc.team3494.robot.commands.auto.DistanceDrive; import org.usfirst.frc.team3494.robot.commands.auto.PIDAngleDrive; import org.usfirst.frc.team3494.robot.commands.auto.PIDFullDrive; +import org.usfirst.frc.team3494.robot.commands.auto.SetGearGrasp; import org.usfirst.frc.team3494.robot.commands.auto.XYDrive; -import org.usfirst.frc.team3494.robot.commands.gears.ToggleGearRamp; +import edu.wpi.first.wpilibj.DoubleSolenoid.Value; import edu.wpi.first.wpilibj.command.Command; /** * Class containing methods that return valid lists to pass to * {@link org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto}. - * + * * @since 0.0.3 * @see org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto */ public class AutoGenerator { + /** + * The distance of the first pull in gear placing. + */ + private static final double FIRST_PULL = 101.5 - 35.5 - 17.75 - 5.5; + /** + * The angle to turn after the first pull in gear placing. + */ + private static final double ANGLE = 60; + /** + * After turning {@link AutoGenerator#ANGLE} degrees, drive this distance. + */ + private static final double SECOND_PULL = 35 - 17.75; + /** * Test method. Drives to XY (36, 36) (inches). - * + * * @since 0.0.3 * @see org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto * @see org.usfirst.frc.team3494.robot.commands.auto.XYDrive @@ -28,60 +42,100 @@ public class AutoGenerator { * {@link org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto}. */ public static ArrayList autoOne() { - ArrayList list = new ArrayList(); + ArrayList list = new ArrayList<>(); list.add(new XYDrive(36, 36)); return list; } /** - * Drives to the baseline and earns us five points (hopefully.) - * + * Drives to the baseline. + * * @see org.usfirst.frc.team3494.robot.commands.auto.DistanceDrive * @since 0.0.3 * @return A list of commands suitable for use with * {@link org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto}. */ public static ArrayList crossBaseLine() { - ArrayList list = new ArrayList(); - list.add(new DistanceDrive(-72, UnitTypes.INCHES)); + ArrayList list = new ArrayList<>(); + list.add(new DistanceDrive(72, UnitTypes.INCHES)); return list; } public static ArrayList placeCenterGear() { - ArrayList list = new ArrayList(); - list.add(new PIDFullDrive(110.5)); + ArrayList list = new ArrayList<>(); + list.add(new PIDFullDrive(110.75)); return list; } - public static ArrayList gearPlaceAttempt() { - ArrayList list = new ArrayList(); - list.add(new PIDFullDrive(87.5)); - list.add(new PIDAngleDrive(65)); - list.add(new PIDFullDrive(54)); + /** + * Drives forward, turns right, drives forward again. + * + * @see org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto + * Constructed Auto + * @return A list for use with + * {@link org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto + * ConstructedAuto} + */ + public static ArrayList gearPassiveRight() { + ArrayList list = new ArrayList<>(); + list.add(new PIDFullDrive(FIRST_PULL)); + list.add(new PIDAngleDrive(ANGLE)); + list.add(new PIDFullDrive(SECOND_PULL)); // list.add(new DistanceDrive(-60, UnitTypes.INCHES)); return list; } - public static ArrayList gearPlaceAttemptLeft() { - ArrayList list = new ArrayList(); - list.add(new PIDFullDrive(87.5)); - list.add(new PIDAngleDrive(-65)); - list.add(new PIDFullDrive(54)); + /** + * Drives forward, turns left, drives forward again. + * + * @see org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto + * Constructed Auto + * @return A list for use with + * {@link org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto + * ConstructedAuto} + */ + public static ArrayList gearPassiveLeft() { + ArrayList list = new ArrayList<>(); + list.add(new PIDFullDrive(FIRST_PULL)); + list.add(new PIDAngleDrive(-ANGLE)); + list.add(new PIDFullDrive(SECOND_PULL)); // list.add(new DistanceDrive(-60, UnitTypes.INCHES)); return list; } - + + /** + * Same as {@link AutoGenerator#gearPassiveLeft()}, but drops the gear on + * the peg at the end. + * + * @see org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto + * Constructed Auto + * @return A list for use with + * {@link org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto + * ConstructedAuto} + */ public static ArrayList activeLeftGear() { - ArrayList list = AutoGenerator.gearPlaceAttemptLeft(); - list.add(new ToggleGearRamp()); - list.add(new PIDFullDrive(10)); + ArrayList list = AutoGenerator.gearPassiveLeft(); + list.add(new SetGearGrasp(Value.kForward)); + list.add(new PIDFullDrive(-10)); + list.add(new SetGearGrasp(Value.kReverse)); return list; } - + + /** + * Same as {@link AutoGenerator#gearPassiveRight()}, but drops the gear on + * the peg at the end. + * + * @see org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto + * Constructed Auto + * @return A list for use with + * {@link org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto + * ConstructedAuto} + */ public static ArrayList activeGearRight() { - ArrayList list = AutoGenerator.gearPlaceAttempt(); - list.add(new ToggleGearRamp()); + ArrayList list = AutoGenerator.gearPassiveRight(); + list.add(new SetGearGrasp(Value.kForward)); list.add(new PIDFullDrive(-10)); + list.add(new SetGearGrasp(Value.kReverse)); return list; } } diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/DriveDirections.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/DriveDirections.java index 442bd56..8b326ea 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/DriveDirections.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/DriveDirections.java @@ -2,7 +2,7 @@ /** * Enum of directions to drive in. - * + * * @since 0.0.0 */ public enum DriveDirections { diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/OI.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/OI.java index 7ab7abc..eee5260 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/OI.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/OI.java @@ -1,15 +1,13 @@ package org.usfirst.frc.team3494.robot; -import org.usfirst.frc.team3494.robot.commands.auto.DistanceDrive; import org.usfirst.frc.team3494.robot.commands.climb.Climb; -import org.usfirst.frc.team3494.robot.commands.climb.ClimberToggle; +import org.usfirst.frc.team3494.robot.commands.climb.ClimberPTOSetter; import org.usfirst.frc.team3494.robot.commands.climb.StopClimber; import org.usfirst.frc.team3494.robot.commands.drive.HoldDriveTrain; -import org.usfirst.frc.team3494.robot.commands.gears.HoldInState_Forward; -import org.usfirst.frc.team3494.robot.commands.gears.SetReverse; +import org.usfirst.frc.team3494.robot.commands.gears.SetHolderState; import org.usfirst.frc.team3494.robot.commands.gears.ToggleGearRamp; -import org.usfirst.frc.team3494.robot.commands.turret.Shoot; +import edu.wpi.first.wpilibj.DoubleSolenoid.Value; import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.XboxController; import edu.wpi.first.wpilibj.buttons.JoystickButton; @@ -52,7 +50,7 @@ public class OI { public JoystickButton xbox_a = new JoystickButton(xbox, 1); public JoystickButton xbox_a_2 = new JoystickButton(xbox_2, 1); - public JoystickButton xbox_lt = new JoystickButton(xbox, 5); + public JoystickButton xbox_lt_2 = new JoystickButton(xbox_2, 5); public JoystickButton xbox_rt = new JoystickButton(xbox, 6); public JoystickButton xbox_rt_2 = new JoystickButton(xbox_2, 6); @@ -71,22 +69,19 @@ public class OI { public OI() { // Ready Player One - xbox_a.whenPressed(new DistanceDrive(-12, UnitTypes.INCHES)); // Ready Player Two // Climb controls xbox_a_2.whileActive(new Climb(DriveDirections.UP)); xbox_a_2.whenReleased(new StopClimber()); - xbox_b_2.whenPressed(new SetReverse()); + xbox_b_2.whileHeld(new HoldDriveTrain()); - xbox_x_2.whileHeld(new HoldInState_Forward()); + xbox_x_2.whenPressed(new SetHolderState(Value.kForward)); + xbox_x_2.whenReleased(new SetHolderState(Value.kReverse)); xbox_y_2.whenPressed(new ToggleGearRamp()); - xbox_rt_2.whenPressed(new Shoot()); - xbox_rt_2.whenReleased(new Shoot(0)); - - xbox_select_2.whenPressed(new ClimberToggle()); - xbox_start_2.whileHeld(new HoldDriveTrain()); + xbox_lt_2.whenPressed(new ClimberPTOSetter(true)); + xbox_rt_2.whenPressed(new ClimberPTOSetter(false)); } } diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/Robot.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/Robot.java index 892a28f..7e1bfd2 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/Robot.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/Robot.java @@ -8,13 +8,11 @@ import org.opencv.imgproc.Imgproc; import org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto; import org.usfirst.frc.team3494.robot.commands.auto.NullAuto; -import org.usfirst.frc.team3494.robot.commands.auto.PIDAngleDrive; -import org.usfirst.frc.team3494.robot.commands.auto.PIDFullDrive; import org.usfirst.frc.team3494.robot.subsystems.Climber; +import org.usfirst.frc.team3494.robot.subsystems.ClimberPTO; import org.usfirst.frc.team3494.robot.subsystems.Drivetrain; import org.usfirst.frc.team3494.robot.subsystems.GearTake_2; import org.usfirst.frc.team3494.robot.subsystems.Kompressor; -import org.usfirst.frc.team3494.robot.subsystems.Turret; import org.usfirst.frc.team3494.robot.vision.GripPipeline; import com.ctre.CANTalon; @@ -22,7 +20,6 @@ import edu.wpi.cscore.UsbCamera; import edu.wpi.first.wpilibj.CameraServer; -import edu.wpi.first.wpilibj.DoubleSolenoid.Value; import edu.wpi.first.wpilibj.IterativeRobot; import edu.wpi.first.wpilibj.PowerDistributionPanel; import edu.wpi.first.wpilibj.Preferences; @@ -35,34 +32,35 @@ import edu.wpi.first.wpilibj.vision.VisionThread; /** - * The VM is configured to automatically run this class, and to call the + * The JVM is configured to automatically run this class, and to call the * functions corresponding to each mode, as described in the IterativeRobot - * documentation. If you change the name of this class or the package after - * creating this project, you must also update the manifest file in the resource - * directory. + * documentation. */ public class Robot extends IterativeRobot { public static OI oi; public static Drivetrain driveTrain; public static Climber climber; - public static Turret turret; public static Kompressor kompressor; public static GearTake_2 gearTake; + public static ClimberPTO pto; + /** * The gyro board mounted to the RoboRIO. - * + * * @since 0.0.2 */ public static AHRS ahrs; - public static PowerDistributionPanel pdp = new PowerDistributionPanel(); + /** + * The robot's PDP panel. Use for reading current draw. + */ + public static PowerDistributionPanel pdp; Command autonomousCommand; public static SendableChooser chooser; public static Preferences prefs; public static UsbCamera camera_0; - public static UsbCamera camera_1; // Vision items private static final int IMG_WIDTH = 320; @SuppressWarnings("unused") @@ -72,7 +70,7 @@ public class Robot extends IterativeRobot { public double absolutelyAverage = 0.0; @SuppressWarnings("unused") private ArrayList filteredContours; - private ArrayList averages = new ArrayList(); + private ArrayList averages = new ArrayList<>(); private final Object imgLock = new Object(); @@ -84,35 +82,37 @@ public class Robot extends IterativeRobot { public void robotInit() { System.out.println("Hello FTAs, how are you doing?"); System.out.println("Because I'm a QUADRANGLE."); - chooser = new SendableChooser(); + // Init hardware + pdp = new PowerDistributionPanel(); + ahrs = new AHRS(SerialPort.Port.kMXP); + ahrs.reset(); + camera_0 = CameraServer.getInstance().startAutomaticCapture("Gear View", 0); + camera_0.setExposureManual(20); + // Init subsystems driveTrain = new Drivetrain(); climber = new Climber(); - climber.disengagePTO(); - turret = new Turret(); kompressor = new Kompressor(); gearTake = new GearTake_2(); + gearTake.closeHolder(); + pto = new ClimberPTO(); + pto.disengagePTO(); + // Non subsystem software init + prefs = Preferences.getInstance(); + chooser = new SendableChooser<>(); oi = new OI(); - ahrs = new AHRS(SerialPort.Port.kMXP); - Robot.climber.disengagePTO(); // Auto programs come after all subsystems are created - chooser.addDefault("To the baseline!", new ConstructedAuto(AutoGenerator.crossBaseLine())); + chooser.addDefault("Drive to the baseline", new ConstructedAuto(AutoGenerator.crossBaseLine())); chooser.addObject("Center Gear Placer", new ConstructedAuto(AutoGenerator.placeCenterGear())); - chooser.addObject("[beta] Right Gear Attempt", new ConstructedAuto(AutoGenerator.gearPlaceAttempt())); - chooser.addObject("[beta] Left Gear Attempt", new ConstructedAuto(AutoGenerator.gearPlaceAttemptLeft())); - chooser.addObject("Follow the shiny", null); + chooser.addObject("Passive Gear Placer - Robot turn right", + new ConstructedAuto(AutoGenerator.gearPassiveRight())); + chooser.addObject("Passive Gear Placer - Robot turn left", + new ConstructedAuto(AutoGenerator.gearPassiveLeft())); chooser.addObject("Do nothing", new NullAuto()); - chooser.addObject("PID Test - turn 90 degrees", new PIDAngleDrive(90)); - chooser.addObject("PID Test - drive straight", new PIDFullDrive(36)); chooser.addObject("Active Gear placer - Robot turn left", new ConstructedAuto(AutoGenerator.activeLeftGear())); - chooser.addObject("Active Gear placer - Robot turn right", new ConstructedAuto(AutoGenerator.activeGearRight())); + chooser.addObject("Active Gear placer - Robot turn right", + new ConstructedAuto(AutoGenerator.activeGearRight())); // put chooser on DS SmartDashboard.putData("AUTO CHOOSER", chooser); - // get preferences - prefs = Preferences.getInstance(); - camera_0 = CameraServer.getInstance().startAutomaticCapture("Gear View", 0); - camera_0.setExposureManual(20); - // camera_1 = CameraServer.getInstance().startAutomaticCapture("Intake - // View", 1); // Create and start vision thread visionThread = new VisionThread(camera_0, new GripPipeline(), pipeline -> { if (!pipeline.filterContoursOutput().isEmpty()) { @@ -178,14 +178,8 @@ public void disabledPeriodic() { */ @Override public void autonomousInit() { - autonomousCommand = chooser.getSelected(); - // schedule the autonomous command (example) - if (autonomousCommand != null) { - System.out.println("Selected command " + chooser.getSelected().getName()); - autonomousCommand.start(); - } else { - System.out.println("Defaulting to track the shiny"); - } + // reset gyro + Robot.ahrs.reset(); // set ramps for (CANTalon t : Robot.driveTrain.leftSide) { t.setVoltageRampRate(0); @@ -195,6 +189,14 @@ public void autonomousInit() { t.setVoltageRampRate(0); t.enableBrakeMode(true); } + autonomousCommand = chooser.getSelected(); + // schedule the autonomous command (example) + if (autonomousCommand != null) { + System.out.println("Selected command " + chooser.getSelected().getName()); + autonomousCommand.start(); + } else { + System.out.println("Defaulting to track the shiny"); + } } /** @@ -216,27 +218,11 @@ public void autonomousPeriodic() { System.out.println("Turn: " + turn); Robot.driveTrain.wpiDrive.arcadeDrive(0.5, (turn * 0.005) * -1); } - SmartDashboard.putNumber("[left] distance", Robot.driveTrain.getLeftDistance(UnitTypes.RAWCOUNT)); - SmartDashboard.putNumber("[left] distance inches", Robot.driveTrain.getLeftDistance(UnitTypes.INCHES)); - - SmartDashboard.putNumber("[right] distance", Robot.driveTrain.getRightDistance(UnitTypes.RAWCOUNT)); - SmartDashboard.putNumber("[right] distance inches", Robot.driveTrain.getRightDistance(UnitTypes.INCHES)); - - SmartDashboard.putNumber("Motor 0", Robot.pdp.getCurrent(0)); - SmartDashboard.putNumber("Motor 1", Robot.pdp.getCurrent(1)); - SmartDashboard.putNumber("Motor 2", Robot.pdp.getCurrent(2)); - - SmartDashboard.putNumber("Talon Distance Right", Robot.driveTrain.rightSide[0].getPosition()); - SmartDashboard.putNumber("Talon Distance Left", Robot.driveTrain.leftSide[0].getPosition()); - - SmartDashboard.putNumber("Motor 13", Robot.pdp.getCurrent(13)); - SmartDashboard.putNumber("Motor 14", Robot.pdp.getCurrent(14)); - SmartDashboard.putNumber("Motor 15", Robot.pdp.getCurrent(15)); + Robot.putDebugInfo(); } @Override public void teleopInit() { - Robot.gearTake.setGrasp(Value.kOff); // This makes sure that the autonomous stops running when // teleop starts running. If you want the autonomous to // continue until interrupted by another command, remove @@ -267,6 +253,18 @@ public void teleopPeriodic() { * Robot.climber.engagePTO(); } */ Scheduler.getInstance().run(); + Robot.putDebugInfo(); + } + + /** + * This function is called periodically during test mode + */ + @Override + public void testPeriodic() { + LiveWindow.run(); + } + + public static void putDebugInfo() { SmartDashboard.putNumber("[left] distance", Robot.driveTrain.getLeftDistance(UnitTypes.RAWCOUNT)); SmartDashboard.putNumber("[left] distance inches", Robot.driveTrain.getLeftDistance(UnitTypes.INCHES)); @@ -285,14 +283,5 @@ public void teleopPeriodic() { SmartDashboard.putNumber("Motor 15", Robot.pdp.getCurrent(15)); SmartDashboard.putNumber("Climber Motor", Robot.pdp.getCurrent(RobotMap.CLIMBER_MOTOR_PDP)); - SmartDashboard.putBoolean("line break", Robot.gearTake.lb.getBroken()); - } - - /** - * This function is called periodically during test mode - */ - @Override - public void testPeriodic() { - LiveWindow.run(); } } diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/RobotMap.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/RobotMap.java index 4a80078..14e9c6a 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/RobotMap.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/RobotMap.java @@ -40,24 +40,27 @@ public class RobotMap { public static final int INTAKE_MOTOR = 5; public static final int UP_MOTOR = 4; // climber - public static final int CLIMBER_MOTOR = 1; - public static final int CLIMBER_MOTOR_PDP = 11; + public static final int CLIMBER_MOTOR = 3; + public static final int CLIMBER_MOTOR_PDP = RobotMap.CLIMBER_MOTOR; public static final int CLIMBER_PTO_FORWARD = 6; public static final int CLIMBER_PTO_BACKARD = 7; // turret - public static final int TURRET_RING = 62; - public static final int TURRET_LOWER = 63; - public static final int TURRET_UPPER = 64; + public static final int UNSCRAMBLER = 3; + public static final int TURRET_CONVEYER = 12; + public static final int TURRET_LOWER = 6; + public static final int TURRET_UPPER = 7; + + public static final int TURRET_ENCUPPER_A = 6; + public static final int TURRET_ENCUPPER_B = 7; + public static final int TURRET_ENCLOWER_A = 4; + public static final int TURRET_ENCLOWER_B = 5; public static final int COMPRESSOR = 0; // gear holder pistons - public static final int GEAR_RAMP_CHONE = 2; - public static final int GEAR_RAMP_CHTWO = 3; - public static final int GEAR_GRASP_CHONE = 4; - public static final int GEAR_GRASP_CHTWO = 5; - - public static final int GEAR_GRASP_S2_FORWARD = 1; - public static final int GEAR_GRASP_S2_BACKWARD = 0; + public static final int GEAR_DOOR_F = 3; + public static final int GEAR_DOOR_R = 2; + public static final int GEAR_RAMP_F = 5; + public static final int GEAR_RAMP_R = 4; // conveyer public static final int CONVEYER_M = 14; diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/UnitTypes.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/UnitTypes.java index 6d165ae..fa1b81a 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/UnitTypes.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/UnitTypes.java @@ -2,7 +2,7 @@ /** * Enum of units. - * + * * @since 0.0.0 */ public enum UnitTypes { diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/DelayCommand.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/DelayCommand.java deleted file mode 100644 index a57b29f..0000000 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/DelayCommand.java +++ /dev/null @@ -1,50 +0,0 @@ -package org.usfirst.frc.team3494.robot.commands; - -import edu.wpi.first.wpilibj.command.Command; - -/** - * Command to cause delays in autonomous. WIP. - */ -public class DelayCommand extends Command { - - double time; - - public DelayCommand(double t) { - // Use requires() here to declare subsystem dependencies - // eg. requires(chassis); - this.time = t; - } - - // Called just before this Command runs the first time - @Override - protected void initialize() { - } - - // Called repeatedly when this Command is scheduled to run - @Override - protected void execute() { - try { - Thread.sleep((long) time); - } catch (InterruptedException e) { - System.out.println("HOW LONG DID YOU WAIT?!"); - e.printStackTrace(); - } - } - - // Make this return true when this Command no longer needs to run execute() - @Override - protected boolean isFinished() { - return true; - } - - // Called once after isFinished returns true - @Override - protected void end() { - } - - // Called when another command which requires one or more of the same - // subsystems is scheduled to run - @Override - protected void interrupted() { - } -} diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/AngleTurn.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/AngleTurn.java index 2034fc5..e9f1343 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/AngleTurn.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/AngleTurn.java @@ -8,7 +8,7 @@ * Turns the robot using the gyro board mounted to the RoboRIO. The angle to * turn by must be specified in the constructor. Angle tolerance is specified by * Robot.prefs (key {@code angle tolerance}.) - * + * * @since 0.0.2 * @see org.usfirst.frc.team3494.robot.Robot * @see org.usfirst.frc.team3494.robot.subsystems.Drivetrain @@ -20,7 +20,7 @@ public class AngleTurn extends Command { /** * Constructor. - * + * * @param angle * The number of degrees to turn. */ diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/ConstructedAuto.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/ConstructedAuto.java index afbb0f5..7d7dbf6 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/ConstructedAuto.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/ConstructedAuto.java @@ -7,13 +7,13 @@ /** * Creates an auto program from a passed-in list of commands. - * + * * @since 0.0.3 */ public class ConstructedAuto extends CommandGroup { /** * Constructor. - * + * * @param commands * The list of commands to make an auto sequence from, in * order. diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/DistanceDrive.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/DistanceDrive.java index ddf7167..a693660 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/DistanceDrive.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/DistanceDrive.java @@ -8,7 +8,7 @@ /** * Drives a given distance. Currently suffering from encoder issues. - * + * * @see org.usfirst.frc.team3494.robot.subsystems.Drivetrain * @since 0.0.2 */ @@ -19,7 +19,7 @@ public class DistanceDrive extends Command { /** * Constructor. - * + * * @param distance * The distance to drive. * @param unitType @@ -35,6 +35,16 @@ public DistanceDrive(double distance, UnitTypes unitType) { this.unit = unitType; } + /** + * Alternative constructor. + * + * @param distance + * The distance to drive, in inches. + */ + public DistanceDrive(double distance) { + this(distance, UnitTypes.INCHES); + } + // Called just before this Command runs the first time @Override protected void initialize() { diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/PIDAngleDrive.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/PIDAngleDrive.java index b588bfc..2c2ed70 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/PIDAngleDrive.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/PIDAngleDrive.java @@ -14,7 +14,7 @@ public class PIDAngleDrive extends Command { /** * Constructor. - * + * * @param angle * The angle to turn, in degrees. */ diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/PIDFullDrive.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/PIDFullDrive.java index dd4f862..c607fd4 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/PIDFullDrive.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/PIDFullDrive.java @@ -18,7 +18,7 @@ public class PIDFullDrive extends Command { /** * Constructor. - * + * * @param dist * The distance to drive, in inches. * @param angle @@ -33,7 +33,7 @@ public PIDFullDrive(double dist, double angle) { /** * Other constructor. Uses default angle of 0 degrees. - * + * * @param dist * The distance to drive in inches. */ @@ -61,9 +61,8 @@ protected void initialize() { @Override protected void execute() { SmartDashboard.putNumber("angle", Robot.ahrs.getAngle()); - System.out.println(Robot.ahrs.getYaw()); // System.out.println(Robot.driveTrain.PIDTune); - if (this.distance < 0) { + if (this.distance < Robot.driveTrain.getAvgDistance(UnitTypes.INCHES)) { Robot.driveTrain.ArcadeDrive(0.5, -Robot.driveTrain.PIDTune, true); } else { Robot.driveTrain.ArcadeDrive(-0.5, -Robot.driveTrain.PIDTune, true); diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/XYDrive.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/XYDrive.java index 4c22e5d..bad88bf 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/XYDrive.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/XYDrive.java @@ -1,12 +1,10 @@ package org.usfirst.frc.team3494.robot.commands.auto; -import org.usfirst.frc.team3494.robot.UnitTypes; - import edu.wpi.first.wpilibj.command.CommandGroup; /** * Drives to a point relative to the robot. - * + * * @since 0.0.3 */ public class XYDrive extends CommandGroup { @@ -16,7 +14,7 @@ public class XYDrive extends CommandGroup { /** * Constructor. - * + * * @param rise * The distance along the Y axis that the point is from the * robot. @@ -25,11 +23,34 @@ public class XYDrive extends CommandGroup { * robot. */ public XYDrive(double rise, double run) { + this(rise, run, true); + } + + /** + * More verbose(?) constructor. + * + * @param rise + * The distance along the Y axis that the point is from the + * robot. + * @param run + * The distance along the X axis that the point is from the + * robot. + * @param PID + * Whether or not to use the drivetrain's PID control to drive to + * the point. {@code true} is the recommended value, for obvious + * reasons. + */ + public XYDrive(double rise, double run, boolean PID) { double run2 = run * run; double rise2 = rise * rise; this.hypot = Math.sqrt(run2 + rise2); this.angle = Math.toDegrees(Math.atan2(rise, run)); - addSequential(new AngleTurn(angle)); - addSequential(new DistanceDrive(hypot, UnitTypes.INCHES)); + if (PID) { + addSequential(new PIDAngleDrive(angle)); + addSequential(new PIDFullDrive(hypot)); + } else { + addSequential(new AngleTurn(angle)); + addSequential(new DistanceDrive(hypot)); // default to inches + } } } diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/climb/Climb.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/climb/Climb.java index 8bd04cb..aa649b4 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/climb/Climb.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/climb/Climb.java @@ -7,7 +7,7 @@ /** * Command for climbing. Climbs both up and down. - * + * * @see org.usfirst.frc.team3494.robot.subsystems.Climber */ public class Climb extends Command { @@ -18,7 +18,7 @@ public class Climb extends Command { /** * Constructor for Climb. - * + * * @param dir * The direction to climb in. If this is not * {@link DriveDirections#UP} or {@link DriveDirections#DOWN}, @@ -63,6 +63,6 @@ protected void end() { // subsystems is scheduled to run @Override protected void interrupted() { - Robot.climber.stopAll(); + end(); } } diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/climb/ClimberToggle.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/climb/ClimberPTOSetter.java similarity index 61% rename from 3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/climb/ClimberToggle.java rename to 3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/climb/ClimberPTOSetter.java index eb532b0..1cbaf92 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/climb/ClimberToggle.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/climb/ClimberPTOSetter.java @@ -2,20 +2,25 @@ import org.usfirst.frc.team3494.robot.Robot; -import edu.wpi.first.wpilibj.DoubleSolenoid.Value; +import com.ctre.CANTalon; + import edu.wpi.first.wpilibj.command.Command; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; /** * Toggles the climber from drivetrain to climb motor. */ -public class ClimberToggle extends Command { +public class ClimberPTOSetter extends Command { + + private boolean b; - public ClimberToggle() { + public ClimberPTOSetter(boolean engage) { // Use requires() here to declare subsystem dependencies // eg. requires(chassis); - requires(Robot.climber); + requires(Robot.pto); requires(Robot.kompressor); - requires(Robot.gearTake); + requires(Robot.driveTrain); + this.b = engage; } // Called just before this Command runs the first time @@ -26,15 +31,21 @@ protected void initialize() { // Called repeatedly when this Command is scheduled to run @Override protected void execute() { - if (!Robot.climber.getState()) { - Robot.climber.engagePTO(); + SmartDashboard.putBoolean("PTO Engaged", this.b); + if (this.b) { + Robot.pto.engagePTO(); Robot.kompressor.compress.stop(); - Robot.gearTake.setRamp(Value.kForward); - Robot.gearTake.setGrasp(Value.kForward); + for (CANTalon c : Robot.driveTrain.leftSide) { + c.setCurrentLimit(35); + c.EnableCurrentLimit(true); + } + for (CANTalon c : Robot.driveTrain.rightSide) { + c.setCurrentLimit(35); + c.EnableCurrentLimit(true); + } } else { - Robot.climber.disengagePTO(); + Robot.pto.disengagePTO(); Robot.kompressor.compress.start(); - Robot.gearTake.setGrasp(Value.kReverse); } } diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/climb/StopClimber.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/climb/StopClimber.java index 7823f15..a6b8eb3 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/climb/StopClimber.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/climb/StopClimber.java @@ -7,7 +7,7 @@ /** * Stops the climber when * it's time to stop. - * + * * @see org.usfirst.frc.team3494.robot.subsystems.Climber */ public class StopClimber extends Command { diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/drive/Drive.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/drive/Drive.java index d2ca781..6dfd9c1 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/drive/Drive.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/drive/Drive.java @@ -8,7 +8,7 @@ /** * Command to run drivetrain. Only takes input in the form of joysticks. - * + * * @see org.usfirst.frc.team3494.robot.subsystems.Drivetrain Drivetrain * @see org.usfirst.frc.team3494.robot.commands.auto.DistanceDrive Distance * Driving (auto) @@ -32,6 +32,8 @@ protected void initialize() { // Called repeatedly when this Command is scheduled to run @Override protected void execute() { + SmartDashboard.putNumber("Drive setpoint", Robot.driveTrain.getSetpoint()); + SmartDashboard.putBoolean("Drive PID enabled", Robot.driveTrain.getPIDController().isEnabled()); int dpad = Robot.oi.stick_l.getPOV(); if (dpad == 0 || Robot.oi.stick_l.getRawButton(7)) { Robot.driveTrain.inverter = 1; @@ -44,21 +46,12 @@ protected void execute() { } SmartDashboard.putNumber("inverter", Robot.driveTrain.inverter); SmartDashboard.putNumber("scale down", Robot.driveTrain.scaleDown); - boolean useX = Robot.prefs.getBoolean("usexbox", true); + boolean useX = Robot.prefs.getBoolean("xbone", false); if (useX) { - if (Robot.prefs.getBoolean("arcade", true)) { - if (Robot.driveTrain.getInverted()) { - Robot.driveTrain.ArcadeDrive( - Robot.oi.xbox.getY(Hand.kLeft) * Robot.driveTrain.inverter * Robot.driveTrain.scaleDown, - Robot.oi.xbox.getX(Hand.kLeft) * Robot.driveTrain.inverter * Robot.driveTrain.scaleDown, - true); - } else { - Robot.driveTrain.ArcadeDrive( - Robot.oi.xbox.getY(Hand.kLeft) * Robot.driveTrain.inverter * Robot.driveTrain.scaleDown, - -Robot.oi.xbox.getX(Hand.kLeft) * Robot.driveTrain.inverter * Robot.driveTrain.scaleDown, - true); - } - } else { + if (Robot.prefs.getBoolean("arcade", false)) { + Drive.driveArcade(); + } else if (!Robot.prefs.getBoolean("betapid", false)) { + // 10 gbp to whoever can reduce this to one call if (!Robot.driveTrain.getInverted()) { Robot.driveTrain.adjustedTankDrive(-Robot.oi.xbox.getY(Hand.kRight) * Robot.driveTrain.inverter, -Robot.oi.xbox.getY(Hand.kLeft) * Robot.driveTrain.inverter); @@ -66,8 +59,19 @@ protected void execute() { Robot.driveTrain.adjustedTankDrive(-Robot.oi.xbox.getY(Hand.kLeft) * Robot.driveTrain.inverter, -Robot.oi.xbox.getY(Hand.kRight) * Robot.driveTrain.inverter); } + } else { + // BETA - steer using Drivetrain PID + if (!Robot.driveTrain.getPIDController().isEnabled()) { + Robot.driveTrain.enable(); // enable only if disabled + } + if (Math.abs(Robot.oi.xbox.getX(Hand.kRight)) > 0.1) { + Robot.driveTrain + .setSetpoint(Robot.driveTrain.getSetpoint() + (3 * Robot.oi.xbox.getX(Hand.kRight))); + } + Robot.driveTrain.ArcadeDrive(Robot.oi.xbox.getY(Hand.kLeft), -Robot.driveTrain.PIDTune, true); } } else { + // Same reward here. if (Robot.driveTrain.getInverted()) { Robot.driveTrain.TankDrive(-Robot.oi.stick_l.getY(), Robot.oi.stick_r.getY()); } else { @@ -92,4 +96,19 @@ protected void end() { @Override protected void interrupted() { } + + private static void driveArcade() { + double leftX = Robot.oi.xbox.getX(Hand.kLeft); + if (Robot.oi.xbox.getX(Hand.kLeft) == 0 || leftX > -0.09 || leftX < 0.01) { + Robot.driveTrain.setSetpoint(0); + Robot.driveTrain.enable(); + Robot.driveTrain.ArcadeDrive( + Robot.oi.xbox.getY(Hand.kLeft) * Robot.driveTrain.inverter * Robot.driveTrain.scaleDown, + -Robot.driveTrain.PIDTune, true); + } else { + Robot.driveTrain.ArcadeDrive( + Robot.oi.xbox.getY(Hand.kLeft) * Robot.driveTrain.inverter * Robot.driveTrain.scaleDown, + Robot.oi.xbox.getX(Hand.kLeft) * Robot.driveTrain.inverter * Robot.driveTrain.scaleDown, true); + } + } } diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/turret/Shoot.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/gears/SetHolderState.java similarity index 67% rename from 3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/turret/Shoot.java rename to 3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/gears/SetHolderState.java index b4cf41b..ef59408 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/turret/Shoot.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/gears/SetHolderState.java @@ -1,27 +1,22 @@ -package org.usfirst.frc.team3494.robot.commands.turret; +package org.usfirst.frc.team3494.robot.commands.gears; import org.usfirst.frc.team3494.robot.Robot; +import edu.wpi.first.wpilibj.DoubleSolenoid.Value; import edu.wpi.first.wpilibj.command.Command; /** - * Command to run the shooter off of OI input. - * - * @see org.usfirst.frc.team3494.robot.OI OI + * Sets the state of the gear holder. */ -public class Shoot extends Command { - private double power; +public class SetHolderState extends Command { - public Shoot() { + private Value value; + + public SetHolderState(Value v) { // Use requires() here to declare subsystem dependencies // eg. requires(chassis); - this(0.75); - } - - public Shoot(double power) { - super(); - this.power = power; - requires(Robot.turret); + this.value = v; + requires(Robot.gearTake); } // Called just before this Command runs the first time @@ -32,7 +27,7 @@ protected void initialize() { // Called repeatedly when this Command is scheduled to run @Override protected void execute() { - Robot.turret.shoot(this.power); + Robot.gearTake.setGrasp(value); } // Make this return true when this Command no longer needs to run execute() @@ -50,5 +45,6 @@ protected void end() { // subsystems is scheduled to run @Override protected void interrupted() { + end(); } } diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/package-info.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/package-info.java index 464d6c4..4d4602b 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/package-info.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/package-info.java @@ -1,7 +1,7 @@ /** * Root commands package. You should not put any actual commands in here, place * them in sub-packages instead. - * + * * @since 0.0.0 * @see edu.wpi.first.wpilibj.command.Command */ diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/turret/TurretCon.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/turret/TurretCon.java deleted file mode 100644 index bd3229a..0000000 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/turret/TurretCon.java +++ /dev/null @@ -1,61 +0,0 @@ -package org.usfirst.frc.team3494.robot.commands.turret; - -import org.usfirst.frc.team3494.robot.DriveDirections; -import org.usfirst.frc.team3494.robot.Robot; - -import edu.wpi.first.wpilibj.command.Command; - -/** - * - */ -public class TurretCon extends Command { - - public TurretCon() { - // Use requires() here to declare subsystem dependencies - // eg. requires(chassis); - requires(Robot.turret); - } - - // Called just before this Command runs the first time - @Override - protected void initialize() { - } - - // Called repeatedly when this Command is scheduled to run - @Override - protected void execute() { - int dpad = Robot.oi.xbox_2.getPOV(); - if (dpad == -1) { - Robot.turret.stopHood(); - } else if (dpad == 0) { - Robot.turret.stopTurret(); - Robot.turret.setHood(0.25); - } else if (dpad == 180) { - Robot.turret.stopTurret(); - Robot.turret.setHood(-0.25); - } else if (dpad == 90) { - Robot.turret.stopHood(); - Robot.turret.turnTurret(DriveDirections.RIGHT); - } else if (dpad == 270) { - Robot.turret.stopHood(); - Robot.turret.turnTurret(DriveDirections.LEFT); - } - } - - // Make this return true when this Command no longer needs to run execute() - @Override - protected boolean isFinished() { - return false; - } - - // Called once after isFinished returns true - @Override - protected void end() { - } - - // Called when another command which requires one or more of the same - // subsystems is scheduled to run - @Override - protected void interrupted() { - } -} diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/turret/package-info.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/turret/package-info.java deleted file mode 100644 index f47249d..0000000 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/turret/package-info.java +++ /dev/null @@ -1,7 +0,0 @@ -/** - * Turret related packages. - * - * @see org.usfirst.frc.team3494.robot.subsystems.Turret Turret - * - */ -package org.usfirst.frc.team3494.robot.commands.turret; \ No newline at end of file diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/sensors/LineBreak.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/sensors/LineBreak.java deleted file mode 100644 index cf6c18a..0000000 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/sensors/LineBreak.java +++ /dev/null @@ -1,38 +0,0 @@ -package org.usfirst.frc.team3494.robot.sensors; - -import edu.wpi.first.wpilibj.AnalogInput; -import edu.wpi.first.wpilibj.AnalogTrigger; - -public class LineBreak { - /** - * Actual analog channel. - */ - private AnalogInput ai1; - /** - * Analog trigger object. - */ - private AnalogTrigger trigger1; - - public LineBreak(int channel) { - this.ai1 = new AnalogInput(channel); - this.trigger1 = new AnalogTrigger(ai1); - this.trigger1.setLimitsVoltage(0.777, 3.703); - } - - public LineBreak() { - this(1); - } - - /** - * Returns true if the trigger is broken. - * - * @return Whether or not the line is broken. - */ - public boolean getBroken() { - if (!this.trigger1.getInWindow()) { - return trigger1.getTriggerState(); - } else { - return false; - } - } -} diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/sensors/package-info.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/sensors/package-info.java deleted file mode 100644 index 5ec6a82..0000000 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/sensors/package-info.java +++ /dev/null @@ -1,4 +0,0 @@ -/** - * Package for sensor type classes. - */ -package org.usfirst.frc.team3494.robot.sensors; \ No newline at end of file diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Climber.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Climber.java index 2dfa9bd..c8d86f2 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Climber.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Climber.java @@ -4,30 +4,26 @@ import org.usfirst.frc.team3494.robot.Robot; import org.usfirst.frc.team3494.robot.RobotMap; -import edu.wpi.first.wpilibj.DoubleSolenoid; -import edu.wpi.first.wpilibj.DoubleSolenoid.Value; -import edu.wpi.first.wpilibj.Talon; +import com.ctre.CANTalon; + import edu.wpi.first.wpilibj.command.Subsystem; /** * Climber subsystem. Contains methods for controlling the rope climber. - * + * * @since 0.0.0 */ public class Climber extends Subsystem implements IMotorizedSubsystem { - private Talon motor; - private boolean driveTrainMode; - private DoubleSolenoid pto; // zarya named it + private CANTalon motor; // Put methods for controlling this subsystem // here. Call these from Commands. public Climber() { super("Climber"); - this.motor = new Talon(RobotMap.CLIMBER_MOTOR); - this.pto = new DoubleSolenoid(RobotMap.CLIMBER_PTO_FORWARD, RobotMap.CLIMBER_PTO_BACKARD); - this.pto.set(Value.kForward); - this.driveTrainMode = false; + this.motor = new CANTalon(RobotMap.CLIMBER_MOTOR); + this.motor.setInverted(true); + this.motor.enableBrakeMode(false); } @Override @@ -38,17 +34,17 @@ public void initDefaultCommand() { /** * Climbs in the specified direction. - * + * * @param dir * The direction to climb. Setting this to anything other than * {@link DriveDirections#UP} or {@link DriveDirections#DOWN} * will stop the climber. */ public void climb(DriveDirections dir) { - if (dir.equals(DriveDirections.UP) && !this.driveTrainMode) { - this.motor.set(0.4); - } else if (dir.equals(DriveDirections.DOWN) && !this.driveTrainMode) { - this.motor.set(-0.4); + if (dir.equals(DriveDirections.UP) && !Robot.pto.getState()) { + this.motor.set(1); + } else if (dir.equals(DriveDirections.DOWN) && !Robot.pto.getState()) { + this.motor.set(-1); } else { // stop the climber this.motor.set(0); @@ -65,36 +61,6 @@ public void setAll(double speed) { this.motor.set(speed); } - /** - * Engages or disengages the drivetrain from the climber. Note that with the - * drivetrain engaged controlling the climber by this subsystem becomes - * impossible (you must use {@link Drivetrain} instead.) - * - * @see Drivetrain - * @param value - * The state to set the PTO piston in. - */ - public void setPTO(Value value) { - this.pto.set(value); - if (value.equals(Value.kOff) || value.equals(Value.kReverse)) { - this.driveTrainMode = true; - } else { - this.driveTrainMode = false; - } - } - - public void disengagePTO() { - this.setPTO(Value.kForward); - } - - public void engagePTO() { - this.setPTO(Value.kReverse); - } - - public boolean getState() { - return this.driveTrainMode; - } - public double getMotorCurrent() { return Robot.pdp.getCurrent(RobotMap.CLIMBER_MOTOR_PDP); } diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/ClimberPTO.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/ClimberPTO.java new file mode 100644 index 0000000..b875efe --- /dev/null +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/ClimberPTO.java @@ -0,0 +1,63 @@ +package org.usfirst.frc.team3494.robot.subsystems; + +import org.usfirst.frc.team3494.robot.RobotMap; + +import edu.wpi.first.wpilibj.DoubleSolenoid; +import edu.wpi.first.wpilibj.DoubleSolenoid.Value; +import edu.wpi.first.wpilibj.command.Subsystem; + +/** + * Subsystem that controls the climber's PTO. Done to help minimize latency. + * It's not right, but we do what we must because we can. + */ +public class ClimberPTO extends Subsystem { + + // Put methods for controlling this subsystem + // here. Call these from Commands. + private boolean driveTrainMode; + private DoubleSolenoid pto; // zarya named it + + public ClimberPTO() { + super("Climber PTO"); + this.pto = new DoubleSolenoid(RobotMap.CLIMBER_PTO_FORWARD, RobotMap.CLIMBER_PTO_BACKARD); + this.pto.set(Value.kForward); + this.driveTrainMode = false; + } + + @Override + public void initDefaultCommand() { + // Set the default command for a subsystem here. + // setDefaultCommand(new MySpecialCommand()); + } + + public boolean getState() { + return this.driveTrainMode; + } + + /** + * Engages or disengages the drivetrain from the climber. Note that with the + * drivetrain engaged controlling the climber by this subsystem becomes + * impossible (you must use {@link Drivetrain} instead.) + * + * @see Drivetrain + * @param value + * The state to set the PTO piston in. + */ + public void setPTO(Value value) { + this.pto.set(value); + if (value.equals(Value.kOff) || value.equals(Value.kReverse)) { + this.driveTrainMode = true; + } else { + this.driveTrainMode = false; + } + } + + public void disengagePTO() { + this.setPTO(Value.kForward); + } + + public void engagePTO() { + this.setPTO(Value.kReverse); + } + +} diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Conveyer.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Conveyer.java index 83d56a5..8677183 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Conveyer.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Conveyer.java @@ -9,7 +9,7 @@ /** * Conveyer subsystem. Contains all methods for controlling the robot's * conveyer. - * + * * @since 0.0.4 */ public class Conveyer extends Subsystem implements IMotorizedSubsystem { @@ -44,7 +44,7 @@ public void setAll(double speed) { * DriveDirections.FORWARD} and * {@link org.usfirst.frc.team3494.robot.DriveDirections#BACKWARD * DriveDirections.BACKWARD} (anything else will stop the conveyer.). - * + * * @see org.usfirst.frc.team3494.robot.DriveDirections * @param dir * The direction to run the diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Drivetrain.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Drivetrain.java index c957820..a5f8ebd 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Drivetrain.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Drivetrain.java @@ -16,59 +16,59 @@ * Drivetrain subsystem. Contains all methods for controlling the robot's * drivetrain. Also has in instance of RobotDrive (wpiDrive) if you want to use * that. - * + * * @since 0.0.0 */ public class Drivetrain extends PIDSubsystem implements IMotorizedSubsystem { /** * Master drive talon, left side. Setting this should set all the talons on * the left side of the drive train. - * + * * @since 0.0.0 */ private CANTalon driveLeftMaster; /** * Follower talon on left side. - * + * * @since 0.0.0 */ private CANTalon driveLeftFollower_One; /** * Follower talon on left side. - * + * * @since 0.0.0 */ private CANTalon driveLeftFollower_Two; /** * Master drive talon, right side. Setting this should set all the talons on * the left side of the drive train. - * + * * @since 0.0.0 */ private CANTalon driveRightMaster; /** * Follower talon on right side. - * + * * @since 0.0.0 */ private CANTalon driveRightFollower_One; /** * Follower talon on right side. - * + * * @since 0.0.0 */ private CANTalon driveRightFollower_Two; /** * Instance of wpiDrive for using WPI's driving code. Should not be * used for tank driving (use {@link Drivetrain#TankDrive} instead.) - * + * * @since 0.0.0 */ public RobotDrive wpiDrive; - public static final double RAMP = 48; + public static final double RAMP = 0; - public int inverter = -1; + public int inverter = 1; public double scaleDown = 1; public CANTalon[] leftSide; @@ -140,10 +140,14 @@ public Drivetrain() { // PID control this.PIDTune = 0; double outRange = 0.5; - this.getPIDController().setInputRange(-180, 180); - this.getPIDController().setOutputRange(-outRange, outRange); - this.getPIDController().setContinuous(false); - this.getPIDController().setPercentTolerance(2.5); + this.disable(); + if (this.getSetpoint() != 0) { + this.setSetpoint(0); + } + this.setInputRange(-180, 180); + this.setOutputRange(-outRange, outRange); + this.getPIDController().setContinuous(true); + this.setPercentTolerance(2.5); } // Put methods for controlling this subsystem // here. Call these from Commands. @@ -157,7 +161,7 @@ public void initDefaultCommand() { /** * Drives the drivetrain tank drive style. The drivetrain will continue to * run until stopped with a method like {@link Drivetrain#stopAll()}. - * + * * @param left * The power to drive the left side. Should be a {@code double} * between 0 and 1. @@ -184,7 +188,7 @@ public void TeleopTank(double left, double right) { * Drives the drivetrain, with the value passed in for left inverted. This * corrects for the left side being inverted hardware side.
* It works if you don't think about it too hard. - * + * * @param left * The power to set the left side to. This will be multiplied by * -1 before getting to the Talons. @@ -253,7 +257,7 @@ public void ArcadeDrive(double moveValue, double rotateValue, boolean squaredInp /** * Gets the distance the right encoder has counted in the specified unit. - * + * * @param unit * The unit type to get the distance in. * @return The distance the right encoder has counted, in the specified @@ -277,7 +281,7 @@ public double getRightDistance(UnitTypes unit) { /** * Gets the distance the left encoder has counted in the specified unit. - * + * * @param unit * The unit type to get the distance in. * @return The distance the left encoder has counted, in the specified unit. @@ -331,7 +335,7 @@ public void setAll(double speed) { /** * Returns {@code true} if the drivetrain is inverted (the gear holder is * considered forward.) - * + * * @return {@code true} if the drivetrain is inverted. */ public boolean getInverted() { @@ -341,7 +345,7 @@ public boolean getInverted() { /** * Stage-sets the drivetrain. Please, for the love of all that is holy call * {@link Drivetrain#snapBackToReality()} after this. - * + * * @param left * The left power * @param right diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/GearTake_2.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/GearTake_2.java index fbf83e7..b600cd8 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/GearTake_2.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/GearTake_2.java @@ -1,7 +1,6 @@ package org.usfirst.frc.team3494.robot.subsystems; import org.usfirst.frc.team3494.robot.RobotMap; -import org.usfirst.frc.team3494.robot.sensors.LineBreak; import edu.wpi.first.wpilibj.DoubleSolenoid; import edu.wpi.first.wpilibj.DoubleSolenoid.Value; @@ -21,38 +20,21 @@ public class GearTake_2 extends Subsystem { * forward most of the time. */ private DoubleSolenoid rampenoid; - /** - * The solenoid that holds the gear or drops it. - */ - private DoubleSolenoid openandclose_forward; - private DoubleSolenoid openandclose_backward; - - public LineBreak lb; + private DoubleSolenoid doornoid; public GearTake_2() { super(); - this.rampenoid = new DoubleSolenoid(RobotMap.GEAR_RAMP_CHONE, RobotMap.GEAR_RAMP_CHTWO); - this.openandclose_forward = new DoubleSolenoid(RobotMap.GEAR_GRASP_CHONE, RobotMap.GEAR_GRASP_CHTWO); - this.openandclose_backward = new DoubleSolenoid(RobotMap.GEAR_GRASP_S2_FORWARD, - RobotMap.GEAR_GRASP_S2_BACKWARD); - this.openandclose_forward.set(Value.kForward); - this.openandclose_forward.set(Value.kReverse); - - this.openandclose_backward.set(Value.kReverse); - this.openandclose_backward.set(Value.kForward); - - this.lb = new LineBreak(0); + this.doornoid = new DoubleSolenoid(RobotMap.GEAR_DOOR_F, RobotMap.GEAR_DOOR_R); + this.rampenoid = new DoubleSolenoid(RobotMap.GEAR_RAMP_F, RobotMap.GEAR_RAMP_R); } @Override public void initDefaultCommand() { - // Set the default command for a subsystem here. - // setDefaultCommand(new MySpecialCommand()); } /** * Sets the position of the intake ramp. - * + * * @param value * The position to set the ramp to. */ @@ -62,23 +44,12 @@ public void setRamp(Value value) { /** * Sets the position of the actual gear holder. - * + * * @param value * The position to set the holder to. */ public void setGrasp(Value value) { - if (value.equals(Value.kForward)) { - this.openandclose_forward.set(Value.kForward); - this.openandclose_backward.set(Value.kForward); - } else if (value.equals(Value.kReverse)) { - this.openandclose_backward.set(Value.kReverse); - this.openandclose_forward.set(Value.kReverse); - } else { - this.openandclose_forward.set(Value.kForward); - this.openandclose_forward.set(Value.kReverse); - this.openandclose_backward.set(Value.kReverse); - this.openandclose_backward.set(Value.kForward); - } + this.doornoid.set(value); } /** @@ -99,7 +70,7 @@ public void closeHolder() { * Gets the state of the intake ramp solenoid. Equivalent to * {@code this.rampenoid.get()}, but {@link GearTake_2#rampenoid} is * private. - * + * * @return The value of {@code this.rampenoid.get()}. */ public Value getRampState() { @@ -108,12 +79,12 @@ public Value getRampState() { /** * Gets the state of the gear holder. Equivalent to - * {@code this.openandclose.get()}, but - * {@link GearTake_2#openandclose_forward} is private. - * - * @return The value of {@code this.openandclose.get()}. + * {@code this.rampenoid.get()}, but {@link GearTake_2#rampenoid} is + * private. + * + * @return The value of {@code this.rampenoid.get()}. */ public Value getGearState() { - return this.openandclose_forward.get(); + return this.doornoid.get(); } } diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/IMotorizedSubsystem.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/IMotorizedSubsystem.java index 802d0c9..21afec8 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/IMotorizedSubsystem.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/IMotorizedSubsystem.java @@ -2,7 +2,7 @@ /** * Interface to apply to subsystems with motors. - * + * * @since 0.0.0 * @see edu.wpi.first.wpilibj.command.Subsystem */ @@ -15,7 +15,7 @@ public interface IMotorizedSubsystem { /** * Sets all motors on a subsystem to a given speed. (Example use: driving * forward) - * + * * @param speed * The speed to set the motors to. */ diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/MonoGearTake.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/MonoGearTake.java deleted file mode 100644 index 53e8805..0000000 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/MonoGearTake.java +++ /dev/null @@ -1,32 +0,0 @@ -package org.usfirst.frc.team3494.robot.subsystems; - -import org.usfirst.frc.team3494.robot.RobotMap; - -import edu.wpi.first.wpilibj.DoubleSolenoid; -import edu.wpi.first.wpilibj.DoubleSolenoid.Value; -import edu.wpi.first.wpilibj.command.Subsystem; - -/** - * Single piston gear holder. - */ -public class MonoGearTake extends Subsystem { - - // Put methods for controlling this subsystem - // here. Call these from Commands. - private DoubleSolenoid piston; - - @Override - public void initDefaultCommand() { - // Set the default command for a subsystem here. - // setDefaultCommand(new MySpecialCommand()); - this.piston = new DoubleSolenoid(RobotMap.MONO_GEAR_FORWARD, RobotMap.MONO_GEAR_REVERSE); - } - - public void setPos(Value v) { - this.piston.set(v); - } - - public Value getPos() { - return this.piston.get(); - } -} diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Turret.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Turret.java deleted file mode 100644 index a749dcc..0000000 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Turret.java +++ /dev/null @@ -1,111 +0,0 @@ -package org.usfirst.frc.team3494.robot.subsystems; - -import org.usfirst.frc.team3494.robot.DriveDirections; -import org.usfirst.frc.team3494.robot.RobotMap; - -import com.ctre.CANTalon; - -import edu.wpi.first.wpilibj.Encoder; -import edu.wpi.first.wpilibj.Talon; -import edu.wpi.first.wpilibj.command.Subsystem; - -/** - * Turret subsystem. Contains methods for controlling the turret. - * - * @since 0.0.0 - */ -public class Turret extends Subsystem implements IMotorizedSubsystem { - // Put methods for controlling this subsystem - // here. Call these from Commands. - private Encoder turretRingEnc; - private Encoder shooterEnc_lower; - private Encoder shooterEnc_upper; - - private CANTalon shooterUpper; - private CANTalon shooterLower; - private CANTalon turretRing; - - private Talon turretHood; - /** - * Constant for the turret ring speed. Placed here for easy editing. - */ - private static double turretTurnPower = 0.4; - - public Turret() { - super("Turret"); - this.turretRing = new CANTalon(RobotMap.TURRET_RING); - this.shooterUpper = new CANTalon(RobotMap.TURRET_UPPER); - this.shooterLower = new CANTalon(RobotMap.TURRET_LOWER); - } - - @Override - public void initDefaultCommand() { - // Set the default command for a subsystem here. - // setDefaultCommand(new MySpecialCommand()); - } - - @Override - public void stopAll() { - this.shooterLower.set(0); - this.shooterUpper.set(0); - this.turretRing.set(0); - } - - @Override - public void setAll(double speed) { - this.shooterLower.set(speed); - this.shooterUpper.set(speed); - this.turretRing.set(speed); - } - - public double getDistance(TurretEncoders enc) { - if (enc.equals(TurretEncoders.RING)) { - return this.turretRingEnc.getDistance(); - } else if (enc.equals(TurretEncoders.BOTTOM)) { - return this.shooterEnc_lower.getDistance(); - } else { - return this.shooterEnc_upper.getDistance(); - } - } - - /** - * Turns the turret at a hard-coded speed in the specified direction. - * - * @param dir - * The direction to turn in. Defaults to right if you put in - * something stupid like {@link DriveDirections#UP}. - */ - public void turnTurret(DriveDirections dir) { - if (dir.equals(DriveDirections.LEFT)) { - this.turretRing.set(turretTurnPower); - } else { - this.turretRing.set(-turretTurnPower); - } - } - - /** - * Runs the turret at the specified power. Screw you, negative numbers are - * not allowed. - * - * @param power - * The power to run the shooter at. It will be run by abosolute - * value first. - */ - public void shoot(double power) { - power = Math.abs(power); - this.shooterUpper.set(power); - this.shooterLower.set(power); - } - - public void setHood(double power) { - this.turretHood.set(power); - } - - public void stopHood() { - this.setHood(0); - } - - public void stopTurret() { - this.turretRing.set(0); - } -} diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/TurretEncoders.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/TurretEncoders.java deleted file mode 100644 index 6f81800..0000000 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/TurretEncoders.java +++ /dev/null @@ -1,5 +0,0 @@ -package org.usfirst.frc.team3494.robot.subsystems; - -public enum TurretEncoders { - TOP, BOTTOM, RING; -} diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/vision/GearPipeline.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/vision/GearPipeline.java index 36e8f3d..72043fe 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/vision/GearPipeline.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/vision/GearPipeline.java @@ -27,8 +27,8 @@ public class GearPipeline implements VisionPipeline { // Outputs private Mat rgbThresholdOutput = new Mat(); - private ArrayList findContoursOutput = new ArrayList(); - private ArrayList filterContoursOutput = new ArrayList(); + private ArrayList findContoursOutput = new ArrayList<>(); + private ArrayList filterContoursOutput = new ArrayList<>(); static { System.loadLibrary(Core.NATIVE_LIBRARY_NAME); @@ -74,7 +74,7 @@ public void process(Mat source0) { /** * This method is a generated getter for the output of a RGB_Threshold. - * + * * @return Mat output from RGB_Threshold. */ public Mat rgbThresholdOutput() { @@ -83,7 +83,7 @@ public Mat rgbThresholdOutput() { /** * This method is a generated getter for the output of a Find_Contours. - * + * * @return ArrayList<MatOfPoint> output from Find_Contours. */ public ArrayList findContoursOutput() { @@ -92,7 +92,7 @@ public ArrayList findContoursOutput() { /** * This method is a generated getter for the output of a Filter_Contours. - * + * * @return ArrayList<MatOfPoint> output from Filter_Contours. */ public ArrayList filterContoursOutput() { @@ -101,7 +101,7 @@ public ArrayList filterContoursOutput() { /** * Segment an image based on color ranges. - * + * * @param input * The image on which to perform the RGB threshold. * @param red @@ -121,7 +121,7 @@ private void rgbThreshold(Mat input, double[] red, double[] green, double[] blue /** * Sets the values of pixels in a binary image to their distance to the * nearest black pixel. - * + * * @param input * The image on which to perform the Distance Transform. * @param type @@ -146,7 +146,7 @@ private void findContours(Mat input, boolean externalOnly, List cont /** * Filters out contours that do not meet certain criteria. - * + * * @param inputContours * is the input list of contours * @param output @@ -183,15 +183,19 @@ private void filterContours(List inputContours, double minArea, doub for (int i = 0; i < inputContours.size(); i++) { final MatOfPoint contour = inputContours.get(i); final Rect bb = Imgproc.boundingRect(contour); - if (bb.width < minWidth || bb.width > maxWidth) + if (bb.width < minWidth || bb.width > maxWidth) { continue; - if (bb.height < minHeight || bb.height > maxHeight) + } + if (bb.height < minHeight || bb.height > maxHeight) { continue; + } final double area = Imgproc.contourArea(contour); - if (area < minArea) + if (area < minArea) { continue; - if (Imgproc.arcLength(new MatOfPoint2f(contour.toArray()), true) < minPerimeter) + } + if (Imgproc.arcLength(new MatOfPoint2f(contour.toArray()), true) < minPerimeter) { continue; + } Imgproc.convexHull(contour, hull); MatOfPoint mopHull = new MatOfPoint(); mopHull.create((int) hull.size().height, 1, CvType.CV_32SC2); @@ -201,13 +205,16 @@ private void filterContours(List inputContours, double minArea, doub mopHull.put(j, 0, point); } final double solid = 100 * area / Imgproc.contourArea(mopHull); - if (solid < solidity[0] || solid > solidity[1]) + if (solid < solidity[0] || solid > solidity[1]) { continue; - if (contour.rows() < minVertexCount || contour.rows() > maxVertexCount) + } + if (contour.rows() < minVertexCount || contour.rows() > maxVertexCount) { continue; + } final double ratio = bb.width / (double) bb.height; - if (ratio < minRatio || ratio > maxRatio) + if (ratio < minRatio || ratio > maxRatio) { continue; + } output.add(contour); } } diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/vision/GripPipeline.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/vision/GripPipeline.java index 87e732e..fd93819 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/vision/GripPipeline.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/vision/GripPipeline.java @@ -27,8 +27,8 @@ public class GripPipeline implements VisionPipeline { // Outputs private Mat hslThresholdOutput = new Mat(); - private ArrayList findContoursOutput = new ArrayList(); - private ArrayList filterContoursOutput = new ArrayList(); + private ArrayList findContoursOutput = new ArrayList<>(); + private ArrayList filterContoursOutput = new ArrayList<>(); static { System.loadLibrary(Core.NATIVE_LIBRARY_NAME); @@ -75,7 +75,7 @@ public void process(Mat source0) { /** * This method is a generated getter for the output of a HSL_Threshold. - * + * * @return Mat output from HSL_Threshold. */ public Mat hslThresholdOutput() { @@ -84,7 +84,7 @@ public Mat hslThresholdOutput() { /** * This method is a generated getter for the output of a Find_Contours. - * + * * @return {@literal ArrayList} output from Find_Contours. */ public ArrayList findContoursOutput() { @@ -93,7 +93,7 @@ public ArrayList findContoursOutput() { /** * This method is a generated getter for the output of a Filter_Contours. - * + * * @return {@literal ArrayList} output from Filter_Contours. */ public ArrayList filterContoursOutput() { @@ -122,7 +122,7 @@ private void hslThreshold(Mat input, double[] hue, double[] sat, double[] lum, M /** * Sets the values of pixels in a binary image to their distance to the * nearest black pixel. - * + * * @param input * The image on which to perform the Distance Transform. * @param type @@ -147,7 +147,7 @@ private void findContours(Mat input, boolean externalOnly, List cont /** * Filters out contours that do not meet certain criteria. - * + * * @param inputContours * is the input list of contours * @param output @@ -184,15 +184,19 @@ private void filterContours(List inputContours, double minArea, doub for (int i = 0; i < inputContours.size(); i++) { final MatOfPoint contour = inputContours.get(i); final Rect bb = Imgproc.boundingRect(contour); - if (bb.width < minWidth || bb.width > maxWidth) + if (bb.width < minWidth || bb.width > maxWidth) { continue; - if (bb.height < minHeight || bb.height > maxHeight) + } + if (bb.height < minHeight || bb.height > maxHeight) { continue; + } final double area = Imgproc.contourArea(contour); - if (area < minArea) + if (area < minArea) { continue; - if (Imgproc.arcLength(new MatOfPoint2f(contour.toArray()), true) < minPerimeter) + } + if (Imgproc.arcLength(new MatOfPoint2f(contour.toArray()), true) < minPerimeter) { continue; + } Imgproc.convexHull(contour, hull); MatOfPoint mopHull = new MatOfPoint(); mopHull.create((int) hull.size().height, 1, CvType.CV_32SC2); @@ -202,13 +206,16 @@ private void filterContours(List inputContours, double minArea, doub mopHull.put(j, 0, point); } final double solid = 100 * area / Imgproc.contourArea(mopHull); - if (solid < solidity[0] || solid > solidity[1]) + if (solid < solidity[0] || solid > solidity[1]) { continue; - if (contour.rows() < minVertexCount || contour.rows() > maxVertexCount) + } + if (contour.rows() < minVertexCount || contour.rows() > maxVertexCount) { continue; + } final double ratio = bb.width / (double) bb.height; - if (ratio < minRatio || ratio > maxRatio) + if (ratio < minRatio || ratio > maxRatio) { continue; + } output.add(contour); } } diff --git a/docs/allclasses-frame.html b/docs/allclasses-frame.html index 27f3d7b..cf5fe81 100644 --- a/docs/allclasses-frame.html +++ b/docs/allclasses-frame.html @@ -2,9 +2,9 @@ - + All Classes - + @@ -16,10 +16,9 @@

All Classes

  • AutoGenerator
  • Climb
  • Climber
  • -
  • ClimberToggle
  • +
  • ClimberPTOSetter
  • ConstructedAuto
  • Conveyer
  • -
  • DelayCommand
  • DistanceDrive
  • Drive
  • DriveDirections
  • @@ -31,8 +30,6 @@

    All Classes

  • HoldInState_Forward
  • IMotorizedSubsystem
  • Kompressor
  • -
  • LineBreak
  • -
  • MonoGearTake
  • NullAuto
  • OI
  • PIDAngleDrive
  • @@ -40,16 +37,13 @@

    All Classes

  • Robot
  • RobotMap
  • SetGearGrasp
  • +
  • SetHolderState
  • SetReverse
  • -
  • Shoot
  • SpeedTest
  • StageTest
  • StopClimber
  • ToggleGearPosition
  • ToggleGearRamp
  • -
  • Turret
  • -
  • TurretCon
  • -
  • TurretEncoders
  • UnitTypes
  • VisionUtils
  • XYDrive
  • diff --git a/docs/allclasses-noframe.html b/docs/allclasses-noframe.html index e7a084e..4a423dd 100644 --- a/docs/allclasses-noframe.html +++ b/docs/allclasses-noframe.html @@ -2,9 +2,9 @@ - + All Classes - + @@ -16,10 +16,9 @@

    All Classes

  • AutoGenerator
  • Climb
  • Climber
  • -
  • ClimberToggle
  • +
  • ClimberPTOSetter
  • ConstructedAuto
  • Conveyer
  • -
  • DelayCommand
  • DistanceDrive
  • Drive
  • DriveDirections
  • @@ -31,8 +30,6 @@

    All Classes

  • HoldInState_Forward
  • IMotorizedSubsystem
  • Kompressor
  • -
  • LineBreak
  • -
  • MonoGearTake
  • NullAuto
  • OI
  • PIDAngleDrive
  • @@ -40,16 +37,13 @@

    All Classes

  • Robot
  • RobotMap
  • SetGearGrasp
  • +
  • SetHolderState
  • SetReverse
  • -
  • Shoot
  • SpeedTest
  • StageTest
  • StopClimber
  • ToggleGearPosition
  • ToggleGearRamp
  • -
  • Turret
  • -
  • TurretCon
  • -
  • TurretEncoders
  • UnitTypes
  • VisionUtils
  • XYDrive
  • diff --git a/docs/constant-values.html b/docs/constant-values.html index 89492a4..a4a235d 100644 --- a/docs/constant-values.html +++ b/docs/constant-values.html @@ -2,9 +2,9 @@ - + Constant Field Values - + @@ -83,6 +83,32 @@

    org.usfirst.*

    @@ -363,13 +470,13 @@

    activeGearRight

    diff --git a/docs/org/usfirst/frc/team3494/robot/DriveDirections.html b/docs/org/usfirst/frc/team3494/robot/DriveDirections.html index c95604d..6dd4be9 100644 --- a/docs/org/usfirst/frc/team3494/robot/DriveDirections.html +++ b/docs/org/usfirst/frc/team3494/robot/DriveDirections.html @@ -2,9 +2,9 @@ - + DriveDirections - + diff --git a/docs/org/usfirst/frc/team3494/robot/OI.html b/docs/org/usfirst/frc/team3494/robot/OI.html index d4f0b6e..966ca53 100644 --- a/docs/org/usfirst/frc/team3494/robot/OI.html +++ b/docs/org/usfirst/frc/team3494/robot/OI.html @@ -2,9 +2,9 @@ - + OI - + @@ -159,7 +159,7 @@

    Field Summary

    edu.wpi.first.wpilibj.buttons.JoystickButton -xbox_lt  +xbox_lt_2  edu.wpi.first.wpilibj.buttons.JoystickButton @@ -294,13 +294,13 @@

    xbox_a_2

    public edu.wpi.first.wpilibj.buttons.JoystickButton xbox_a_2
    - +
    • -

      xbox_lt

      -
      public edu.wpi.first.wpilibj.buttons.JoystickButton xbox_lt
      +

      xbox_lt_2

      +
      public edu.wpi.first.wpilibj.buttons.JoystickButton xbox_lt_2
    diff --git a/docs/org/usfirst/frc/team3494/robot/Robot.html b/docs/org/usfirst/frc/team3494/robot/Robot.html index b2630ba..e2a09f2 100644 --- a/docs/org/usfirst/frc/team3494/robot/Robot.html +++ b/docs/org/usfirst/frc/team3494/robot/Robot.html @@ -2,9 +2,9 @@ - + Robot - + @@ -18,8 +18,8 @@ catch(err) { } //--> -var methods = {"i0":10,"i1":10,"i2":10,"i3":10,"i4":10,"i5":10,"i6":10,"i7":10}; -var tabs = {65535:["t0","All Methods"],2:["t2","Instance Methods"],8:["t4","Concrete Methods"]}; +var methods = {"i0":10,"i1":10,"i2":10,"i3":10,"i4":9,"i5":10,"i6":10,"i7":10,"i8":10}; +var tabs = {65535:["t0","All Methods"],1:["t1","Static Methods"],2:["t2","Instance Methods"],8:["t4","Concrete Methods"]}; var altColor = "altColor"; var rowColor = "rowColor"; var tableTab = "tableTab"; @@ -121,11 +121,9 @@

    Class Robot


    public class Robot
     extends edu.wpi.first.wpilibj.IterativeRobot
    -
    The VM is configured to automatically run this class, and to call the +
    The JVM is configured to automatically run this class, and to call the functions corresponding to each mode, as described in the IterativeRobot - documentation. If you change the name of this class or the package after - creating this project, you must also update the manifest file in the resource - directory.
    + documentation.
    @@ -167,65 +165,59 @@

    Field Summary

    camera_0  -static edu.wpi.cscore.UsbCamera -camera_1  - - double centerX  - + static edu.wpi.first.wpilibj.smartdashboard.SendableChooser<edu.wpi.first.wpilibj.command.Command> chooser  - + static Climber climber  - + static Drivetrain driveTrain  - + private java.util.ArrayList<org.opencv.core.MatOfPoint> filteredContours  - + static GearTake_2 gearTake  - + private static int IMG_HEIGHT  - + private static int IMG_WIDTH  - + private java.lang.Object imgLock  - + static Kompressor kompressor  - + static OI oi  - + static edu.wpi.first.wpilibj.PowerDistributionPanel -pdp  +pdp +
    The robot's PDP panel.
    + - + static edu.wpi.first.wpilibj.Preferences prefs  - -static Turret -turret  - (package private) edu.wpi.first.wpilibj.vision.VisionThread visionThread  @@ -264,7 +256,7 @@

    Constructor Summary

    Method Summary

    - + @@ -293,23 +285,27 @@

    Method Summary

    + + + + - + - + - + - + - + - + - - - - - - - - - + @@ -239,11 +231,27 @@

    Field Summary

    - + + + + + + + + + - + + + + + + + + + @@ -251,14 +259,18 @@

    Field Summary

    - + - + + + + +
    All Methods Instance Methods Concrete Methods All Methods Static Methods Instance Methods Concrete Methods 
    Modifier and Type Method and Description disabledPeriodic() 
    static voidputDebugInfo() 
    void robotInit()
    This function is run when the robot is first started up and should be used for any initialization code.
    void teleopInit() 
    void teleopPeriodic()
    This function is called periodically during operator control.
    void testPeriodic()
    This function is called periodically during test mode
    @@ -378,15 +374,6 @@

    climber

    public static Climber climber
    - - - -
      -
    • -

      turret

      -
      public static Turret turret
      -
    • -
    @@ -426,6 +413,7 @@

    ahrs

  • pdp

    public static edu.wpi.first.wpilibj.PowerDistributionPanel pdp
    +
    The robot's PDP panel. Use for reading current draw.
  • @@ -464,15 +452,6 @@

    camera_0

    public static edu.wpi.cscore.UsbCamera camera_0
    -
    - - -
      -
    • -

      camera_1

      -
      public static edu.wpi.cscore.UsbCamera camera_1
      -
    • -
    @@ -688,7 +667,7 @@

    teleopPeriodic

    -
      +
      • testPeriodic

        public void testPeriodic()
        @@ -699,6 +678,15 @@

        testPeriodic

      + + + +
        +
      • +

        putDebugInfo

        +
        public static void putDebugInfo()
        +
      • +
    diff --git a/docs/org/usfirst/frc/team3494/robot/RobotMap.html b/docs/org/usfirst/frc/team3494/robot/RobotMap.html index 9c0dbe9..f27c0e7 100644 --- a/docs/org/usfirst/frc/team3494/robot/RobotMap.html +++ b/docs/org/usfirst/frc/team3494/robot/RobotMap.html @@ -2,9 +2,9 @@ - + RobotMap - + @@ -175,27 +175,19 @@

    Field Summary

    static intGEAR_GRASP_CHONE GEAR_DOOR_F 
    static intGEAR_GRASP_CHTWO GEAR_DOOR_R 
    static intGEAR_GRASP_S2_BACKWARD GEAR_RAMP_F 
    static intGEAR_GRASP_S2_FORWARD 
    static intGEAR_RAMP_CHONE 
    static intGEAR_RAMP_CHTWO GEAR_RAMP_R 
    static int
    static intTURRET_LOWER TURRET_CONVEYER 
    static intTURRET_ENCLOWER_A 
    static intTURRET_ENCLOWER_B 
    static intTURRET_RING TURRET_ENCUPPER_A 
    static intTURRET_ENCUPPER_B 
    static intTURRET_LOWER 
    static int
    static intUP_MOTOR UNSCRAMBLER 
    static intXBOX_ONE UP_MOTOR 
    static intXBOX_ONE 
    static int XBOX_TWO 
    @@ -556,16 +568,29 @@

    CLIMBER_PTO_BACKARD

    - + + + + + @@ -595,94 +620,120 @@

    TURRET_UPPER

    - + - + - + + + + +
      +
    • +

      TURRET_ENCLOWER_B

      +
      public static final int TURRET_ENCLOWER_B
      +
      +
      See Also:
      +
      Constant Field Values
      +
      +
    • +
    + + + + - + - + - + - + diff --git a/docs/org/usfirst/frc/team3494/robot/UnitTypes.html b/docs/org/usfirst/frc/team3494/robot/UnitTypes.html index facd93f..9344397 100644 --- a/docs/org/usfirst/frc/team3494/robot/UnitTypes.html +++ b/docs/org/usfirst/frc/team3494/robot/UnitTypes.html @@ -2,9 +2,9 @@ - + UnitTypes - + diff --git a/docs/org/usfirst/frc/team3494/robot/class-use/AutoGenerator.html b/docs/org/usfirst/frc/team3494/robot/class-use/AutoGenerator.html index 965ff65..4749d66 100644 --- a/docs/org/usfirst/frc/team3494/robot/class-use/AutoGenerator.html +++ b/docs/org/usfirst/frc/team3494/robot/class-use/AutoGenerator.html @@ -2,9 +2,9 @@ - + Uses of Class org.usfirst.frc.team3494.robot.AutoGenerator - + diff --git a/docs/org/usfirst/frc/team3494/robot/class-use/DriveDirections.html b/docs/org/usfirst/frc/team3494/robot/class-use/DriveDirections.html index 8ec0add..e96810d 100644 --- a/docs/org/usfirst/frc/team3494/robot/class-use/DriveDirections.html +++ b/docs/org/usfirst/frc/team3494/robot/class-use/DriveDirections.html @@ -2,9 +2,9 @@ - + Uses of Class org.usfirst.frc.team3494.robot.DriveDirections - + @@ -182,12 +182,6 @@

    Uses of Runs the conveyer in the specified direction. - -void -Turret.turnTurret(DriveDirections dir) -
    Turns the turret at a hard-coded speed in the specified direction.
    - - diff --git a/docs/org/usfirst/frc/team3494/robot/class-use/OI.html b/docs/org/usfirst/frc/team3494/robot/class-use/OI.html index bf6b94b..60a5be5 100644 --- a/docs/org/usfirst/frc/team3494/robot/class-use/OI.html +++ b/docs/org/usfirst/frc/team3494/robot/class-use/OI.html @@ -2,9 +2,9 @@ - + Uses of Class org.usfirst.frc.team3494.robot.OI - + diff --git a/docs/org/usfirst/frc/team3494/robot/class-use/Robot.html b/docs/org/usfirst/frc/team3494/robot/class-use/Robot.html index cc4ab50..2367394 100644 --- a/docs/org/usfirst/frc/team3494/robot/class-use/Robot.html +++ b/docs/org/usfirst/frc/team3494/robot/class-use/Robot.html @@ -2,9 +2,9 @@ - + Uses of Class org.usfirst.frc.team3494.robot.Robot - + diff --git a/docs/org/usfirst/frc/team3494/robot/class-use/RobotMap.html b/docs/org/usfirst/frc/team3494/robot/class-use/RobotMap.html index 076c3c6..673fa0c 100644 --- a/docs/org/usfirst/frc/team3494/robot/class-use/RobotMap.html +++ b/docs/org/usfirst/frc/team3494/robot/class-use/RobotMap.html @@ -2,9 +2,9 @@ - + Uses of Class org.usfirst.frc.team3494.robot.RobotMap - + diff --git a/docs/org/usfirst/frc/team3494/robot/class-use/UnitTypes.html b/docs/org/usfirst/frc/team3494/robot/class-use/UnitTypes.html index aa6f558..db66241 100644 --- a/docs/org/usfirst/frc/team3494/robot/class-use/UnitTypes.html +++ b/docs/org/usfirst/frc/team3494/robot/class-use/UnitTypes.html @@ -2,9 +2,9 @@ - + Uses of Class org.usfirst.frc.team3494.robot.UnitTypes - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/DelayCommand.html b/docs/org/usfirst/frc/team3494/robot/commands/DelayCommand.html deleted file mode 100644 index 71731ed..0000000 --- a/docs/org/usfirst/frc/team3494/robot/commands/DelayCommand.html +++ /dev/null @@ -1,396 +0,0 @@ - - - - - -DelayCommand - - - - - - - - - - - - -
    -
    org.usfirst.frc.team3494.robot.commands
    -

    Class DelayCommand

    -
    -
    -
      -
    • java.lang.Object
    • -
    • -
        -
      • edu.wpi.first.wpilibj.command.Command
      • -
      • -
          -
        • org.usfirst.frc.team3494.robot.commands.DelayCommand
        • -
        -
      • -
      -
    • -
    -
    -
      -
    • -
      -
      All Implemented Interfaces:
      -
      edu.wpi.first.wpilibj.NamedSendable, edu.wpi.first.wpilibj.Sendable
      -
      -
      -
      -
      public class DelayCommand
      -extends edu.wpi.first.wpilibj.command.Command
      -
      Command to cause delays in autonomous. WIP.
      -
    • -
    -
    -
    -
      -
    • - -
        -
      • - - -

        Field Summary

        - - - - - - - - - - -
        Fields 
        Modifier and TypeField and Description
        (package private) doubletime 
        -
      • -
      - -
        -
      • - - -

        Constructor Summary

        - - - - - - - - -
        Constructors 
        Constructor and Description
        DelayCommand(double t) 
        -
      • -
      - -
        -
      • - - -

        Method Summary

        - - - - - - - - - - - - - - - - - - - - - - - - - - -
        All Methods Instance Methods Concrete Methods 
        Modifier and TypeMethod and Description
        protected voidend() 
        protected voidexecute() 
        protected voidinitialize() 
        protected voidinterrupted() 
        protected booleanisFinished() 
        -
          -
        • - - -

          Methods inherited from class edu.wpi.first.wpilibj.command.Command

          -cancel, clearRequirements, doesRequire, getGroup, getName, getSmartDashboardType, getTable, initTable, isCanceled, isInterruptible, isRunning, isTimedOut, requires, setInterruptible, setRunWhenDisabled, setTimeout, start, timeSinceInitialized, toString, willRunWhenDisabled
        • -
        -
          -
        • - - -

          Methods inherited from class java.lang.Object

          -clone, equals, finalize, getClass, hashCode, notify, notifyAll, wait, wait, wait
        • -
        -
      • -
      -
    • -
    -
    -
    -
      -
    • - -
        -
      • - - -

        Field Detail

        - - - -
          -
        • -

          time

          -
          double time
          -
        • -
        -
      • -
      - -
        -
      • - - -

        Constructor Detail

        - - - -
          -
        • -

          DelayCommand

          -
          public DelayCommand(double t)
          -
        • -
        -
      • -
      - -
        -
      • - - -

        Method Detail

        - - - -
          -
        • -

          initialize

          -
          protected void initialize()
          -
          -
          Overrides:
          -
          initialize in class edu.wpi.first.wpilibj.command.Command
          -
          -
        • -
        - - - -
          -
        • -

          execute

          -
          protected void execute()
          -
          -
          Overrides:
          -
          execute in class edu.wpi.first.wpilibj.command.Command
          -
          -
        • -
        - - - -
          -
        • -

          isFinished

          -
          protected boolean isFinished()
          -
          -
          Specified by:
          -
          isFinished in class edu.wpi.first.wpilibj.command.Command
          -
          -
        • -
        - - - -
          -
        • -

          end

          -
          protected void end()
          -
          -
          Overrides:
          -
          end in class edu.wpi.first.wpilibj.command.Command
          -
          -
        • -
        - - - -
          -
        • -

          interrupted

          -
          protected void interrupted()
          -
          -
          Overrides:
          -
          interrupted in class edu.wpi.first.wpilibj.command.Command
          -
          -
        • -
        -
      • -
      -
    • -
    -
    -
    - - - - - - - diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/AngleTurn.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/AngleTurn.html index cbd6f67..8ad15f9 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/AngleTurn.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/AngleTurn.html @@ -2,9 +2,9 @@ - + AngleTurn - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/CartesianTurnDrive.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/CartesianTurnDrive.html deleted file mode 100644 index e4792bf..0000000 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/CartesianTurnDrive.html +++ /dev/null @@ -1,457 +0,0 @@ - - - - - -CartesianTurnDrive - - - - - - - - - - - - -
    -
    org.usfirst.frc.team3494.robot.commands.auto
    -

    Class CartesianTurnDrive

    -
    -
    -
      -
    • java.lang.Object
    • -
    • -
        -
      • edu.wpi.first.wpilibj.command.Command
      • -
      • -
          -
        • org.usfirst.frc.team3494.robot.commands.auto.CartesianTurnDrive
        • -
        -
      • -
      -
    • -
    -
    -
      -
    • -
      -
      All Implemented Interfaces:
      -
      edu.wpi.first.wpilibj.NamedSendable, edu.wpi.first.wpilibj.Sendable
      -
      -
      -
      -
      public class CartesianTurnDrive
      -extends edu.wpi.first.wpilibj.command.Command
      -
      WIP coordinate drive system.
      -
      -
      Since:
      -
      0.0.2
      -
      See Also:
      -
      AngleTurn, -DistanceDrive
      -
      -
    • -
    -
    -
    -
      -
    • - -
        -
      • - - -

        Field Summary

        - - - - - - - - - - - - - - - - - - - - - - - - - - -
        Fields 
        Modifier and TypeField and Description
        private doubleangle 
        private doublehypot 
        private booleanisDone 
        private doublerise 
        private doublerun 
        -
      • -
      - -
        -
      • - - -

        Constructor Summary

        - - - - - - - - -
        Constructors 
        Constructor and Description
        CartesianTurnDrive(double rise, - double run) 
        -
      • -
      - -
        -
      • - - -

        Method Summary

        - - - - - - - - - - - - - - - - - - - - - - - - - - -
        All Methods Instance Methods Concrete Methods 
        Modifier and TypeMethod and Description
        protected voidend() 
        protected voidexecute() 
        protected voidinitialize() 
        protected voidinterrupted() 
        protected booleanisFinished() 
        -
          -
        • - - -

          Methods inherited from class edu.wpi.first.wpilibj.command.Command

          -cancel, clearRequirements, doesRequire, getGroup, getName, getSmartDashboardType, getTable, initTable, isCanceled, isInterruptible, isRunning, isTimedOut, requires, setInterruptible, setRunWhenDisabled, setTimeout, start, timeSinceInitialized, toString, willRunWhenDisabled
        • -
        -
          -
        • - - -

          Methods inherited from class java.lang.Object

          -clone, equals, finalize, getClass, hashCode, notify, notifyAll, wait, wait, wait
        • -
        -
      • -
      -
    • -
    -
    -
    -
      -
    • - -
        -
      • - - -

        Field Detail

        - - - -
          -
        • -

          rise

          -
          private double rise
          -
        • -
        - - - -
          -
        • -

          run

          -
          private double run
          -
        • -
        - - - -
          -
        • -

          hypot

          -
          private double hypot
          -
        • -
        - - - -
          -
        • -

          angle

          -
          private double angle
          -
        • -
        - - - -
          -
        • -

          isDone

          -
          private boolean isDone
          -
        • -
        -
      • -
      - -
        -
      • - - -

        Constructor Detail

        - - - -
          -
        • -

          CartesianTurnDrive

          -
          public CartesianTurnDrive(double rise,
          -                          double run)
          -
        • -
        -
      • -
      - -
        -
      • - - -

        Method Detail

        - - - -
          -
        • -

          initialize

          -
          protected void initialize()
          -
          -
          Overrides:
          -
          initialize in class edu.wpi.first.wpilibj.command.Command
          -
          -
        • -
        - - - -
          -
        • -

          execute

          -
          protected void execute()
          -
          -
          Overrides:
          -
          execute in class edu.wpi.first.wpilibj.command.Command
          -
          -
        • -
        - - - -
          -
        • -

          isFinished

          -
          protected boolean isFinished()
          -
          -
          Specified by:
          -
          isFinished in class edu.wpi.first.wpilibj.command.Command
          -
          -
        • -
        - - - -
          -
        • -

          end

          -
          protected void end()
          -
          -
          Overrides:
          -
          end in class edu.wpi.first.wpilibj.command.Command
          -
          -
        • -
        - - - -
          -
        • -

          interrupted

          -
          protected void interrupted()
          -
          -
          Overrides:
          -
          interrupted in class edu.wpi.first.wpilibj.command.Command
          -
          -
        • -
        -
      • -
      -
    • -
    -
    -
    - - - - - - - diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/ConstructedAuto.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/ConstructedAuto.html index 5db21a2..77e5c7d 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/ConstructedAuto.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/ConstructedAuto.html @@ -2,9 +2,9 @@ - + ConstructedAuto - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/DistanceDrive.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/DistanceDrive.html index 9e2b26a..1ba8809 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/DistanceDrive.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/DistanceDrive.html @@ -2,9 +2,9 @@ - + DistanceDrive - + @@ -168,6 +168,11 @@

    Constructor Summary

    Constructor and Description +DistanceDrive(double distance) +
    Alternative constructor.
    + + + DistanceDrive(double distance, UnitTypes unitType)
    Constructor.
    @@ -266,7 +271,7 @@

    Constructor Detail

    -
      +
      • DistanceDrive

        public DistanceDrive(double distance,
        @@ -281,6 +286,20 @@ 

        DistanceDrive

      + + + +
        +
      • +

        DistanceDrive

        +
        public DistanceDrive(double distance)
        +
        Alternative constructor.
        +
        +
        Parameters:
        +
        distance - The distance to drive, in inches.
        +
        +
      • +
    diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/NullAuto.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/NullAuto.html index fd9a3d0..58c6aec 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/NullAuto.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/NullAuto.html @@ -2,9 +2,9 @@ - + NullAuto - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/PIDAngleDrive.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/PIDAngleDrive.html index c63ac72..703027c 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/PIDAngleDrive.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/PIDAngleDrive.html @@ -2,9 +2,9 @@ - + PIDAngleDrive - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/PIDFullDrive.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/PIDFullDrive.html index aaa7dd6..e79eb83 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/PIDFullDrive.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/PIDFullDrive.html @@ -2,9 +2,9 @@ - + PIDFullDrive - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/PIDStraightDrive.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/PIDStraightDrive.html deleted file mode 100644 index d226b16..0000000 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/PIDStraightDrive.html +++ /dev/null @@ -1,438 +0,0 @@ - - - - - -PIDStraightDrive - - - - - - - - - - - - -
    -
    org.usfirst.frc.team3494.robot.commands.auto
    -

    Class PIDStraightDrive

    -
    -
    -
      -
    • java.lang.Object
    • -
    • -
        -
      • edu.wpi.first.wpilibj.command.Command
      • -
      • -
          -
        • org.usfirst.frc.team3494.robot.commands.auto.PIDStraightDrive
        • -
        -
      • -
      -
    • -
    -
    -
      -
    • -
      -
      All Implemented Interfaces:
      -
      edu.wpi.first.wpilibj.NamedSendable, edu.wpi.first.wpilibj.Sendable
      -
      -
      -
      -
      public class PIDStraightDrive
      -extends edu.wpi.first.wpilibj.command.Command
      -
      Drives straight using the drivetrain's PID loop. Only works in inches.
      -
    • -
    -
    -
    -
      -
    • - -
        -
      • - - -

        Field Summary

        - - - - - - - - - - - - - - -
        Fields 
        Modifier and TypeField and Description
        private doubleangle 
        private doubledistance 
        -
      • -
      - -
        -
      • - - -

        Constructor Summary

        - - - - - - - - - - - -
        Constructors 
        Constructor and Description
        PIDStraightDrive(double dist) -
        Other constructor.
        -
        PIDStraightDrive(double dist, - double angle) -
        Constructor.
        -
        -
      • -
      - -
        -
      • - - -

        Method Summary

        - - - - - - - - - - - - - - - - - - - - - - - - - - -
        All Methods Instance Methods Concrete Methods 
        Modifier and TypeMethod and Description
        protected voidend() 
        protected voidexecute() 
        protected voidinitialize() 
        protected voidinterrupted() 
        protected booleanisFinished() 
        -
          -
        • - - -

          Methods inherited from class edu.wpi.first.wpilibj.command.Command

          -cancel, clearRequirements, doesRequire, getGroup, getName, getSmartDashboardType, getTable, initTable, isCanceled, isInterruptible, isRunning, isTimedOut, requires, setInterruptible, setRunWhenDisabled, setTimeout, start, timeSinceInitialized, toString, willRunWhenDisabled
        • -
        -
          -
        • - - -

          Methods inherited from class java.lang.Object

          -clone, equals, finalize, getClass, hashCode, notify, notifyAll, wait, wait, wait
        • -
        -
      • -
      -
    • -
    -
    -
    -
      -
    • - -
        -
      • - - -

        Field Detail

        - - - -
          -
        • -

          distance

          -
          private double distance
          -
        • -
        - - - -
          -
        • -

          angle

          -
          private double angle
          -
        • -
        -
      • -
      - -
        -
      • - - -

        Constructor Detail

        - - - -
          -
        • -

          PIDStraightDrive

          -
          public PIDStraightDrive(double dist,
          -                        double angle)
          -
          Constructor.
          -
          -
          Parameters:
          -
          dist - The distance to drive, in inches.
          -
          angle - The angle to turn to.
          -
          -
        • -
        - - - -
          -
        • -

          PIDStraightDrive

          -
          public PIDStraightDrive(double dist)
          -
          Other constructor. Uses default angle of 0 degrees.
          -
          -
          Parameters:
          -
          dist - The distance to drive in inches.
          -
          -
        • -
        -
      • -
      - -
        -
      • - - -

        Method Detail

        - - - -
          -
        • -

          initialize

          -
          protected void initialize()
          -
          -
          Overrides:
          -
          initialize in class edu.wpi.first.wpilibj.command.Command
          -
          -
        • -
        - - - -
          -
        • -

          execute

          -
          protected void execute()
          -
          -
          Overrides:
          -
          execute in class edu.wpi.first.wpilibj.command.Command
          -
          -
        • -
        - - - -
          -
        • -

          isFinished

          -
          protected boolean isFinished()
          -
          -
          Specified by:
          -
          isFinished in class edu.wpi.first.wpilibj.command.Command
          -
          -
        • -
        - - - -
          -
        • -

          end

          -
          protected void end()
          -
          -
          Overrides:
          -
          end in class edu.wpi.first.wpilibj.command.Command
          -
          -
        • -
        - - - -
          -
        • -

          interrupted

          -
          protected void interrupted()
          -
          -
          Overrides:
          -
          interrupted in class edu.wpi.first.wpilibj.command.Command
          -
          -
        • -
        -
      • -
      -
    • -
    -
    -
    - - - - - - - diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/SetGearGrasp.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/SetGearGrasp.html index 8aa4020..7a76915 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/SetGearGrasp.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/SetGearGrasp.html @@ -2,9 +2,9 @@ - + SetGearGrasp - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/XYDrive.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/XYDrive.html index a8f62a3..9224c17 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/XYDrive.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/XYDrive.html @@ -2,9 +2,9 @@ - + XYDrive - + @@ -170,6 +170,13 @@

    Constructor Summary

    Constructor.
    + +XYDrive(double rise, + double run, + boolean PID) +
    More verbose(?) constructor.
    + + @@ -243,7 +250,7 @@

    Constructor Detail

    -
      +
      • XYDrive

        public XYDrive(double rise,
        @@ -258,6 +265,28 @@ 

        XYDrive

      + + + +
        +
      • +

        XYDrive

        +
        public XYDrive(double rise,
        +               double run,
        +               boolean PID)
        +
        More verbose(?) constructor.
        +
        +
        Parameters:
        +
        rise - The distance along the Y axis that the point is from the + robot.
        +
        run - The distance along the X axis that the point is from the + robot.
        +
        PID - Whether or not to use the drivetrain's PID control to drive to + the point. true is the recommended value, for obvious + reasons.
        +
        +
      • +
    diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/AngleTurn.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/AngleTurn.html index 932514c..d5fe28e 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/AngleTurn.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/AngleTurn.html @@ -2,9 +2,9 @@ - + Uses of Class org.usfirst.frc.team3494.robot.commands.auto.AngleTurn - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/CartesianTurnDrive.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/CartesianTurnDrive.html deleted file mode 100644 index 41de028..0000000 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/CartesianTurnDrive.html +++ /dev/null @@ -1,124 +0,0 @@ - - - - - -Uses of Class org.usfirst.frc.team3494.robot.commands.auto.CartesianTurnDrive - - - - - - - - - - - -
    -

    Uses of Class
    org.usfirst.frc.team3494.robot.commands.auto.CartesianTurnDrive

    -
    -
    No usage of org.usfirst.frc.team3494.robot.commands.auto.CartesianTurnDrive
    - - - - - - diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/ConstructedAuto.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/ConstructedAuto.html index d7c66ea..fdfeeb6 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/ConstructedAuto.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/ConstructedAuto.html @@ -2,9 +2,9 @@ - + Uses of Class org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/DistanceDrive.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/DistanceDrive.html index 178675a..fe75554 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/DistanceDrive.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/DistanceDrive.html @@ -2,9 +2,9 @@ - + Uses of Class org.usfirst.frc.team3494.robot.commands.auto.DistanceDrive - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/NullAuto.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/NullAuto.html index ae2f9e1..6a13e42 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/NullAuto.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/NullAuto.html @@ -2,9 +2,9 @@ - + Uses of Class org.usfirst.frc.team3494.robot.commands.auto.NullAuto - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/PIDAngleDrive.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/PIDAngleDrive.html index 73d252b..b4edb9c 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/PIDAngleDrive.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/PIDAngleDrive.html @@ -2,9 +2,9 @@ - + Uses of Class org.usfirst.frc.team3494.robot.commands.auto.PIDAngleDrive - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/PIDFullDrive.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/PIDFullDrive.html index 16d3e5e..5c863e1 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/PIDFullDrive.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/PIDFullDrive.html @@ -2,9 +2,9 @@ - + Uses of Class org.usfirst.frc.team3494.robot.commands.auto.PIDFullDrive - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/PIDStraightDrive.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/PIDStraightDrive.html deleted file mode 100644 index 56da23a..0000000 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/PIDStraightDrive.html +++ /dev/null @@ -1,124 +0,0 @@ - - - - - -Uses of Class org.usfirst.frc.team3494.robot.commands.auto.PIDStraightDrive - - - - - - - - - - - -
    -

    Uses of Class
    org.usfirst.frc.team3494.robot.commands.auto.PIDStraightDrive

    -
    -
    No usage of org.usfirst.frc.team3494.robot.commands.auto.PIDStraightDrive
    - - - - - - diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/SetGearGrasp.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/SetGearGrasp.html index 23bb43c..a0e1086 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/SetGearGrasp.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/SetGearGrasp.html @@ -2,9 +2,9 @@ - + Uses of Class org.usfirst.frc.team3494.robot.commands.auto.SetGearGrasp - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/StageTest.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/StageTest.html deleted file mode 100644 index 3aa3b28..0000000 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/StageTest.html +++ /dev/null @@ -1,124 +0,0 @@ - - - - - -Uses of Class org.usfirst.frc.team3494.robot.commands.auto.StageTest - - - - - - - - - - - -
    -

    Uses of Class
    org.usfirst.frc.team3494.robot.commands.auto.StageTest

    -
    -
    No usage of org.usfirst.frc.team3494.robot.commands.auto.StageTest
    - - - - - - diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/XYDrive.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/XYDrive.html index 475ddce..9a7f7ce 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/XYDrive.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/class-use/XYDrive.html @@ -2,9 +2,9 @@ - + Uses of Class org.usfirst.frc.team3494.robot.commands.auto.XYDrive - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/package-frame.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/package-frame.html index f137838..dc4859e 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/package-frame.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/package-frame.html @@ -2,9 +2,9 @@ - + org.usfirst.frc.team3494.robot.commands.auto - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/package-summary.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/package-summary.html index bc956e0..9792396 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/package-summary.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/package-summary.html @@ -2,9 +2,9 @@ - + org.usfirst.frc.team3494.robot.commands.auto - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/package-tree.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/package-tree.html index 2f08ea3..c3e7a66 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/package-tree.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/package-tree.html @@ -2,9 +2,9 @@ - + org.usfirst.frc.team3494.robot.commands.auto Class Hierarchy - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/package-use.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/package-use.html index cf50332..91eb281 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/package-use.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/package-use.html @@ -2,9 +2,9 @@ - + Uses of Package org.usfirst.frc.team3494.robot.commands.auto - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/SpeedTest.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/SpeedTest.html index 2573ce1..c57669d 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/SpeedTest.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/SpeedTest.html @@ -2,9 +2,9 @@ - + SpeedTest - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/StageTest.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/StageTest.html index 3f22b67..a3c774c 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/StageTest.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/StageTest.html @@ -2,9 +2,9 @@ - + StageTest - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/class-use/SpeedTest.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/class-use/SpeedTest.html index a909fff..31b9765 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/class-use/SpeedTest.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/class-use/SpeedTest.html @@ -2,9 +2,9 @@ - + Uses of Class org.usfirst.frc.team3494.robot.commands.auto.tests.SpeedTest - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/class-use/StageTest.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/class-use/StageTest.html index 5912028..fcef2c8 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/class-use/StageTest.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/class-use/StageTest.html @@ -2,9 +2,9 @@ - + Uses of Class org.usfirst.frc.team3494.robot.commands.auto.tests.StageTest - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/package-frame.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/package-frame.html index 1cf1c0c..46f70fa 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/package-frame.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/package-frame.html @@ -2,9 +2,9 @@ - + org.usfirst.frc.team3494.robot.commands.auto.tests - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/package-summary.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/package-summary.html index cc72beb..21f2ec0 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/package-summary.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/package-summary.html @@ -2,9 +2,9 @@ - + org.usfirst.frc.team3494.robot.commands.auto.tests - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/package-tree.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/package-tree.html index b3abe3f..aacd2db 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/package-tree.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/package-tree.html @@ -2,9 +2,9 @@ - + org.usfirst.frc.team3494.robot.commands.auto.tests Class Hierarchy - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/package-use.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/package-use.html index 32660ff..3654761 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/package-use.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/tests/package-use.html @@ -2,9 +2,9 @@ - + Uses of Package org.usfirst.frc.team3494.robot.commands.auto.tests - + diff --git a/docs/org/usfirst/frc/team3494/robot/commands/class-use/DelayCommand.html b/docs/org/usfirst/frc/team3494/robot/commands/class-use/DelayCommand.html deleted file mode 100644 index e9bd357..0000000 --- a/docs/org/usfirst/frc/team3494/robot/commands/class-use/DelayCommand.html +++ /dev/null @@ -1,124 +0,0 @@ - - - - - -Uses of Class org.usfirst.frc.team3494.robot.commands.DelayCommand - - - - - - - - - - - -
    -

    Uses of Class
    org.usfirst.frc.team3494.robot.commands.DelayCommand

    -
    -
    No usage of org.usfirst.frc.team3494.robot.commands.DelayCommand
    - - - - - - diff --git a/docs/org/usfirst/frc/team3494/robot/commands/climb/Climb.html b/docs/org/usfirst/frc/team3494/robot/commands/climb/Climb.html index aed08aa..134c5fd 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/climb/Climb.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/climb/Climb.html @@ -2,9 +2,9 @@ - + Climb - + @@ -50,7 +50,7 @@ -
    -
      -
    • - -
        -
      • - - -

        Constructor Detail

        - - - -
          -
        • -

          HoldInState

          -
          public HoldInState()
          -
        • -
        -
      • -
      - -
        -
      • - - -

        Method Detail

        - - - -
          -
        • -

          initialize

          -
          protected void initialize()
          -
          -
          Overrides:
          -
          initialize in class edu.wpi.first.wpilibj.command.Command
          -
          -
        • -
        - - - -
          -
        • -

          execute

          -
          protected void execute()
          -
          -
          Overrides:
          -
          execute in class edu.wpi.first.wpilibj.command.Command
          -
          -
        • -
        - - - -
          -
        • -

          isFinished

          -
          protected boolean isFinished()
          -
          -
          Specified by:
          -
          isFinished in class edu.wpi.first.wpilibj.command.Command
          -
          -
        • -
        - - - -
          -
        • -

          end

          -
          protected void end()
          -
          -
          Overrides:
          -
          end in class edu.wpi.first.wpilibj.command.Command
          -
          -
        • -
        - - - -
          -
        • -

          interrupted

          -
          protected void interrupted()
          -
          -
          Overrides:
          -
          interrupted in class edu.wpi.first.wpilibj.command.Command
          -
          -
        • -
        -
      • -
      -
    • -
    -
    - - - - - - - - diff --git a/docs/org/usfirst/frc/team3494/robot/commands/gears/HoldInState_Forward.html b/docs/org/usfirst/frc/team3494/robot/commands/gears/HoldInState_Forward.html index cb7d6d1..6111c34 100644 --- a/docs/org/usfirst/frc/team3494/robot/commands/gears/HoldInState_Forward.html +++ b/docs/org/usfirst/frc/team3494/robot/commands/gears/HoldInState_Forward.html @@ -2,9 +2,9 @@ - + HoldInState_Forward - + @@ -50,7 +50,7 @@ - -Turret -
    Turret subsystem.
    - - @@ -144,9 +139,6 @@

    Interface to apply to subsystems with motors. - -TurretEncoders  - diff --git a/docs/org/usfirst/frc/team3494/robot/vision/GearPipeline.html b/docs/org/usfirst/frc/team3494/robot/vision/GearPipeline.html index 280701a..3619dd6 100644 --- a/docs/org/usfirst/frc/team3494/robot/vision/GearPipeline.html +++ b/docs/org/usfirst/frc/team3494/robot/vision/GearPipeline.html @@ -2,9 +2,9 @@ - + GearPipeline - + diff --git a/docs/org/usfirst/frc/team3494/robot/vision/GripPipeline.html b/docs/org/usfirst/frc/team3494/robot/vision/GripPipeline.html index ca906d7..1db951f 100644 --- a/docs/org/usfirst/frc/team3494/robot/vision/GripPipeline.html +++ b/docs/org/usfirst/frc/team3494/robot/vision/GripPipeline.html @@ -2,9 +2,9 @@ - + GripPipeline - + diff --git a/docs/org/usfirst/frc/team3494/robot/vision/VisionUtils.html b/docs/org/usfirst/frc/team3494/robot/vision/VisionUtils.html index e8db09b..d1ae9e6 100644 --- a/docs/org/usfirst/frc/team3494/robot/vision/VisionUtils.html +++ b/docs/org/usfirst/frc/team3494/robot/vision/VisionUtils.html @@ -2,9 +2,9 @@ - + VisionUtils - + diff --git a/docs/org/usfirst/frc/team3494/robot/vision/class-use/GearPipeline.html b/docs/org/usfirst/frc/team3494/robot/vision/class-use/GearPipeline.html index b5eaff5..d418e69 100644 --- a/docs/org/usfirst/frc/team3494/robot/vision/class-use/GearPipeline.html +++ b/docs/org/usfirst/frc/team3494/robot/vision/class-use/GearPipeline.html @@ -2,9 +2,9 @@ - + Uses of Class org.usfirst.frc.team3494.robot.vision.GearPipeline - + diff --git a/docs/org/usfirst/frc/team3494/robot/vision/class-use/GripPipeline.html b/docs/org/usfirst/frc/team3494/robot/vision/class-use/GripPipeline.html index 3206862..a75639d 100644 --- a/docs/org/usfirst/frc/team3494/robot/vision/class-use/GripPipeline.html +++ b/docs/org/usfirst/frc/team3494/robot/vision/class-use/GripPipeline.html @@ -2,9 +2,9 @@ - + Uses of Class org.usfirst.frc.team3494.robot.vision.GripPipeline - + diff --git a/docs/org/usfirst/frc/team3494/robot/vision/class-use/VisionUtils.html b/docs/org/usfirst/frc/team3494/robot/vision/class-use/VisionUtils.html index 11adb48..945a684 100644 --- a/docs/org/usfirst/frc/team3494/robot/vision/class-use/VisionUtils.html +++ b/docs/org/usfirst/frc/team3494/robot/vision/class-use/VisionUtils.html @@ -2,9 +2,9 @@ - + Uses of Class org.usfirst.frc.team3494.robot.vision.VisionUtils - + diff --git a/docs/org/usfirst/frc/team3494/robot/vision/package-frame.html b/docs/org/usfirst/frc/team3494/robot/vision/package-frame.html index 25d9645..0ffa3a3 100644 --- a/docs/org/usfirst/frc/team3494/robot/vision/package-frame.html +++ b/docs/org/usfirst/frc/team3494/robot/vision/package-frame.html @@ -2,9 +2,9 @@ - + org.usfirst.frc.team3494.robot.vision - + diff --git a/docs/org/usfirst/frc/team3494/robot/vision/package-summary.html b/docs/org/usfirst/frc/team3494/robot/vision/package-summary.html index 53fd8a0..389eca8 100644 --- a/docs/org/usfirst/frc/team3494/robot/vision/package-summary.html +++ b/docs/org/usfirst/frc/team3494/robot/vision/package-summary.html @@ -2,9 +2,9 @@ - + org.usfirst.frc.team3494.robot.vision - + diff --git a/docs/org/usfirst/frc/team3494/robot/vision/package-tree.html b/docs/org/usfirst/frc/team3494/robot/vision/package-tree.html index aac80e7..d14af49 100644 --- a/docs/org/usfirst/frc/team3494/robot/vision/package-tree.html +++ b/docs/org/usfirst/frc/team3494/robot/vision/package-tree.html @@ -2,9 +2,9 @@ - + org.usfirst.frc.team3494.robot.vision Class Hierarchy - + diff --git a/docs/org/usfirst/frc/team3494/robot/vision/package-use.html b/docs/org/usfirst/frc/team3494/robot/vision/package-use.html index eb32497..a84d646 100644 --- a/docs/org/usfirst/frc/team3494/robot/vision/package-use.html +++ b/docs/org/usfirst/frc/team3494/robot/vision/package-use.html @@ -2,9 +2,9 @@ - + Uses of Package org.usfirst.frc.team3494.robot.vision - + diff --git a/docs/overview-frame.html b/docs/overview-frame.html index 6ad559a..94b0053 100644 --- a/docs/overview-frame.html +++ b/docs/overview-frame.html @@ -2,9 +2,9 @@ - + Overview List - + @@ -20,8 +20,6 @@

    Packages

  • org.usfirst.frc.team3494.robot.commands.climb
  • org.usfirst.frc.team3494.robot.commands.drive
  • org.usfirst.frc.team3494.robot.commands.gears
  • -
  • org.usfirst.frc.team3494.robot.commands.turret
  • -
  • org.usfirst.frc.team3494.robot.sensors
  • org.usfirst.frc.team3494.robot.subsystems
  • org.usfirst.frc.team3494.robot.vision
  • diff --git a/docs/overview-summary.html b/docs/overview-summary.html index ac3044f..f749d04 100644 --- a/docs/overview-summary.html +++ b/docs/overview-summary.html @@ -2,9 +2,9 @@ - + Overview - + @@ -115,18 +115,6 @@ -org.usfirst.frc.team3494.robot.commands.turret - -
    Turret related packages.
    - - - -org.usfirst.frc.team3494.robot.sensors - -
    Package for sensor type classes.
    - - - org.usfirst.frc.team3494.robot.subsystems   diff --git a/docs/overview-tree.html b/docs/overview-tree.html index d98b5fc..76bd820 100644 --- a/docs/overview-tree.html +++ b/docs/overview-tree.html @@ -2,9 +2,9 @@ - + Class Hierarchy - + @@ -80,8 +80,6 @@

    Hierarchy For All Packages

  • org.usfirst.frc.team3494.robot.commands.climb,
  • org.usfirst.frc.team3494.robot.commands.drive,
  • org.usfirst.frc.team3494.robot.commands.gears,
  • -
  • org.usfirst.frc.team3494.robot.commands.turret,
  • -
  • org.usfirst.frc.team3494.robot.sensors,
  • org.usfirst.frc.team3494.robot.subsystems,
  • org.usfirst.frc.team3494.robot.vision
  • @@ -96,14 +94,13 @@

    Class Hierarchy

    • org.usfirst.frc.team3494.robot.commands.auto.AngleTurn
    • org.usfirst.frc.team3494.robot.commands.climb.Climb
    • -
    • org.usfirst.frc.team3494.robot.commands.climb.ClimberToggle
    • +
    • org.usfirst.frc.team3494.robot.commands.climb.ClimberPTOSetter
    • edu.wpi.first.wpilibj.command.CommandGroup
      • org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto
      • org.usfirst.frc.team3494.robot.commands.auto.XYDrive
    • -
    • org.usfirst.frc.team3494.robot.commands.DelayCommand
    • org.usfirst.frc.team3494.robot.commands.auto.DistanceDrive
    • org.usfirst.frc.team3494.robot.commands.drive.Drive
    • org.usfirst.frc.team3494.robot.commands.drive.HoldDriveTrain
    • @@ -112,19 +109,17 @@

      Class Hierarchy

    • org.usfirst.frc.team3494.robot.commands.auto.PIDAngleDrive
    • org.usfirst.frc.team3494.robot.commands.auto.PIDFullDrive
    • org.usfirst.frc.team3494.robot.commands.auto.SetGearGrasp
    • +
    • org.usfirst.frc.team3494.robot.commands.gears.SetHolderState
    • org.usfirst.frc.team3494.robot.commands.gears.SetReverse
    • -
    • org.usfirst.frc.team3494.robot.commands.turret.Shoot
    • org.usfirst.frc.team3494.robot.commands.auto.tests.SpeedTest
    • org.usfirst.frc.team3494.robot.commands.auto.tests.StageTest
    • org.usfirst.frc.team3494.robot.commands.climb.StopClimber
    • org.usfirst.frc.team3494.robot.commands.gears.ToggleGearPosition
    • org.usfirst.frc.team3494.robot.commands.gears.ToggleGearRamp
    • -
    • org.usfirst.frc.team3494.robot.commands.turret.TurretCon
  • org.usfirst.frc.team3494.robot.vision.GearPipeline (implements edu.wpi.first.wpilibj.vision.VisionPipeline)
  • org.usfirst.frc.team3494.robot.vision.GripPipeline (implements edu.wpi.first.wpilibj.vision.VisionPipeline)
  • -
  • org.usfirst.frc.team3494.robot.sensors.LineBreak
  • org.usfirst.frc.team3494.robot.OI
  • edu.wpi.first.wpilibj.RobotBase
      @@ -142,13 +137,11 @@

      Class Hierarchy

    • org.usfirst.frc.team3494.robot.subsystems.Conveyer (implements org.usfirst.frc.team3494.robot.subsystems.IMotorizedSubsystem)
    • org.usfirst.frc.team3494.robot.subsystems.GearTake_2
    • org.usfirst.frc.team3494.robot.subsystems.Kompressor
    • -
    • org.usfirst.frc.team3494.robot.subsystems.MonoGearTake
    • edu.wpi.first.wpilibj.command.PIDSubsystem (implements edu.wpi.first.wpilibj.Sendable)
    • -
    • org.usfirst.frc.team3494.robot.subsystems.Turret (implements org.usfirst.frc.team3494.robot.subsystems.IMotorizedSubsystem)
  • org.usfirst.frc.team3494.robot.vision.VisionUtils
  • @@ -167,7 +160,6 @@

    Enum Hierarchy

    diff --git a/docs/package-list b/docs/package-list index 42fdb1a..b64563d 100644 --- a/docs/package-list +++ b/docs/package-list @@ -5,7 +5,5 @@ org.usfirst.frc.team3494.robot.commands.auto.tests org.usfirst.frc.team3494.robot.commands.climb org.usfirst.frc.team3494.robot.commands.drive org.usfirst.frc.team3494.robot.commands.gears -org.usfirst.frc.team3494.robot.commands.turret -org.usfirst.frc.team3494.robot.sensors org.usfirst.frc.team3494.robot.subsystems org.usfirst.frc.team3494.robot.vision