diff --git a/.classpath b/.classpath
index 2d44a3f..11f6c5c 100644
--- a/.classpath
+++ b/.classpath
@@ -8,5 +8,6 @@
+
diff --git a/build/jars/CTRE_Phoenix.jar b/build/jars/CTRE_Phoenix.jar
new file mode 100644
index 0000000..0b89cf6
Binary files /dev/null and b/build/jars/CTRE_Phoenix.jar differ
diff --git a/build/jars/WPILib.jar b/build/jars/WPILib.jar
new file mode 100644
index 0000000..7697e83
Binary files /dev/null and b/build/jars/WPILib.jar differ
diff --git a/build/jars/cscore.jar b/build/jars/cscore.jar
new file mode 100644
index 0000000..ff66874
Binary files /dev/null and b/build/jars/cscore.jar differ
diff --git a/build/jars/ntcore.jar b/build/jars/ntcore.jar
new file mode 100644
index 0000000..ac47caa
Binary files /dev/null and b/build/jars/ntcore.jar differ
diff --git a/build/jars/opencv.jar b/build/jars/opencv.jar
new file mode 100644
index 0000000..5ece408
Binary files /dev/null and b/build/jars/opencv.jar differ
diff --git a/build/jars/wpiutil.jar b/build/jars/wpiutil.jar
new file mode 100644
index 0000000..6c92601
Binary files /dev/null and b/build/jars/wpiutil.jar differ
diff --git a/dist/FRCUserProgram.jar b/dist/FRCUserProgram.jar
new file mode 100644
index 0000000..0c0dd36
Binary files /dev/null and b/dist/FRCUserProgram.jar differ
diff --git a/src/org/usfirst/frc/team2264/robot/Robot.java b/src/org/usfirst/frc/team2264/robot/Robot.java
index 9027f3b..266aa0d 100644
--- a/src/org/usfirst/frc/team2264/robot/Robot.java
+++ b/src/org/usfirst/frc/team2264/robot/Robot.java
@@ -1,8 +1,14 @@
package org.usfirst.frc.team2264.robot;
+import javax.swing.JOptionPane;
+
+import com.ctre.phoenix.motorcontrol.ControlMode;
import com.ctre.phoenix.motorcontrol.can.*;
+
+import edu.wpi.first.wpilibj.ADXRS450_Gyro;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.IterativeRobot;
+import edu.wpi.first.wpilibj.interfaces.Gyro;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
@@ -24,11 +30,13 @@ public class Robot extends IterativeRobot {
TalonSRX right;
String autoSelected;
int side;
- String gameData= DriverStation.getInstance().getGameMessage();
+ //String gameData= DriverStation.getInstance().getGameMessage();//commented because we do not have access to gameMessage
+ String gameData = "LRR";//just a random configuration for the field state Purely for testing
long autoStartTime;
long timeInAuto;
SendableChooser chooser = new SendableChooser<>();
autonomous auto;
+ ADXRS450_Gyro Gyro;
/**
* This function is run when the robot is first started up and should be
@@ -43,6 +51,10 @@ public void robotInit() {
chooser.addObject("Drive straight", driveAuto);
chooser.addDefault("no auto", noAuto);
SmartDashboard.putData("Auto choices", chooser);
+ Gyro = new ADXRS450_Gyro();
+ right = new TalonSRX(1);
+ left = new TalonSRX(2);
+ auto = new autonomous();
}
/**
@@ -61,9 +73,10 @@ public void autonomousInit() {
this.autoStartTime = System.currentTimeMillis();
autoSelected = chooser.getSelected();
- // autoSelected = SmartDashboard.getString("Auto Selector",
- // defaultAuto);
+ autoSelected = SmartDashboard.getString("Auto Selector", autoSelected);
System.out.println("Auto selected: " + autoSelected);
+ SmartDashboard.putString("Automode: ", autoSelected);
+ Gyro.reset();
}
/**
@@ -71,30 +84,32 @@ public void autonomousInit() {
*/
@Override
public void autonomousPeriodic() {
+ timeInAuto=System.currentTimeMillis()- autoStartTime;
+ SmartDashboard.putNumber("timeInAuto: ", timeInAuto);
switch (autoSelected) {
case leftAuto:
if(auto.getSwitch(gameData, 0)){
- auto.leftLeft(left, right);
+ auto.leftLeft(left, right, timeInAuto, Gyro);
}
else{
- auto.leftRight(left, right);
+ auto.leftRight(left, right, timeInAuto, Gyro);
}
break;
case rightAuto:
if(auto.getSwitch(gameData, 1)){
- auto.rightRight(left, right);
+ auto.rightRight(left, right, timeInAuto, Gyro);
}
else{
- auto.rightLeft(left,right);
+ auto.rightLeft(left,right, timeInAuto, Gyro);
}
case centerAuto:
//auto.center(left, right);
break;
//case straightSwitch:
- side=1;
+ //side=1;
// auto.sideChoice(left, right, side);
case driveAuto:
- timeInAuto=System.currentTimeMillis()- autoStartTime;
+
auto.crossLineAuto(left, right, timeInAuto);
default:
auto.noAuto(left, right);
@@ -116,4 +131,3 @@ public void teleopPeriodic() {
public void testPeriodic() {
}
}
-
diff --git a/src/org/usfirst/frc/team2264/robot/autonomous.java b/src/org/usfirst/frc/team2264/robot/autonomous.java
index 04f4898..3f269ad 100644
--- a/src/org/usfirst/frc/team2264/robot/autonomous.java
+++ b/src/org/usfirst/frc/team2264/robot/autonomous.java
@@ -7,73 +7,153 @@
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.DriverStation;
+import edu.wpi.first.wpilibj.interfaces.Gyro;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
public class autonomous {
char switchPlacement;
- double motorPer=.6;
+ double motorPer=.2;
int driveTime=4000;
+ final static long sameSideStop1 = 2000, sameSideStop2 = 6000;//determines for how long the robot will drive forward during the leftLeft and rightRight autos
+ final static long oppSideStop1 = 2000, oppSideStop2 = 6000, oppSideStop3 = 10000;//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')){
+ //returns true if the the robot is on the same side as its switch and false if they are on the opposite side or in the middle
+ public boolean getSwitch(String data, int side) {
+ switchPlacement = data.charAt(0);
+ if ((side==0) && (switchPlacement=='L')) {
return true;
}
- else if ((side==1)&&(switchPlacement=='R')){
+ else if ((side==1) && (switchPlacement=='R')) {
return true;
}
- else{
+
+ else {
return false;
}
}
- public void driveForward(TalonSRX left, TalonSRX right){
-
- left.set(ControlMode.PercentOutput, motorPer);
- right.set(ControlMode.PercentOutput,motorPer);
- }
+
+ //causes the robot to move forward in a straight line
+ public void driveForward(TalonSRX left, TalonSRX right) {
+ left.set(ControlMode.PercentOutput, 1 * motorPer);
+ right.set(ControlMode.PercentOutput, -.943 * motorPer);
+ }
- public void turn(TalonSRX left, TalonSRX right,int angle){
- switch(angle){
+ //Causes the the robot to turn at a fixed rate
+ //if angle = 0, the robot will turn right
+ //if angle = 1, the robot will turn left
+ 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
+ left.set(ControlMode.PercentOutput, 1 * motorPer);
+ right.set(ControlMode.PercentOutput, .943 * motorPer);
break;
case 1:
+ //turn left
+ left.set(ControlMode.PercentOutput, -motorPer);
+ right.set(ControlMode.PercentOutput, .943 * motorPer);
+ break;
}
+ }
+
+ //if driver station is on the left and our switch is on the left
+ public void leftLeft(TalonSRX left, TalonSRX right, long time, ADXRS450_Gyro gyro){
+ if(time < sameSideStop1) {
+ driveForward(left, right);
}
-
- //side = driver station placement, 0=left side, 1=right side
- public void leftLeft(TalonSRX left, TalonSRX right){
-
- //if distance travelled<10{
- driveForward(left,right);
- //else{
- turn(left, right, 20);
-
- //drop cube
- }
- public void leftRight(TalonSRX left, TalonSRX right){
- //if driver station is on the left and our switch is on the right
- }
- public void rightRight(TalonSRX left, TalonSRX right){
- //if driver station is on the right and our switch is on the right
- }
- public void rightLeft(TalonSRX left, TalonSRX right){
- //if driver station is on the right and our switch is on the left
- }
-
- 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);
- }
- }
+ else if (time >= sameSideStop1 && gyro.getAngle() < 90) {
+ turn(left, right, 0);
+ }
+ else if (gyro.getAngle() >= 90 && time < sameSideStop2) {
+ driveForward(left, right);
+ }
+ else {
+ left.set(ControlMode.PercentOutput, 0);
+ right.set(ControlMode.PercentOutput, 0);
+ //drop the cube
+ }
+ }
+
+ //if driver station is on the left and our switch is on the right
+ public void leftRight(TalonSRX left, TalonSRX right, long time, ADXRS450_Gyro gyro){
+ 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 {
+ left.set(ControlMode.PercentOutput, 0);
+ right.set(ControlMode.PercentOutput, 0);
+ //drop the cube
+ }
+ }
+
+ //if driver station is on the right and our switch is on the right
+ public void rightRight(TalonSRX left, TalonSRX right, long time, ADXRS450_Gyro gyro){
+ if(time < sameSideStop1) {
+ driveForward(left, right);
+ }
+ else if (time >= sameSideStop1 && gyro.getAngle() > 270) {
+ turn(left, right, 1);
+ }
+ else if (gyro.getAngle() <= 270 && time < sameSideStop2) {
+ driveForward(left, right);
+ }
+ else {
+ left.set(ControlMode.PercentOutput, 0);
+ right.set(ControlMode.PercentOutput, 0);
+ //drop the cube
+ }
+ }
+
+ //if driver station is on the right and our switch is on the left
+ public void rightLeft(TalonSRX left, TalonSRX right, long time, ADXRS450_Gyro gyro){
+ if(time < oppSideStop1) {
+ driveForward(left, right);
+ }
+ else if (time >= oppSideStop1 && gyro.getAngle() > 270) {
+ turn(left, right, 1);
+ }
+ else if (gyro.getAngle() <= 270 && 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 {
+ left.set(ControlMode.PercentOutput, 0);
+ right.set(ControlMode.PercentOutput, 0);
+ //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);
+ }
+ }
}
-
+
\ No newline at end of file