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 009e862..059692b 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,6 +1,8 @@ package org.usfirst.frc.team3494.robot; +import org.usfirst.frc.team3494.robot.commands.auto.AngleTurn; import org.usfirst.frc.team3494.robot.commands.auto.DistanceDrive; +import org.usfirst.frc.team3494.robot.commands.intake.SwitchPosition; import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.XboxController; @@ -41,8 +43,15 @@ public class OI { // until it is finished as determined by it's isFinished method. // button.whenReleased(new ExampleCommand()); public JoystickButton xbox_a = new JoystickButton(xbox, 1); + public JoystickButton xbox_lt = new JoystickButton(xbox, 5); + public JoystickButton xbox_rt = new JoystickButton(xbox, 6); + public JoystickButton xbox_b = new JoystickButton(xbox, 2); + public JoystickButton xbox_y = new JoystickButton(xbox, 4); + public JoystickButton xbox_x = new JoystickButton(xbox, 3); public OI() { - xbox_a.whenPressed(new DistanceDrive(8.0, UnitTypes.INCHES)); + xbox_b.whenPressed(new SwitchPosition()); + xbox_y.whenPressed(new AngleTurn(90)); + xbox_x.whenPressed(new DistanceDrive(2, UnitTypes.FEET)); } } 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 4c45489..5fd6d6e 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 @@ -2,11 +2,16 @@ import org.usfirst.frc.team3494.robot.subsystems.Climber; import org.usfirst.frc.team3494.robot.subsystems.Drivetrain; +import org.usfirst.frc.team3494.robot.subsystems.Intake; import org.usfirst.frc.team3494.robot.subsystems.Kompressor; import org.usfirst.frc.team3494.robot.subsystems.Turret; +import com.kauailabs.navx.frc.AHRS; + import edu.wpi.first.wpilibj.IterativeRobot; +import edu.wpi.first.wpilibj.PowerDistributionPanel; import edu.wpi.first.wpilibj.Preferences; +import edu.wpi.first.wpilibj.SerialPort; import edu.wpi.first.wpilibj.command.Command; import edu.wpi.first.wpilibj.command.Scheduler; import edu.wpi.first.wpilibj.livewindow.LiveWindow; @@ -26,7 +31,15 @@ public class Robot extends IterativeRobot { public static Drivetrain driveTrain; public static Climber climber; public static Turret turret; + public static Intake intake; public static Kompressor kompressor; + /** + * The gyro board mounted to the RoboRIO. + * + * @since 0.0.2 + */ + public static AHRS ahrs; + public static PowerDistributionPanel pdp = new PowerDistributionPanel(); Command autonomousCommand; SendableChooser chooser = new SendableChooser<>(); @@ -41,12 +54,14 @@ public void robotInit() { // chooser.addDefault("Default Auto", new ExampleCommand()); // chooser.addObject("My Auto", new MyAutoCommand()); driveTrain = new Drivetrain(); - oi = new OI(); climber = new Climber(); turret = new Turret(); kompressor = new Kompressor(); + intake = new Intake(); + oi = new OI(); + ahrs = new AHRS(SerialPort.Port.kMXP); // put chooser on DS - SmartDashboard.putData("Auto mode", chooser); + // SmartDashboard.putData("Auto mode", chooser); // get preferences prefs = Preferences.getInstance(); } @@ -94,7 +109,7 @@ public void autonomousInit() { } /** - * This function is called periodically during autonomous + * This function is called periodically during autonomous. */ @Override public void autonomousPeriodic() { @@ -112,11 +127,20 @@ public void teleopInit() { } /** - * This function is called periodically during operator control + * This function is called periodically during operator control. */ @Override public void teleopPeriodic() { Scheduler.getInstance().run(); + SmartDashboard.putNumber("Gyro Z", ahrs.getAngle()); + + 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("Motor 13", Robot.pdp.getCurrent(13)); + SmartDashboard.putNumber("Motor 14", Robot.pdp.getCurrent(14)); + SmartDashboard.putNumber("Motor 15", Robot.pdp.getCurrent(15)); } /** 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 696402c..b2e1d2f 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 @@ -17,7 +17,7 @@ public class RobotMap { // public static int rangefinderPort = 1; // public static int rangefinderModule = 1; // drivetrain left - public static final int leftTalonOne = 0; + public static final int leftTalonOne = 17; public static final int leftTalonTwo = 1; public static final int leftTalonThree = 2; // drivetrain right @@ -32,8 +32,8 @@ public class RobotMap { public static final int ENCODER_RIGHT_A = 0; public static final int ENCODER_RIGHT_B = 1; // intake - public static final int INTAKE_MOTOR = 60; - public static final int UP_MOTOR = 65; + public static final int INTAKE_MOTOR = 0; + public static final int UP_MOTOR = 2; // climber public static final int CLIMBER_MOTOR = 1; // turret @@ -42,4 +42,6 @@ public class RobotMap { public static final int TURRET_UPPER = 64; // compressor public static final int COMPRESSOR = 0; + public static final int INTAKE_PISTON_CHONE = 2; + public static final int INTAKE_PISTON_CHTWO = 3; } 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 new file mode 100644 index 0000000..f452f74 --- /dev/null +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/AngleTurn.java @@ -0,0 +1,63 @@ +package org.usfirst.frc.team3494.robot.commands.auto; + +import org.usfirst.frc.team3494.robot.Robot; + +import edu.wpi.first.wpilibj.command.Command; + +/** + * Turns the robot using the gyro board mounted to the RoboRIO. The angle to + * turn by must be specified in the constructor. + * + * @since 0.0.2 + * @see org.usfirst.frc.team3494.robot.Robot + * @see org.usfirst.frc.team3494.robot.subsystems.Drivetrain + */ +public class AngleTurn extends Command { + + private double angle; + private static double tolerance = Robot.prefs.getDouble("angle tolerance", 2.5); + + public AngleTurn(double angle) { + // Use requires() here to declare subsystem dependencies + // eg. requires(chassis); + requires(Robot.driveTrain); + this.angle = angle; + } + + // Called just before this Command runs the first time + protected void initialize() { + Robot.ahrs.reset(); + } + + // Called repeatedly when this Command is scheduled to run + protected void execute() { + if (!((Robot.ahrs.getAngle() > this.angle - tolerance) && (Robot.ahrs.getAngle() < this.angle + tolerance))) { + System.out.println(this.angle); + if (this.angle > 0) { + Robot.driveTrain.adjustedTankDrive(-0.4, 0.4); + Robot.driveTrain.resetRight(); + return; + } else if (this.angle < 0) { + Robot.driveTrain.adjustedTankDrive(0.4, -0.4); + Robot.driveTrain.resetRight(); + return; + } else { + Robot.driveTrain.adjustedTankDrive(0.4, 0.4); + } + } + } + + // Make this return true when this Command no longer needs to run execute() + protected boolean isFinished() { + return ((Robot.ahrs.getAngle() > this.angle - tolerance) && (Robot.ahrs.getAngle() < this.angle + tolerance)); + } + + // Called once after isFinished returns true + protected void end() { + } + + // Called when another command which requires one or more of the same + // subsystems is scheduled to run + protected void interrupted() { + } +} diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/CartesianTurnDrive.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/CartesianTurnDrive.java new file mode 100644 index 0000000..ab9a04a --- /dev/null +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/auto/CartesianTurnDrive.java @@ -0,0 +1,68 @@ +package org.usfirst.frc.team3494.robot.commands.auto; + +import org.usfirst.frc.team3494.robot.Robot; +import org.usfirst.frc.team3494.robot.UnitTypes; + +import edu.wpi.first.wpilibj.command.Command; +import edu.wpi.first.wpilibj.command.Scheduler; + +/** + * WIP coordinate drive system. + * + * @see org.usfirst.frc.team3494.robot.commands.auto.AngleTurn + * @see org.usfirst.frc.team3494.robot.commands.auto.DistanceDrive + * @since 0.0.2 + */ +public class CartesianTurnDrive extends Command { + + private double rise; + private double run; + private double hypot; + private double angle; + private boolean isDone = false; + + public CartesianTurnDrive(double rise, double run) { + // Use requires() here to declare subsystem dependencies + // eg. requires(chassis); + requires(Robot.driveTrain); + this.rise = rise; + this.run = run; + // angle = inverse tan(rise/run) + this.angle = Math.toDegrees(Math.atan2(rise, run)); + } + + // Called just before this Command runs the first time + protected void initialize() { + Robot.ahrs.reset(); + Robot.driveTrain.resetRight(); + double run2 = this.run * this.run; + double rise2 = this.rise * this.rise; + this.hypot = Math.sqrt(run2 + rise2); + } + + // Called repeatedly when this Command is scheduled to run + protected void execute() { + Scheduler.getInstance().add(new AngleTurn(this.angle)); + Robot.driveTrain.resetRight(); + if (Robot.driveTrain.getRightDistance(UnitTypes.INCHES) > this.hypot) { + Robot.driveTrain.adjustedTankDrive(0.3, 0.3); + } else { + this.isDone = true; + } + } + + // Make this return true when this Command no longer needs to run execute() + protected boolean isFinished() { + return this.isDone; + } + + // Called once after isFinished returns true + protected void end() { + this.isDone = false; + } + + // Called when another command which requires one or more of the same + // subsystems is scheduled to run + protected void interrupted() { + } +} 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 fc57d54..f862b8e 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 @@ -6,11 +6,15 @@ import edu.wpi.first.wpilibj.command.Command; /** - * Drives a given distance. + * Drives a given distance. Currently suffering from encoder issues. + * + * @see org.usfirst.frc.team3494.robot.subsystems.Drivetrain + * @since 0.0.2 */ public class DistanceDrive extends Command { - double dist = 0; - UnitTypes unit; + + private double dist; + private UnitTypes unit; public DistanceDrive(double distance, UnitTypes unitType) { // Use requires() here to declare subsystem dependencies @@ -24,20 +28,21 @@ public DistanceDrive(double distance, UnitTypes unitType) { // Called just before this Command runs the first time @Override protected void initialize() { - Robot.driveTrain.stopAll(); Robot.driveTrain.resetRight(); } // Called repeatedly when this Command is scheduled to run @Override protected void execute() { - Robot.driveTrain.TankDrive(0.2, 0.2); + System.out.println("Driving forward: " + this.dist); + Robot.driveTrain.adjustedTankDrive(0.3, 0.3); + System.out.println("Right distance: " + Robot.driveTrain.getRightDistance(this.unit)); } // Make this return true when this Command no longer needs to run execute() @Override protected boolean isFinished() { - return Robot.driveTrain.getRightDistance(UnitTypes.INCHES) >= 8; + return (Robot.driveTrain.getRightDistance(this.unit) >= this.dist); } // Called once after isFinished returns true 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 8268165..8d5d81e 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 @@ -29,19 +29,23 @@ protected void initialize() { @Override protected void execute() { if (Robot.prefs.getBoolean("xcontrol", true)) { - Robot.driveTrain.wpiDrive.arcadeDrive(Robot.oi.xbox.getY(Hand.kLeft) * -1, - Robot.oi.xbox.getX(Hand.kLeft) * -1); + if (Robot.prefs.getBoolean("arcade", true)) { + Robot.driveTrain.wpiDrive.arcadeDrive(Robot.oi.xbox.getY(Hand.kLeft), -Robot.oi.xbox.getX(Hand.kLeft)); + } else { + Robot.driveTrain.adjustedTankDrive(-Robot.oi.xbox.getY(Hand.kLeft), -Robot.oi.xbox.getY(Hand.kRight)); + } } else { - Robot.driveTrain.TankDrive(Robot.oi.leftStick.getY(), Robot.oi.rightStick.getY()); + Robot.driveTrain.TankDrive(-Robot.oi.leftStick.getY(), -Robot.oi.rightStick.getY()); } + double throttle = Robot.oi.xbox.getTriggerAxis(Hand.kRight); if (Robot.oi.xbox.getPOV() == 0) { - Robot.driveTrain.adjustedTankDrive(0.4, 0.4); + Robot.driveTrain.adjustedTankDrive(throttle, throttle); } else if (Robot.oi.xbox.getPOV() == 90) { - Robot.driveTrain.adjustedTankDrive(-0.4, 0.4); + Robot.driveTrain.adjustedTankDrive(-throttle, throttle); } else if (Robot.oi.xbox.getPOV() == 180) { - Robot.driveTrain.adjustedTankDrive(-0.4, -0.4); + Robot.driveTrain.adjustedTankDrive(-throttle, -throttle); } else if (Robot.oi.xbox.getPOV() == 270) { - Robot.driveTrain.adjustedTankDrive(0.4, -0.4); + Robot.driveTrain.adjustedTankDrive(throttle, -throttle); } } diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/intake/RunIntake.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/intake/RunIntake.java new file mode 100644 index 0000000..7946224 --- /dev/null +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/intake/RunIntake.java @@ -0,0 +1,54 @@ +package org.usfirst.frc.team3494.robot.commands.intake; + +import org.usfirst.frc.team3494.robot.Robot; + +import edu.wpi.first.wpilibj.command.Command; + +/** + * Runs the intake. Default command for Intake subsystem. + */ +public class RunIntake extends Command { + + boolean running = false; + double speed; + + public RunIntake() { + // Use requires() here to declare subsystem dependencies + // eg. requires(chassis); + requires(Robot.intake); + } + + // Called just before this Command runs the first time + protected void initialize() { + } + + // Called repeatedly when this Command is scheduled to run + protected void execute() { + if (Robot.oi.xbox_lt.get()) { + this.speed = 1; + this.running = !this.running; + } else if (Robot.oi.xbox_rt.get()) { + this.speed = -1; + this.running = !this.running; + } + if (running) { + Robot.intake.runIntake(this.speed); + } else { + Robot.intake.stopAll(); + } + } + + // Make this return true when this Command no longer needs to run execute() + protected boolean isFinished() { + return false; + } + + // Called once after isFinished returns true + protected void end() { + } + + // Called when another command which requires one or more of the same + // subsystems is scheduled to run + protected void interrupted() { + } +} diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/intake/SwitchPosition.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/intake/SwitchPosition.java new file mode 100644 index 0000000..e4d73fb --- /dev/null +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/intake/SwitchPosition.java @@ -0,0 +1,48 @@ +package org.usfirst.frc.team3494.robot.commands.intake; + +import org.usfirst.frc.team3494.robot.Robot; + +import edu.wpi.first.wpilibj.command.Command; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; + +/** + * Deploys the intake for the start of teleop. + * + * @see org.usfirst.frc.team3494.robot.subsystems.Intake + */ +public class SwitchPosition extends Command { + + public SwitchPosition() { + // Use requires() here to declare subsystem dependencies + // eg. requires(chassis); + requires(Robot.intake); + } + + // Called just before this Command runs the first time + protected void initialize() { + } + + // Called repeatedly when this Command is scheduled to run + protected void execute() { + if (!Robot.intake.isDeployed) { + Robot.intake.pushForward(); + } else { + Robot.intake.retract(); + } + SmartDashboard.putBoolean("Intake Deployed", Robot.intake.isDeployed); + } + + // Make this return true when this Command no longer needs to run execute() + protected boolean isFinished() { + return true; + } + + // Called once after isFinished returns true + protected void end() { + } + + // Called when another command which requires one or more of the same + // subsystems is scheduled to run + protected void interrupted() { + } +} diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/intake/package-info.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/intake/package-info.java new file mode 100644 index 0000000..e9ecfbd --- /dev/null +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/commands/intake/package-info.java @@ -0,0 +1,7 @@ +/** + * Package for intake-related commands. Commands for use in auto belong in + * {@link org.usfirst.frc.team3494.robot.commands.auto}. + * + * @see org.usfirst.frc.team3494.robot.subsystems.Intake + */ +package org.usfirst.frc.team3494.robot.commands.intake; \ No newline at end of file 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 1d57305..6b6538b 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 @@ -69,8 +69,11 @@ public Drivetrain() { super("Drivetrain"); this.driveLeftMaster = new CANTalon(RobotMap.leftTalonOne); + this.driveLeftMaster.enableBrakeMode(true); this.driveLeftFollower_One = new CANTalon(RobotMap.leftTalonTwo); + this.driveLeftFollower_One.enableBrakeMode(true); this.driveLeftFollower_Two = new CANTalon(RobotMap.leftTalonThree); + this.driveLeftFollower_Two.enableBrakeMode(true); // master follower this.driveLeftFollower_One.changeControlMode(CANTalon.TalonControlMode.Follower); this.driveLeftFollower_One.set(driveLeftMaster.getDeviceID()); @@ -78,8 +81,11 @@ public Drivetrain() { this.driveLeftFollower_Two.set(driveLeftMaster.getDeviceID()); this.driveRightMaster = new CANTalon(RobotMap.rightTalonOne); + this.driveRightMaster.enableBrakeMode(true); this.driveRightFollower_One = new CANTalon(RobotMap.rightTalonTwo); + this.driveRightFollower_One.enableBrakeMode(true); this.driveRightFollower_Two = new CANTalon(RobotMap.rightTalonThree); + this.driveLeftFollower_Two.enableBrakeMode(true); // master follower this.driveRightFollower_One.changeControlMode(CANTalon.TalonControlMode.Follower); this.driveRightFollower_One.set(driveRightMaster.getDeviceID()); @@ -88,8 +94,10 @@ public Drivetrain() { this.wpiDrive = new RobotDrive(driveLeftMaster, driveRightMaster); - this.encRight = new Encoder(RobotMap.ENCODER_RIGHT_A, RobotMap.ENCODER_RIGHT_B); + this.encRight = new Encoder(RobotMap.ENCODER_RIGHT_A, RobotMap.ENCODER_RIGHT_B, false, + Encoder.EncodingType.k4X); this.encRight.setDistancePerPulse(1 / 1440); + this.encRight.reset(); } // Put methods for controlling this subsystem // here. Call these from Commands. @@ -142,13 +150,18 @@ public void adjustedTankDrive(double left, double right) { * unit. */ public double getRightDistance(UnitTypes unit) { - double inches = (Math.PI * 4) * (1 / this.encRight.getDistance()); + double inches; + try { + inches = ((Math.PI * 4) * (this.encRight.get() / 1440) * 360); + } catch (ArithmeticException e) { + inches = 0; + } if (unit.equals(UnitTypes.INCHES)) { - return (Math.PI * 4) * (1 / this.encRight.getDistance()); + return inches; } else if (unit.equals(UnitTypes.FEET)) { return inches / 12; } else { - return this.encRight.getDistance(); + return this.encRight.get(); } } diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Intake.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Intake.java index 7bb0ac9..4c6060e 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Intake.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Intake.java @@ -1,11 +1,12 @@ package org.usfirst.frc.team3494.robot.subsystems; import org.usfirst.frc.team3494.robot.RobotMap; +import org.usfirst.frc.team3494.robot.commands.intake.RunIntake; -import com.ctre.CANTalon; - +import edu.wpi.first.wpilibj.DoubleSolenoid; import edu.wpi.first.wpilibj.TalonSRX; import edu.wpi.first.wpilibj.command.Subsystem; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; /** * Intake subsystem. Contains methods for controlling the ball intake. @@ -19,12 +20,17 @@ public class Intake extends Subsystem implements IMotorizedSubsystem { * @see RobotMap */ private TalonSRX inMotor; - private CANTalon upMotor; + private TalonSRX upMotor; + // pistons push + private DoubleSolenoid piston; + public boolean isDeployed; public Intake() { super("Intake"); this.inMotor = new TalonSRX(RobotMap.INTAKE_MOTOR); - this.upMotor = new CANTalon(RobotMap.UP_MOTOR); + this.upMotor = new TalonSRX(RobotMap.UP_MOTOR); + this.piston = new DoubleSolenoid(RobotMap.INTAKE_PISTON_CHONE, RobotMap.INTAKE_PISTON_CHTWO); + this.isDeployed = false; } // Put methods for controlling this subsystem // here. Call these from Commands. @@ -33,18 +39,12 @@ public Intake() { public void initDefaultCommand() { // Set the default command for a subsystem here. // setDefaultCommand(new MySpecialCommand()); + this.setDefaultCommand(new RunIntake()); } public void runIntake(double speed) { this.inMotor.set(speed); - if (speed > 0) { - this.upMotor.set(speed - 0.3); - } else if (speed < 0) { - this.upMotor.set(speed + 0.3); - } else { - // no - this.stopAll(); - } + this.upMotor.set(speed); } @Override @@ -58,4 +58,24 @@ public void setAll(double speed) { this.inMotor.set(speed); this.upMotor.set(speed); } + + public void pushForward() { + this.piston.set(DoubleSolenoid.Value.kForward); + this.isDeployed = true; + } + + public void retract() { + this.piston.set(DoubleSolenoid.Value.kReverse); + this.isDeployed = false; + } + + public void setPiston(DoubleSolenoid.Value position) { + this.piston.set(position); + if (position.equals(DoubleSolenoid.Value.kForward)) { + this.isDeployed = true; + } else { + this.isDeployed = true; + } + SmartDashboard.putBoolean("Intake Deployed", this.isDeployed); + } } diff --git a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Kompressor.java b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Kompressor.java index 6b4f290..57e33fa 100644 --- a/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Kompressor.java +++ b/3494_2017_repo/src/org/usfirst/frc/team3494/robot/subsystems/Kompressor.java @@ -10,17 +10,17 @@ */ public class Kompressor extends Subsystem { public Compressor compress; - // Put methods for controlling this subsystem - // here. Call these from Commands. + + // Put methods for controlling this subsystem + // here. Call these from Commands. public Kompressor() { super("Kompressor"); this.compress = new Compressor(RobotMap.COMPRESSOR); this.compress.setClosedLoopControl(true); } - public void initDefaultCommand() { - // Set the default command for a subsystem here. - //setDefaultCommand(new MySpecialCommand()); - } + public void initDefaultCommand() { + // Set the default command for a subsystem here. + // setDefaultCommand(new MySpecialCommand()); + } } - diff --git a/docs/allclasses-frame.html b/docs/allclasses-frame.html index f46fcb7..f756ed0 100644 --- a/docs/allclasses-frame.html +++ b/docs/allclasses-frame.html @@ -2,9 +2,9 @@ - + All Classes - + @@ -12,6 +12,8 @@

All Classes

@@ -218,12 +238,57 @@

xbox

- diff --git a/docs/org/usfirst/frc/team3494/robot/Robot.html b/docs/org/usfirst/frc/team3494/robot/Robot.html index d759523..ddd9f59 100644 --- a/docs/org/usfirst/frc/team3494/robot/Robot.html +++ b/docs/org/usfirst/frc/team3494/robot/Robot.html @@ -2,9 +2,9 @@ - + Robot - + @@ -145,25 +145,43 @@

Field Summary

Field and Description +static com.kauailabs.navx.frc.AHRS +ahrs +
The gyro board mounted to the RoboRIO.
+ + + (package private) edu.wpi.first.wpilibj.command.Command autonomousCommand  - + (package private) edu.wpi.first.wpilibj.smartdashboard.SendableChooser<edu.wpi.first.wpilibj.command.Command> chooser  - + static Climber climber  - + static Drivetrain driveTrain  + +static Intake +intake  + +static Kompressor +kompressor  + + static OI oi  + +static edu.wpi.first.wpilibj.PowerDistributionPanel +pdp  + static edu.wpi.first.wpilibj.Preferences prefs  @@ -221,7 +239,7 @@

Method Summary

void autonomousPeriodic() -
This function is called periodically during autonomous
+
This function is called periodically during autonomous.
@@ -248,7 +266,7 @@

Method Summary

void teleopPeriodic() -
This function is called periodically during operator control
+
This function is called periodically during operator control.
@@ -329,6 +347,47 @@

turret

public static Turret turret
+ + + + + + + + + + + + + + + + @@ -454,7 +513,7 @@

autonomousInit

  • autonomousPeriodic

    public void autonomousPeriodic()
    -
    This function is called periodically during autonomous
    +
    This function is called periodically during autonomous.
    Overrides:
    autonomousPeriodic in class edu.wpi.first.wpilibj.IterativeRobot
    @@ -481,7 +540,7 @@

    teleopInit

  • teleopPeriodic

    public void teleopPeriodic()
    -
    This function is called periodically during operator control
    +
    This function is called periodically during operator control.
    Overrides:
    teleopPeriodic in class edu.wpi.first.wpilibj.IterativeRobot
    diff --git a/docs/org/usfirst/frc/team3494/robot/RobotMap.html b/docs/org/usfirst/frc/team3494/robot/RobotMap.html index e91f30e..9e952f9 100644 --- a/docs/org/usfirst/frc/team3494/robot/RobotMap.html +++ b/docs/org/usfirst/frc/team3494/robot/RobotMap.html @@ -2,9 +2,9 @@ - + RobotMap - + @@ -132,59 +132,75 @@

    Field Summary

    CLIMBER_MOTOR  +static int +COMPRESSOR  + + static double DRIVE_TOLERANCE
    Minumum drive speed.
    - + static int ENCODER_RIGHT_A  - + static int ENCODER_RIGHT_B  - + static int INTAKE_MOTOR  + +static int +INTAKE_PISTON_CHONE  + static int -leftTalonOne  +INTAKE_PISTON_CHTWO  static int -leftTalonThree  +leftTalonOne  static int -leftTalonTwo  +leftTalonThree  static int -rightTalonOne  +leftTalonTwo  static int -rightTalonThree  +rightTalonOne  static int -rightTalonTwo  +rightTalonThree  static int -TURRET_LOWER  +rightTalonTwo  static int -TURRET_RING  +TURRET_LOWER  static int +TURRET_RING  + + +static int TURRET_UPPER  + +static int +UP_MOTOR  +
  • @@ -363,6 +379,19 @@

    INTAKE_MOTOR

  • + + + + @@ -405,7 +434,7 @@

    TURRET_LOWER

    - diff --git a/docs/org/usfirst/frc/team3494/robot/UnitTypes.html b/docs/org/usfirst/frc/team3494/robot/UnitTypes.html index 158fc79..f8e05a2 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/DriveDirections.html b/docs/org/usfirst/frc/team3494/robot/class-use/DriveDirections.html index 4f15dd7..9ed92c7 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 - + 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 859349b..2fdbbbb 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 d9bf9b4..5f26771 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 2821afa..7ee1e45 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 7866eec..9d4960c 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 - + @@ -138,7 +138,7 @@

    Uses of -(package private) UnitTypes +private UnitTypes DistanceDrive.unit  diff --git a/docs/org/usfirst/frc/team3494/robot/commands/auto/AngleTurn.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/AngleTurn.html new file mode 100644 index 0000000..7783050 --- /dev/null +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/AngleTurn.html @@ -0,0 +1,417 @@ + + + + + +AngleTurn + + + + + + + + + + + + +
    +
    org.usfirst.frc.team3494.robot.commands.auto
    +

    Class AngleTurn

    +
    +
    +
      +
    • java.lang.Object
    • +
    • +
        +
      • edu.wpi.first.wpilibj.command.Command
      • +
      • +
          +
        • org.usfirst.frc.team3494.robot.commands.auto.AngleTurn
        • +
        +
      • +
      +
    • +
    +
    +
      +
    • +
      +
      All Implemented Interfaces:
      +
      edu.wpi.first.wpilibj.NamedSendable, edu.wpi.first.wpilibj.Sendable
      +
      +
      +
      +
      public class AngleTurn
      +extends edu.wpi.first.wpilibj.command.Command
      +
      Turns the robot using the gyro board mounted to the RoboRIO. The angle to + turn by must be specified in the constructor.
      +
      +
      Since:
      +
      0.0.2
      +
      See Also:
      +
      Robot, +Drivetrain
      +
      +
    • +
    +
    +
    +
      +
    • + +
        +
      • + + +

        Field Summary

        + + + + + + + + + + + + + + +
        Fields 
        Modifier and TypeField and Description
        private doubleangle 
        private static doubletolerance 
        +
      • +
      + +
        +
      • + + +

        Constructor Summary

        + + + + + + + + +
        Constructors 
        Constructor and Description
        AngleTurn(double angle) 
        +
      • +
      + +
        +
      • + + +

        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

        + + + +
          +
        • +

          angle

          +
          private double angle
          +
        • +
        + + + +
          +
        • +

          tolerance

          +
          private static double tolerance
          +
        • +
        +
      • +
      + +
        +
      • + + +

        Constructor Detail

        + + + +
          +
        • +

          AngleTurn

          +
          public AngleTurn(double angle)
          +
        • +
        +
      • +
      + +
        +
      • + + +

        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/CartesianTurnDrive.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/CartesianTurnDrive.html new file mode 100644 index 0000000..e4792bf --- /dev/null +++ b/docs/org/usfirst/frc/team3494/robot/commands/auto/CartesianTurnDrive.html @@ -0,0 +1,457 @@ + + + + + +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/DistanceDrive.html b/docs/org/usfirst/frc/team3494/robot/commands/auto/DistanceDrive.html index 214aa11..80c6b83 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 - + @@ -49,7 +49,7 @@

    @@ -140,11 +146,11 @@

    Field Summary

    Field and Description -(package private) double +private double dist  -(package private) UnitTypes +private UnitTypes unit  @@ -235,7 +241,7 @@

    Field Detail

    @@ -244,7 +250,7 @@

    dist

    @@ -366,7 +372,7 @@

    interrupted

    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 0f1dd97..b051b88 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 - + @@ -83,6 +83,18 @@

    Package org.usfirst.frc.team3494.robot.co +AngleTurn + +
    Turns the robot using the gyro board mounted to the RoboRIO.
    + + + +CartesianTurnDrive + +
    WIP coordinate drive system.
    + + + DistanceDrive
    Drives a given distance.
    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 c650a59..a2a05ec 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 - + @@ -83,6 +83,8 @@

    Class Hierarchy