diff --git a/.classpath b/.classpath index 616c997..9d41f0e 100644 --- a/.classpath +++ b/.classpath @@ -2,10 +2,12 @@ - + + - + + diff --git a/.gitignore b/.gitignore index f5cce12..65b47f8 100644 --- a/.gitignore +++ b/.gitignore @@ -1,6 +1,6 @@ *.class -*.properties - -*.xml +build +/bin/ +dist diff --git a/build.properties b/build.properties new file mode 100644 index 0000000..59b2710 --- /dev/null +++ b/build.properties @@ -0,0 +1,4 @@ +# Project specific information +package=org.usfirst.frc.team2264.robot +robot.class=${package}.Robot +simulation.world.file=/usr/share/frcsim/worlds/GearsBotDemo.world \ No newline at end of file diff --git a/build.xml b/build.xml new file mode 100644 index 0000000..76fd29a --- /dev/null +++ b/build.xml @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/org/usfirst/frc/team2264/robot/Autos.java b/src/org/usfirst/frc/team2264/robot/Autos.java new file mode 100644 index 0000000..ec73fe1 --- /dev/null +++ b/src/org/usfirst/frc/team2264/robot/Autos.java @@ -0,0 +1,358 @@ +package org.usfirst.frc.team2264.robot; + +import com.ctre.phoenix.motorcontrol.ControlMode; +import com.ctre.phoenix.motorcontrol.can.TalonSRX; + +import edu.wpi.first.wpilibj.ADXRS450_Gyro; + +//@Authors +/* Drake, Lexi, Rafael, Cameron, Nathan, Julian, Preeti */ + +public class Autos { + + // Auto class that will contain the methods for each auto + + final static long SAME_SIDE_STOP_1 = 2000; + final static long SAME_SIDE_STOP_2 = 6000; + + final static long OPP_SIDE_STOP_1 = 2000; + final static long OPP_SIDE_STOP_2 = 6000; + final static long OPP_SIDE_STOP_3 = 10000; + + final static long CENTER_STOP_1 = 2000; + final static long CENTER_STOP_2 = 6000; + final static long CENTER_STOP_3 = 10000; + + final static int RIGHT = 0; + final static int LEFT = 1; + + double motorPer = .4; + double turnPer = .2; + + +// Starting Left +/* --------------------------- */ + + public void leftLeft(TalonSRX frontL, TalonSRX frontR, TalonSRX backL, TalonSRX backR, ADXRS450_Gyro gyro, long time, + TalonSRX shooterLeft, TalonSRX shooterRight, TalonSRX conveyorLeft, TalonSRX conveyorRight, Shooter shooter, Conveyor conveyor, Pneumatic pneumatics) { + + if(time < SAME_SIDE_STOP_1) { + driveForward(frontL, frontR, backL, backR, gyro, 0); + } + + else if(time >= SAME_SIDE_STOP_1 && gyro.getAngle() > -75) { + turn(frontL, frontR, backL, backR, LEFT); + } + + else if(gyro.getAngle() <= -75 && time < SAME_SIDE_STOP_2) { + driveBackward(frontL, frontR, backL, backR, gyro, -90); + } + else { + stop(frontL, frontR, backL, backR); + shoot(shooterLeft, shooterRight, conveyorLeft, conveyorRight, shooter, conveyor, pneumatics, time); + } + + } + + public void leftRight(TalonSRX frontL, TalonSRX frontR, TalonSRX backL, TalonSRX backR, ADXRS450_Gyro gyro, long time, + TalonSRX shooterLeft, TalonSRX shooterRight, TalonSRX conveyorLeft, TalonSRX conveyorRight, Shooter shooter, Conveyor conveyor, Pneumatic pneumatics) { + + if(time < OPP_SIDE_STOP_1) { + driveForward(frontL, frontR, backL, backR, gyro, 0); + } + + else if(time >= OPP_SIDE_STOP_1 && gyro.getAngle() < 75) { + turn(frontL, frontR, backL, backR, RIGHT); + } + + else if(gyro.getAngle() >= 75 && time < OPP_SIDE_STOP_2) { + driveForward(frontL, frontR, backL, backR, gyro, 90); + } + + else if(time >= OPP_SIDE_STOP_2 && gyro.getAngle() > 0) { + turn(frontL, frontR, backL, backR, LEFT); + } + + else if(gyro.getAngle() <= 0 && time < OPP_SIDE_STOP_3) { + driveBackward(frontL, frontR, backL, backR, gyro, 0); + } + + else { + stop(frontL, frontR, backL, backR); + shoot(shooterLeft, shooterRight, conveyorLeft, conveyorRight, shooter, conveyor, pneumatics, time); + } + } + +// Starting Right +/* --------------------------- */ + + public void rightRight(TalonSRX frontL, TalonSRX frontR, TalonSRX backL, TalonSRX backR, ADXRS450_Gyro gyro, long time, + TalonSRX shooterLeft, TalonSRX shooterRight, TalonSRX conveyorLeft, TalonSRX conveyorRight, Shooter shooter, Conveyor conveyor, Pneumatic pneumatics) { + + if(time < SAME_SIDE_STOP_1) { + driveForward(frontL, frontR, backL, backR, gyro, 0); + } + + else if(time >= SAME_SIDE_STOP_1 && gyro.getAngle() < 75) { + turn(frontL, frontR, backL, backR, RIGHT); + } + + else if(gyro.getAngle() >= 75 && time < SAME_SIDE_STOP_2) { + driveBackward(frontL, frontR, backL, backR, gyro, 90); + } + else { + stop(frontL, frontR, backL, backR); + shoot(shooterLeft, shooterRight, conveyorLeft, conveyorRight, shooter, conveyor, pneumatics, time); + } + + } + + public void rightLeft(TalonSRX frontL, TalonSRX frontR, TalonSRX backL, TalonSRX backR, ADXRS450_Gyro gyro, long time, + TalonSRX shooterLeft, TalonSRX shooterRight, TalonSRX conveyorLeft, TalonSRX conveyorRight, Shooter shooter, Conveyor conveyor, Pneumatic pneumatics) { + + if(time < OPP_SIDE_STOP_1) { + driveForward(frontL, frontR, backL, backR, gyro, 0); + } + + else if(time >= OPP_SIDE_STOP_1 && gyro.getAngle() > -75) { + turn(frontL, frontR, backL, backR, LEFT); + } + + else if(gyro.getAngle() <= -75 && time < OPP_SIDE_STOP_2) { + driveForward(frontL, frontR, backL, backR, gyro, -90); + } + + else if(time >= OPP_SIDE_STOP_2 && gyro.getAngle() < 0) { + turn(frontL, frontR, backL, backR, RIGHT); + } + + else if(gyro.getAngle() >= 0 && time < OPP_SIDE_STOP_3) { + driveBackward(frontL, frontR, backL, backR, gyro, 0); + } + + else { + stop(frontL, frontR, backL, backR); + shoot(shooterLeft, shooterRight, conveyorLeft, conveyorRight, shooter, conveyor, pneumatics, time); + } + + } + +// Center +/* --------------------------- */ + + public void centerLeft(TalonSRX frontL, TalonSRX frontR, TalonSRX backL, TalonSRX backR, ADXRS450_Gyro gyro, long time, + TalonSRX shooterLeft, TalonSRX shooterRight, TalonSRX conveyorLeft, TalonSRX conveyorRight, Shooter shooter, Conveyor conveyor, Pneumatic pneumatics) { + + if (time < CENTER_STOP_1) { + driveForward(frontL, frontR, backL, backR, gyro, 0); + } + + else if(time >= CENTER_STOP_1 && gyro.getAngle() > -75) { + turn(frontL, frontR, backL, backR, LEFT); + } + + else if(gyro.getAngle() <= -75 && time < CENTER_STOP_2) { + driveForward(frontL, frontR, backL, backR, gyro, 0); + } + + else if(time >= CENTER_STOP_2 && gyro.getAngle() > -165) { + turn(frontL, frontR, backL, backR, LEFT); + } + + else if(gyro.getAngle() <= -165 && time < CENTER_STOP_3) { + driveBackward(frontL, frontR, backL, backR, gyro, -165); + } + + else { + stop(frontL, frontR, backL, backR); + shoot(shooterLeft, shooterRight, conveyorLeft, conveyorRight, shooter, conveyor, pneumatics, time); + } + } + + public void centerRight(TalonSRX frontL, TalonSRX frontR, TalonSRX backL, TalonSRX backR, ADXRS450_Gyro gyro, long time, + TalonSRX shooterLeft, TalonSRX shooterRight, TalonSRX conveyorLeft, TalonSRX conveyorRight, Shooter shooter, Conveyor conveyor, Pneumatic pneumatics) { + + if (time < CENTER_STOP_1) { + driveForward(frontL, frontR, backL, backR, gyro, 0); + } + + else if(time >= CENTER_STOP_1 && gyro.getAngle() < 75) { + turn(frontL, frontR, backL, backR, RIGHT); + } + + else if(gyro.getAngle() >= 75 && time < CENTER_STOP_2) { + driveForward(frontL, frontR, backL, backR, gyro, 0); + } + + else if(time >= CENTER_STOP_2 && gyro.getAngle() < 165) { + turn(frontL, frontR, backL, backR, RIGHT); + } + + else if(gyro.getAngle() >= 165 && time < CENTER_STOP_3) { + driveBackward(frontL, frontR, backL, backR, gyro, 180); + } + + else { + stop(frontL, frontR, backL, backR); + shoot(shooterLeft, shooterRight, conveyorLeft, conveyorRight, shooter, conveyor, pneumatics, time); + } + + } + +// Forward/Turn/Back/Stop +/* --------------------------- */ + + public void driveForward(TalonSRX frontL, TalonSRX frontR, TalonSRX backL, TalonSRX backR) { + + // Method to drive forward without using bearings + + frontL.set(ControlMode.PercentOutput, -1 * motorPer); + backL.set(ControlMode.PercentOutput, -1 * motorPer); + + frontR.set(ControlMode.PercentOutput, 1 * motorPer); + backR.set(ControlMode.PercentOutput, 1 * motorPer); + + } + + public void driveForward(TalonSRX frontL, TalonSRX frontR, TalonSRX backL, TalonSRX backR, ADXRS450_Gyro gyro, int bearing) { + + // Method to drive forward using bearings + + if(Math.abs(gyro.getAngle() - bearing) < 2) { + driveForward(frontL, frontR, backL, backR); + } + + else if(gyro.getAngle() < bearing) { + frontL.set(ControlMode.PercentOutput, -1 * motorPer); + backL.set(ControlMode.PercentOutput, -1 * motorPer); + + frontR.set(ControlMode.PercentOutput, .9 * motorPer); + backR.set(ControlMode.PercentOutput, .9 * motorPer); + } + + else if (gyro.getAngle() > bearing) { + frontL.set(ControlMode.PercentOutput, -.9 * motorPer); + backL.set(ControlMode.PercentOutput, -.9 * motorPer); + + frontR.set(ControlMode.PercentOutput, 1 * motorPer); + backR.set(ControlMode.PercentOutput, 1 * motorPer); + } + } + + public void turn(TalonSRX frontL, TalonSRX frontR, TalonSRX backL, TalonSRX backR, int angle) { + + // Method to turn using angles + + switch(angle) { + + // Turns Right + case 0: + + frontL.set(ControlMode.PercentOutput, -1 * turnPer); + backL.set(ControlMode.PercentOutput, -1 * turnPer); + + frontR.set(ControlMode.PercentOutput, -1 * turnPer); + backR.set(ControlMode.PercentOutput, -1 * turnPer); + break; + + // Turn Left + case 1: + + frontL.set(ControlMode.PercentOutput, 1 * turnPer); + backL.set(ControlMode.PercentOutput, 1 * turnPer); + + frontR.set(ControlMode.PercentOutput, 1 * turnPer); + backR.set(ControlMode.PercentOutput, 1 * turnPer); + break; + + default: + stop(frontL, frontR, backL, backR); + } + + } + + public void driveBackward(TalonSRX frontL, TalonSRX frontR, TalonSRX backL, TalonSRX backR) { + + frontL.set(ControlMode.PercentOutput, 1 * turnPer); + backL.set(ControlMode.PercentOutput, 1 * turnPer); + + frontR.set(ControlMode.PercentOutput, -1 * turnPer); + backR.set(ControlMode.PercentOutput, -1 * turnPer); + } + + public void driveBackward(TalonSRX frontL, TalonSRX frontR, TalonSRX backL, TalonSRX backR, ADXRS450_Gyro gyro, int bearing) { + + if (Math.abs(gyro.getAngle() - bearing) < 2) { + driveBackward(frontL, frontR, backL, backR); + } + + else if (gyro.getAngle() - bearing > 0) { + frontL.set(ControlMode.PercentOutput, 1 * turnPer); + backL.set(ControlMode.PercentOutput, 1 * turnPer); + + frontR.set(ControlMode.PercentOutput, -.9 * turnPer); + backR.set(ControlMode.PercentOutput, -.9 * turnPer); + } + + else if (gyro.getAngle() - bearing < 0) { + frontL.set(ControlMode.PercentOutput, .9 * turnPer); + backL.set(ControlMode.PercentOutput, .9 * turnPer); + + frontR.set(ControlMode.PercentOutput, -1 * turnPer); + backR.set(ControlMode.PercentOutput, -1 * turnPer); + } + } + + public void stop(TalonSRX frontL, TalonSRX frontR, TalonSRX backL, TalonSRX backR) { + + // Method to stop the robot in autonomous + + frontL.set(ControlMode.PercentOutput, 0); + backL.set(ControlMode.PercentOutput, 0); + + frontR.set(ControlMode.PercentOutput, 0); + backR.set(ControlMode.PercentOutput, 0); + } + +// Shoot +/* -------------------------- */ + + public void shoot(TalonSRX shooterLeft, TalonSRX shooterRight, TalonSRX conveyorLeft, TalonSRX conveyorRight, Shooter shooter, Conveyor conveyor, Pneumatic pneumatics, long time){ + + // Fires the box onto the switch + if(time < 2500){ + shooter.startShooter(shooterLeft, shooterRight, Variables.switchShooterSpeed); + pneumatics.lowerShooter(); + } + + else if(time >= 2500 && time < 3500){ + conveyor.startConveyor(conveyorLeft, conveyorRight); + } + + else { + shooter.stopShooter(shooterLeft, conveyorRight); + conveyor.stopConveyor(conveyorLeft, conveyorRight); + } + } + + +// Switch +/* -------------------------- */ + + public boolean getSwitch(String data, int side) { + + // Getting the side of the switches on the field + + char switchPlacement = data.charAt(0); + + if(side == 0 && switchPlacement == 'L'){ + return true; + } + + else if (side == 1 && switchPlacement == 'R') { + return true; + } + + return false; + } +} \ No newline at end of file diff --git a/src/org/usfirst/frc/team2264/robot/Conveyor.java b/src/org/usfirst/frc/team2264/robot/Conveyor.java new file mode 100644 index 0000000..de4f523 --- /dev/null +++ b/src/org/usfirst/frc/team2264/robot/Conveyor.java @@ -0,0 +1,20 @@ +//@author Cameron McCoy + +package org.usfirst.frc.team2264.robot; + +import com.ctre.phoenix.motorcontrol.ControlMode; +import com.ctre.phoenix.motorcontrol.can.TalonSRX; + +public class Conveyor { + + public void startConveyor(TalonSRX left, TalonSRX right) { + left.set(ControlMode.PercentOutput, Variables.conveyorSpeed); + right.set(ControlMode.PercentOutput, Variables.conveyorSpeed); + } + + public void stopConveyor(TalonSRX left, TalonSRX right) { + left.set(ControlMode.PercentOutput, 0); + right.set(ControlMode.PercentOutput, 0); + } + +} diff --git a/src/org/usfirst/frc/team2264/robot/DriveTrain.java b/src/org/usfirst/frc/team2264/robot/DriveTrain.java new file mode 100644 index 0000000..205f30c --- /dev/null +++ b/src/org/usfirst/frc/team2264/robot/DriveTrain.java @@ -0,0 +1,81 @@ +package org.usfirst.frc.team2264.robot; + +import com.ctre.phoenix.motorcontrol.ControlMode; +import com.ctre.phoenix.motorcontrol.can.TalonSRX; +import edu.wpi.first.wpilibj.Joystick; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import edu.wpi.first.wpilibj.GenericHID; + +//@Authors +/* Drake, Lexi, Rafael, Cameron, Nathan, Julian, Preeti */ + +public class DriveTrain { + + // Drive-train class that will contain methods reading the joysticks and setting the motors + + //Sets motors for robot with four-motor drive train + public static void MotorSet(Joystick leftJ, Joystick rightJ, + TalonSRX frontL, TalonSRX frontR, TalonSRX backL, TalonSRX backR) { + + // Method to set the motors to the joystick readings + + frontL.set(ControlMode.PercentOutput, -0.4 * sensitivityAdjustment(getLeft(leftJ))); + backL.set(ControlMode.PercentOutput, -0.4 * sensitivityAdjustment(getLeft(leftJ))); + + frontR.set(ControlMode.PercentOutput, 0.4 * sensitivityAdjustment(getRight(rightJ))); + backR.set(ControlMode.PercentOutput, 0.4 * sensitivityAdjustment(getLeft(rightJ))); + + } + + //Sets motors for robot with two-motor drive train + public static void MotorSetTwo(Joystick leftJ, Joystick rightJ, TalonSRX backL, TalonSRX backR) { + + // Method to set the motors to the joystick readings + + + backL.set(ControlMode.PercentOutput, -0.4 * sensitivityAdjustment(getLeft(leftJ))); + backR.set(ControlMode.PercentOutput, 0.4 * sensitivityAdjustment(getLeft(rightJ))); + + } + + //Gets reading from left joystick + public static double getLeft(Joystick leftJ) { + + // Method to get the left joystick reading + + SmartDashboard.putNumber("LeftJoystick", leftJ.getY(GenericHID.Hand.kLeft)); + return leftJ.getY(GenericHID.Hand.kLeft); + + } + + //Gets reading from right joystick + public static double getRight(Joystick rightJ) { + + // Method to get the right joystick reading + + SmartDashboard.putNumber("RightJoystick", rightJ.getY(GenericHID.Hand.kRight)); + return rightJ.getY(GenericHID.Hand.kRight); + + } + + + //Makes the joystick outputs/motor inputs exponential + public static double sensitivityAdjustment(double position) { + + // Method to adjust the motor speeds + + double adjustment = Math.pow(position, 2); + + if (position >= 0){ //if position is positive + + return adjustment; + } + else { + + return -1 * adjustment; + } + + + } + +} diff --git a/src/org/usfirst/frc/team2264/robot/Elevator.java b/src/org/usfirst/frc/team2264/robot/Elevator.java new file mode 100644 index 0000000..2ba797b --- /dev/null +++ b/src/org/usfirst/frc/team2264/robot/Elevator.java @@ -0,0 +1,20 @@ +package org.usfirst.frc.team2264.robot; + +import com.ctre.phoenix.motorcontrol.ControlMode; +import com.ctre.phoenix.motorcontrol.can.TalonSRX; + +import edu.wpi.first.wpilibj.DoubleSolenoid; + +public class Elevator { +//raises the shooter to 2 levels + public void upElevator(DoubleSolenoid solenoid){ + solenoid.set(DoubleSolenoid.Value.kForward); + } + + public void downElevator(DoubleSolenoid solenoid){ + solenoid.set(DoubleSolenoid.Value.kReverse); + } + public void stopElevtor(DoubleSolenoid solenoid) { + solenoid.set(DoubleSolenoid.Value.kOff); + } + } diff --git a/src/org/usfirst/frc/team2264/robot/ElevatorGyro.java b/src/org/usfirst/frc/team2264/robot/ElevatorGyro.java new file mode 100644 index 0000000..c2f8a13 --- /dev/null +++ b/src/org/usfirst/frc/team2264/robot/ElevatorGyro.java @@ -0,0 +1,34 @@ +package org.usfirst.frc.team2264.robot; + +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; + +import java.awt.Color; + +import edu.wpi.first.wpilibj.ADXRS450_Gyro; + +public class ElevatorGyro { + + ADXRS450_Gyro ElevatorGyro = new ADXRS450_Gyro(); + double switchAngle = 45.0; + double scaleAngle = 80.0; //Adjust these numbers accordingly + + + public ElevatorGyro() { + ElevatorGyro.calibrate(); + SmartDashboard.putNumber("getAngle", ElevatorGyro.getAngle()); + + } + + /*public int position(double angle) { + if (angle == switchAngle) { + return 0; //If the shooter is at the switch position, it returns a 0 and shows blue on the smart dashboard + //SmartDashboard.putData("Switch", Color.blue); + } + + else if (angle == scaleAngle) { + return 1; //If the shooter is at the scale position, it returns a 1 and shows green on the smart dashboard + //SmartDashboard.putData("Scale", Color.green); + } + } + */ +} diff --git a/src/org/usfirst/frc/team2264/robot/Intake.java b/src/org/usfirst/frc/team2264/robot/Intake.java new file mode 100644 index 0000000..3710561 --- /dev/null +++ b/src/org/usfirst/frc/team2264/robot/Intake.java @@ -0,0 +1,34 @@ +//@author Cameron McCoy + +package org.usfirst.frc.team2264.robot; + +import com.ctre.phoenix.motorcontrol.ControlMode; +import com.ctre.phoenix.motorcontrol.can.TalonSRX; + +public class Intake { + //intake of the rectangular prism for floor pickup + + //Pulls the box inwards + public void doubleIntake(TalonSRX left, TalonSRX right) { + left.set(ControlMode.PercentOutput, Variables.intakeSpeed); + right.set(ControlMode.PercentOutput, Variables.intakeSpeed); + } + + //Stops the intake motors + public void stop(TalonSRX left, TalonSRX right) { + left.set(ControlMode.PercentOutput, 0); + right.set(ControlMode.PercentOutput, 0); + } + + //Pushes the box outwards + public void doubleOutput(TalonSRX left, TalonSRX right) { + left.set(ControlMode.PercentOutput, -Variables.intakeSpeed); + right.set(ControlMode.PercentOutput, -Variables.intakeSpeed); + } + + //Turns the box + public void turn(TalonSRX left, TalonSRX right) { + left.set(ControlMode.PercentOutput, Variables.intakeSpeed); + right.set(ControlMode.PercentOutput, -Variables.intakeSpeed); } + +} diff --git a/src/org/usfirst/frc/team2264/robot/Pneumatic.java b/src/org/usfirst/frc/team2264/robot/Pneumatic.java new file mode 100644 index 0000000..967c2d2 --- /dev/null +++ b/src/org/usfirst/frc/team2264/robot/Pneumatic.java @@ -0,0 +1,42 @@ +package org.usfirst.frc.team2264.robot; + +import edu.wpi.first.wpilibj.Compressor; +import edu.wpi.first.wpilibj.DoubleSolenoid; + +public class Pneumatic { + Compressor compressor; //Air compressor + DoubleSolenoid shooterSolenoid; // Solenoid for the shooter + DoubleSolenoid leftArmSolenoid; // Solenoid for left intake arm + DoubleSolenoid rightArmSolenoid;// Solenoid for right intake arm + + public Pneumatic() { + compressor = new Compressor(1); + shooterSolenoid = new DoubleSolenoid(1, 0, 1); + leftArmSolenoid = new DoubleSolenoid(1, 4, 5); + rightArmSolenoid = new DoubleSolenoid(1, 6, 7); + + compressor.setClosedLoopControl(true); + } + + // raises the shooter + public void raiseShooter() { + shooterSolenoid.set(DoubleSolenoid.Value.kForward); + } + + // Lowers the shooter + public void lowerShooter() { + shooterSolenoid.set(DoubleSolenoid.Value.kReverse); + } + + // Opens the intake arms outwards + public void extendArms() { + leftArmSolenoid.set(DoubleSolenoid.Value.kForward); + rightArmSolenoid.set(DoubleSolenoid.Value.kForward); + } + + // Pulls the intake arms in + public void retractArms() { + leftArmSolenoid.set(DoubleSolenoid.Value.kReverse); + rightArmSolenoid.set(DoubleSolenoid.Value.kReverse); + } +} diff --git a/src/org/usfirst/frc/team2264/robot/Robot.java b/src/org/usfirst/frc/team2264/robot/Robot.java index 7456cb0..4aff4b0 100644 --- a/src/org/usfirst/frc/team2264/robot/Robot.java +++ b/src/org/usfirst/frc/team2264/robot/Robot.java @@ -1,66 +1,246 @@ package org.usfirst.frc.team2264.robot; +import com.ctre.phoenix.motorcontrol.can.TalonSRX; +import java.awt.Color; + +import com.ctre.phoenix.motorcontrol.ControlMode; +import com.ctre.phoenix.motorcontrol.can.TalonSRX; + +import edu.wpi.first.wpilibj.ADXRS450_Gyro; +import edu.wpi.first.wpilibj.CameraServer; +import edu.wpi.first.wpilibj.Compressor; +import edu.wpi.first.wpilibj.DoubleSolenoid; +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj.GenericHID; import edu.wpi.first.wpilibj.IterativeRobot; +import edu.wpi.first.wpilibj.Joystick; +import edu.wpi.first.wpilibj.Sendable; +import edu.wpi.first.wpilibj.Solenoid; +import edu.wpi.first.wpilibj.SolenoidBase; +import edu.wpi.first.wpilibj.XboxController; +import edu.wpi.first.wpilibj.hal.SolenoidJNI; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -/** - * The VM 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. - */ + +// @Authors +/* Drake, Lexi, Rafael, Cameron, Nathan, Julian, Preeti */ + public class Robot extends IterativeRobot { - final String defaultAuto = "Default"; - final String customAuto = "My Auto"; + +// Main class that will use other classes and call methods to run the robot + + //autonomous+ smart dashboard + final String driveAuto = "drive straight"; + final String centerAuto = "Center Auto"; + final String leftAuto= "Left Auto"; + final String rightAuto= "Right Auto"; + final String noAuto= "no Auto"; + String autoSelected; + String gameData= DriverStation.getInstance().getGameSpecificMessage(); + + long autoStartTime; + long timeInAuto; + SendableChooser chooser = new SendableChooser<>(); - - /** - * This function is run when the robot is first started up and should be - * used for any initialization code. - */ - @Override + Autos auto; + double shootingSpeed; + + //Joysticks + Joystick leftJ; + Joystick rightJ; + XboxController controller; + + //Motors/Talons + TalonSRX frontLeft; + TalonSRX frontRight; + TalonSRX backLeft; + TalonSRX backRight; + TalonSRX intakeLeft; + TalonSRX intakeRight; + TalonSRX conveyorLeft; + TalonSRX conveyorRight; + TalonSRX shooterLeft; + TalonSRX shooterRight; + TalonSRX liftMotor; + + //CameraServer + CameraServer camera = CameraServer.getInstance(); + + //Gyro + ADXRS450_Gyro Gyro; + double gyroInitial; + double gyroTrack; + boolean gyroPluggedIn; + + Shooter shooter; + Intake intake; + Conveyor conveyor; + Pneumatic pneumatics; + + public void robotInit() { - chooser.addDefault("Default Auto", defaultAuto); - chooser.addObject("My Auto", customAuto); + + // Method that will run only one time in Teleop + //smart dashboard + + chooser.addObject("Center Auto", centerAuto); + chooser.addObject("Left Auto", leftAuto); + chooser.addObject("Right Auto", rightAuto); + chooser.addObject("Drive straight", driveAuto); + chooser.addDefault("no auto", noAuto); SmartDashboard.putData("Auto choices", chooser); - } + + // Motors + frontLeft = new TalonSRX(Variables.frontLN); + frontRight = new TalonSRX(Variables.frontRN); + backLeft = new TalonSRX(Variables.backLN); + backRight = new TalonSRX(Variables.backRN); + liftMotor = new TalonSRX(Variables.liftElevator); + shooterLeft = new TalonSRX(Variables.shooterLeft); + shooterRight = new TalonSRX(Variables.shooterRight); + conveyorLeft = new TalonSRX(Variables.conveyorLeft); + conveyorRight = new TalonSRX(Variables.conveyorRight); + + // Joysticks + leftJ = new Joystick(Variables.leftStickPort); + rightJ = new Joystick(Variables.rightStickPort); + controller = new XboxController(Variables.controllerPort); + + shooter = new Shooter(); + intake = new Intake(); + conveyor = new Conveyor(); + pneumatics = new Pneumatic(); + + // Gyro + Gyro = new ADXRS450_Gyro(); + + //Solenoid testSol = new Solenoid(1); + //testSol.set(on); + /* + int readVal = solenoid.getAll(); + SmartDashboard.putNumber("getAll", readVal); + readVal = solenoid.getPCMSolenoidBlackList(); + SmartDashboard.putNumber("getPCM", readVal); + boolean boolVal = solenoid.getPCMSolenoidVoltageFault(); + SmartDashboard.putBoolean("getPCMSolenoidVoltageFault", boolVal); + boolVal = solenoid.getPCMSolenoidVoltageStickyFault(); + SmartDashboard.putBoolean("getPCMSolenoidVoltageStickyFault", boolVal); + */ + //Start the camera server + camera.startAutomaticCapture(); + - /** - * This autonomous (along with the chooser code above) shows how to select - * between different autonomous modes using the dashboard. The sendable - * chooser code works with the Java SmartDashboard. If you prefer the - * LabVIEW Dashboard, remove all of the chooser code and uncomment the - * getString line to get the auto name from the text box below the Gyro - * - * You can add additional auto modes by adding additional comparisons to the - * switch structure below with additional strings. If using the - * SendableChooser make sure to add them to the chooser code above as well. - */ - @Override + } + public void autonomousInit() { + + // Method that will run only one time in autonomous + Gyro.calibrate(); + gyroPluggedIn = Util.gyroCheck(Gyro); + this.autoStartTime = System.currentTimeMillis(); autoSelected = chooser.getSelected(); - // autoSelected = SmartDashboard.getString("Auto Selector", - // defaultAuto); System.out.println("Auto selected: " + autoSelected); } + + @Override + public void autonomousPeriodic() { + + /** * This function is called periodically during autonomous */ - @Override - public void autonomousPeriodic() { + + timeInAuto=System.currentTimeMillis()- autoStartTime; switch (autoSelected) { - case customAuto: - // Put custom auto code here + case leftAuto: + if(auto.getSwitch(gameData, 0)){ + auto.leftLeft(frontLeft,frontRight, backLeft, backRight, Gyro, timeInAuto, shooterLeft, shooterRight, conveyorLeft, conveyorRight, shooter, conveyor, pneumatics); + } + else{ + auto.leftRight(frontLeft,frontRight, backLeft, backRight, Gyro, timeInAuto, shooterLeft, shooterRight, conveyorLeft, conveyorRight, shooter, conveyor, pneumatics); + } + break; + case rightAuto: + if(auto.getSwitch(gameData, 1)){ + auto.rightRight(frontLeft,frontRight, backLeft, backRight, Gyro, timeInAuto, shooterLeft, shooterRight, conveyorLeft, conveyorRight, shooter, conveyor, pneumatics); + } + else{ + auto.rightLeft(frontLeft,frontRight, backLeft, backRight, Gyro, timeInAuto, shooterLeft, shooterRight, conveyorLeft, conveyorRight, shooter, conveyor, pneumatics); + } + case centerAuto: + if(auto.getSwitch(gameData, 0)){ + auto.centerLeft(frontLeft, frontRight, backLeft, backRight, Gyro, timeInAuto, shooterLeft, shooterRight, conveyorLeft, conveyorRight, shooter, conveyor, pneumatics); + } + else{ + auto.centerRight(frontLeft, frontRight, backLeft, backRight, Gyro, timeInAuto, shooterLeft, shooterRight, conveyorLeft, conveyorRight, shooter, conveyor, pneumatics); + } break; - case defaultAuto: default: - // Put default auto code here + auto.stop(frontLeft,frontRight, backLeft, backRight); break; } + + } + + void checkButtons() { + //shooter controls + if(controller.getBumperPressed(GenericHID.Hand.kLeft)) + { + shooter.startShooter(shooterLeft, shooterRight,shootingSpeed); + } + + //intake control + if(controller.getBumperPressed(GenericHID.Hand.kRight)) { + conveyor.startConveyor(conveyorLeft, conveyorRight); + } + if(controller.getAButton()) { + pneumatics.extendArms(); + } + if(controller.getYButton()) { + pneumatics.retractArms(); + } + if(controller.getBackButton()) { + shootingSpeed=Variables.switchShooterSpeed; + } + if(controller.getStartButton()) { + shootingSpeed=Variables.scaleShooterSpeed; + } + } + + void checkIntakeControls() { + if(leftJ.getRawButton(3)) { + intake.doubleIntake(intakeLeft, intakeRight); + } + if(leftJ.getRawButton(2)) { + intake.doubleOutput(intakeLeft, intakeRight); + } + if(rightJ.getRawButton(3)) { + intake.turn(intakeLeft, intakeRight); + } + if(rightJ.getRawButton(2)) { + intake.stop(intakeLeft, intakeRight); + } + } + + void elevatorControls() { + if (controller.getTriggerAxis(GenericHID.Hand.kLeft)>.1) { + pneumatics.raiseShooter(); + } + else if (controller.getTriggerAxis(GenericHID.Hand.kRight)>.1) { + pneumatics.lowerShooter(); + } + } + + void checkPressure() { + if(pneumatics.compressor.getPressureSwitchValue()) { + // SmartDashboard.putData("Air Tank Full", (Sendable) Color.GREEN); + } + else { + //SmartDashboard.putData("Air Tank Full", (Sendable) Color.red); + } } /** @@ -68,6 +248,19 @@ public void autonomousPeriodic() { */ @Override public void teleopPeriodic() { + // Method that will be constantly called during Teleop + checkButtons(); + elevatorControls(); + checkPressure(); + SmartDashboard.putNumber("Gyro Value: ", Gyro.getAngle()); + + if(Variables.whichRobot == RobotChoice.MARS) { + DriveTrain.MotorSet(leftJ, rightJ, frontLeft, frontRight, backLeft, backRight); + } + + else { + DriveTrain.MotorSetTwo(leftJ, rightJ, backLeft, backRight); + } } /** @@ -75,6 +268,7 @@ public void teleopPeriodic() { */ @Override public void testPeriodic() { + } -} +} \ No newline at end of file diff --git a/src/org/usfirst/frc/team2264/robot/RobotChoice.java b/src/org/usfirst/frc/team2264/robot/RobotChoice.java new file mode 100644 index 0000000..e16339a --- /dev/null +++ b/src/org/usfirst/frc/team2264/robot/RobotChoice.java @@ -0,0 +1,10 @@ +//@author Kathleen + +package org.usfirst.frc.team2264.robot; +// Enumeration hell f*cking yeah +public enum RobotChoice { + + VERONICA, + BOB, + MARS; +} diff --git a/src/org/usfirst/frc/team2264/robot/Shooter.java b/src/org/usfirst/frc/team2264/robot/Shooter.java new file mode 100644 index 0000000..aed6989 --- /dev/null +++ b/src/org/usfirst/frc/team2264/robot/Shooter.java @@ -0,0 +1,21 @@ +//@author Cameron McCoy + +package org.usfirst.frc.team2264.robot; + +import com.ctre.phoenix.motorcontrol.ControlMode; +import com.ctre.phoenix.motorcontrol.can.TalonSRX; + +public class Shooter { + //wheels that shoot the cube out + + public void startShooter(TalonSRX left, TalonSRX right, double speed) { + left.set(ControlMode.PercentOutput, speed); + right.set(ControlMode.PercentOutput, speed); + } + + public void stopShooter(TalonSRX left, TalonSRX right) { + left.set(ControlMode.PercentOutput, 0); + right.set(ControlMode.PercentOutput, 0); + } + +} \ No newline at end of file diff --git a/src/org/usfirst/frc/team2264/robot/Util.java b/src/org/usfirst/frc/team2264/robot/Util.java new file mode 100644 index 0000000..b542982 --- /dev/null +++ b/src/org/usfirst/frc/team2264/robot/Util.java @@ -0,0 +1,49 @@ +package org.usfirst.frc.team2264.robot; + +import edu.wpi.first.wpilibj.ADXRS450_Gyro; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; + +//@Authors +/* Drake, Lexi, Rafael, Cameron, Nathan, Julian, Preeti */ + +public class Util { + + // Util class that will contain the sensors or other smaller methods + + // Checks if the gyro sensor is plugged in + static boolean gyroCheck(ADXRS450_Gyro Gyro) { + + // Debugger for gyro + + double gyroInitial = Gyro.getAngle(); + double gyroTrack = 0; + + for(int i = 0; i < 5; i++) { + + gyroTrack = gyroTrack + Gyro.getAngle(); + + } + + if(gyroTrack == (5 * gyroInitial)){ + + SmartDashboard.putString("Gyro is:", "NOT plugged in"); + return false; + + } + else { + + SmartDashboard.putString("Gyro is:", "plugged in"); + return true; + + } + + } + + public static double encoderReading() { + + // Method to get the readings off the encoder + + return 0; + } + +} diff --git a/src/org/usfirst/frc/team2264/robot/Variables.java b/src/org/usfirst/frc/team2264/robot/Variables.java new file mode 100644 index 0000000..1538c3b --- /dev/null +++ b/src/org/usfirst/frc/team2264/robot/Variables.java @@ -0,0 +1,58 @@ +package org.usfirst.frc.team2264.robot; + +//@Authors +/* Drake, Lexi, Rafael, Cameron, Nathan, Julian, Preeti */ + +public class Variables { + public static RobotChoice whichRobot = RobotChoice.BOB; + // Variables class to change numbers and use them throughout the code + + // Motors + + public static final int frontLN = 4; + public static final int frontRN = 3; + public static int backLN = 6; + public static int backRN = 5; + public static final int shooterLeft = 5; + public static final int shooterRight = 6; + public static final int conveyorLeft = 4; + public static final int conveyorRight = 3; + + public static final double intakeSpeed = -.5; ///SET THIS NUMBER/// + public static final double conveyorSpeed = .5; //SET THIS NUMBER/// + public static final double switchShooterSpeed = .5;//SET THIS NUMBER/// + public static final double scaleShooterSpeed = .9;//SET THIS NUMBER/// + + + public static final int liftElevator = 7; //change this + public static final double elevateSpeed = 1; + + + + + // Joysticks + public static final int rightStickPort = 0; + public static final int leftStickPort = 1; + + //Gamepad + public static final int controllerPort = 3; ///SET THIS NUMBER/// + // 2 shooting + // 2 moving + // 2 grabbing + + public Variables() { + if(whichRobot == RobotChoice.MARS) { + backLN = 6; + backRN = 5; + } + else if(whichRobot == RobotChoice.VERONICA) { + backLN = 1; + backRN = 2; + } + else { + backLN = 25; + backRN = 26; + } + } + +} diff --git a/src/org/usfirst/frc/team2264/robot/autonomous.java b/src/org/usfirst/frc/team2264/robot/autonomous.java new file mode 100644 index 0000000..d3a9d8a --- /dev/null +++ b/src/org/usfirst/frc/team2264/robot/autonomous.java @@ -0,0 +1,141 @@ +package org.usfirst.frc.team2264.robot; + + + +/* +* @author RafaelDubeau +* @author DrakeJohnson +* @author Preeti Pidatala +* */ +import com.ctre.phoenix.motorcontrol.ControlMode; +import com.ctre.phoenix.motorcontrol.can.TalonSRX; + +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj.interfaces.Gyro; + +public class autonomous { + char switchPlacement; + double motorPer=.6; + int driveTime=4000; + final static int sameSideStop1 = 2000, sameSideStop2 = 4000;//determines for how long the robot will drive forward during the leftLeft and rightRight autos + final static int oppSideStop1 = 2000, oppSideStop2 = 4000, oppSideStop3 = 6000;//determines for how long the robot will drive forward during the leftRight and rightLeft autos + + public boolean getSwitch(String data, int side){ + switchPlacement=data.charAt(0); + if ((side==0)&&(switchPlacement=='L')){ + return true; + } + else if ((side==1)&&(switchPlacement=='R')){ + return true; + } + else{ + return false; + } + } + public void driveForward(TalonSRX left, TalonSRX right){ + + left.set(ControlMode.PercentOutput, motorPer); + right.set(ControlMode.PercentOutput,motorPer); + } + + public void turn(TalonSRX left, TalonSRX right,int angle){ + switch(angle){ + case 0: + left.set(ControlMode.PercentOutput, motorPer); + right.set(ControlMode.PercentOutput,-1*motorPer); + + //turn right + break; + case 1: + } + } + + //side = driver station placement, 0=left side, 1=right side + public void leftLeft(TalonSRX left, TalonSRX right, long time, Gyro gyro){ + //if driver station is on the left and our switch is on the left + if(time < sameSideStop1) { + driveForward(left, right); + } + else if (time >= sameSideStop1 && gyro.getAngle() < 90) { + turn(left, right, 0); + } + else if (gyro.getAngle() >= 90 && time < sameSideStop2) { + driveForward(left, right); + } + else { + //drop the cube + } + } + + public void leftRight(TalonSRX left, TalonSRX right, long time, Gyro gyro){ + //if driver station is on the left and our switch is on the right + if(time < oppSideStop1) { + driveForward(left, right); + } + else if (time >= oppSideStop1 && gyro.getAngle() < 90) { + turn(left, right, 0); + } + else if (gyro.getAngle() >= 90 && time < oppSideStop2) { + driveForward(left, right); + } + else if (time >= oppSideStop2 && gyro.getAngle() < 180) { + turn(left, right, 0); + } + else if (gyro.getAngle() >= 180 && time < oppSideStop3) { + driveForward(left, right); + } + else { + //drop the cube + } + } + public void rightRight(TalonSRX left, TalonSRX right, long time, Gyro gyro){ + //if driver station is on the right and our switch is on the right + if(time < sameSideStop1) { + driveForward(left, right); + } + else if (time >= sameSideStop1 && gyro.getAngle() < 90) { + turn(left, right, 1); + } + else if (gyro.getAngle() >= 90 && time < sameSideStop2) { + driveForward(left, right); + } + else { + //drop the cube + } + } + public void rightLeft(TalonSRX left, TalonSRX right, long time, Gyro gyro){ + //if driver station is on the right and our switch is on the left + if(time < oppSideStop1) { + driveForward(left, right); + } + else if (time >= oppSideStop1 && gyro.getAngle() < 90) { + turn(left, right, 1); + } + else if (gyro.getAngle() >= 90 && time < oppSideStop2) { + driveForward(left, right); + } + else if (time >= oppSideStop2 && gyro.getAngle() < 180) { + turn(left, right, 1); + } + else if (gyro.getAngle() >= 180 && time < oppSideStop3) { + driveForward(left, right); + } + else { + //drop the cube + } + } + + public void noAuto(TalonSRX left, TalonSRX right){ + left.set(ControlMode.PercentOutput,0); + right.set(ControlMode.PercentOutput,0); + } + + public void crossLineAuto(TalonSRX left,TalonSRX right, long time){ + if(time<=driveTime){ + left.set(ControlMode.PercentOutput,0); + right.set(ControlMode.PercentOutput,0); + } + } + +} + diff --git a/src/org/usfirst/frc/team2264/robot/utilities.java b/src/org/usfirst/frc/team2264/robot/utilities.java new file mode 100644 index 0000000..9d59cae --- /dev/null +++ b/src/org/usfirst/frc/team2264/robot/utilities.java @@ -0,0 +1,25 @@ +package org.usfirst.frc.team2264.robot; + +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; + +public class utilities { + + public static double angleDifference(double currentAngle, double goalAngle){ + + double rawDiff= (goalAngle-currentAngle)%360; + System.out.println(rawDiff); + SmartDashboard.putNumber("Gyro- Raw difference", rawDiff+360); + if ((rawDiff)<=-180){ + return rawDiff+360; + } + else if(rawDiff>=180){ + SmartDashboard.putNumber("Gyro- Raw different", rawDiff-360); + return rawDiff-360; + } + else{ + SmartDashboard.putNumber("Gyro- Raw different", rawDiff); + return (rawDiff); + } + + } +}