Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions .classpath
Original file line number Diff line number Diff line change
Expand Up @@ -8,5 +8,6 @@
<classpathentry kind="con" path="org.eclipse.jdt.launching.JRE_CONTAINER/org.eclipse.jdt.internal.debug.ui.launcher.StandardVMType/JavaSE-1.8"/>
<classpathentry kind="var" path="USERLIBS_DIR/CTRE_Phoenix-sources.jar"/>
<classpathentry kind="var" path="USERLIBS_DIR/CTRE_Phoenix.jar" sourcepath="/CTRE_Phoenix.sources"/>
<classpathentry kind="var" path="wpiutil" sourcepath="wpiutil.sources"/>
<classpathentry kind="output" path="bin"/>
</classpath>
Binary file added build/jars/CTRE_Phoenix.jar
Binary file not shown.
Binary file added build/jars/WPILib.jar
Binary file not shown.
Binary file added build/jars/cscore.jar
Binary file not shown.
Binary file added build/jars/ntcore.jar
Binary file not shown.
Binary file added build/jars/opencv.jar
Binary file not shown.
Binary file added build/jars/wpiutil.jar
Binary file not shown.
Binary file added dist/FRCUserProgram.jar
Binary file not shown.
34 changes: 24 additions & 10 deletions src/org/usfirst/frc/team2264/robot/Robot.java
Original file line number Diff line number Diff line change
@@ -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;

Expand All @@ -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<String> chooser = new SendableChooser<>();
autonomous auto;
ADXRS450_Gyro Gyro;

/**
* This function is run when the robot is first started up and should be
Expand All @@ -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();
}

/**
Expand All @@ -61,40 +73,43 @@ 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();
}

/**
* This function is called periodically during autonomous
*/
@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);
Expand All @@ -116,4 +131,3 @@ public void teleopPeriodic() {
public void testPeriodic() {
}
}

176 changes: 128 additions & 48 deletions src/org/usfirst/frc/team2264/robot/autonomous.java
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
}

}