summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLuke Shumaker <lukeshu@sbcglobal.net>2016-01-30 13:15:22 -0500
committerLuke Shumaker <lukeshu@sbcglobal.net>2016-01-30 13:15:22 -0500
commit26b916b43fdcafd9091e10564e68cc351beb9023 (patch)
tree2ec0dd3be68839f897b6b925bb2df8ae227f2357
parent3a20b69a4fec4f13e5685f615b3e94d802720743 (diff)
stuff (from Adi's laptop)
-rw-r--r--src/org/usfirst/frc/team4272/robot2016/Autonomous.java17
-rw-r--r--src/org/usfirst/frc/team4272/robot2016/Control.java4
-rw-r--r--src/org/usfirst/frc/team4272/robot2016/HwRobot.java24
-rw-r--r--src/org/usfirst/frc/team4272/robot2016/Robot.java1
-rw-r--r--src/org/usfirst/frc/team4272/robot2016/Teleop.java28
-rw-r--r--src/org/usfirst/frc/team4272/robotlib/Xbox360Controller.java1
6 files changed, 26 insertions, 49 deletions
diff --git a/src/org/usfirst/frc/team4272/robot2016/Autonomous.java b/src/org/usfirst/frc/team4272/robot2016/Autonomous.java
index 4fab67f..295cba9 100644
--- a/src/org/usfirst/frc/team4272/robot2016/Autonomous.java
+++ b/src/org/usfirst/frc/team4272/robot2016/Autonomous.java
@@ -1,30 +1,13 @@
package org.usfirst.frc.team4272.robot2016;
-import edu.wpi.first.wpilibj.Timer;
-
public class Autonomous {
- private final Timer time = new Timer();
private final HwRobot robot;
public Autonomous(HwRobot robot) {
this.robot = robot;
- time.reset();
- time.start();
- robot.rDriveE.reset();
- robot.lDriveE.reset();
}
public Control run(Control c) {
- if (robot.rDriveE.getDistance() > -(15.5*140*1.15)) {
- c.rDrive = c.lDrive = 0.7;
- //initially -0.7 to drive backwards
- //0 to 9787 for going backwards
- //0 to negative for forward
- //INDY: (15.5*140*1.1)
- //PURDUE: (15.5*140*1.15) for a drop further
- } else {
- c.rDrive = c.lDrive = 0;
- }
return c;
}
}
diff --git a/src/org/usfirst/frc/team4272/robot2016/Control.java b/src/org/usfirst/frc/team4272/robot2016/Control.java
index b136e0c..d7eadf5 100644
--- a/src/org/usfirst/frc/team4272/robot2016/Control.java
+++ b/src/org/usfirst/frc/team4272/robot2016/Control.java
@@ -1,9 +1,9 @@
package org.usfirst.frc.team4272.robot2016;
public class Control {
- double lDrive, rDrive, fBall, bBall;
+ double lDrive, rDrive, fBall, bBall, arm;
public Control() {
- lDrive = rDrive = fBall = bBall = 0;
+ lDrive = rDrive = fBall = bBall = arm = 0;
}
}
diff --git a/src/org/usfirst/frc/team4272/robot2016/HwRobot.java b/src/org/usfirst/frc/team4272/robot2016/HwRobot.java
index b2c7150..22d2fc7 100644
--- a/src/org/usfirst/frc/team4272/robot2016/HwRobot.java
+++ b/src/org/usfirst/frc/team4272/robot2016/HwRobot.java
@@ -2,9 +2,9 @@ package org.usfirst.frc.team4272.robot2016;
import org.usfirst.frc.team4272.robotlib.PIDOutputSplitter;
-import edu.wpi.first.wpilibj.Encoder;
+//import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PIDOutput;
-import edu.wpi.first.wpilibj.PIDSourceType;
+//import edu.wpi.first.wpilibj.PIDSourceType;
import edu.wpi.first.wpilibj.Talon;
public class HwRobot {
@@ -27,23 +27,23 @@ public class HwRobot {
// naming convention: {side_letter}{Thing}{E|M (encoder/motor)}
- public Encoder lDriveE = new Encoder(/*DIO*/2,/*DIO*/3);
- private PIDOutput lDriveM = new PIDOutputSplitter(new Talon(/*PWM*/0),
- new Talon(/*PWM*/1));
- public Encoder rDriveE = new Encoder(/*DIO*/0,/*DIO*/1, true);
- private PIDOutput rDriveM = new PIDOutputSplitter(new Talon(/*PWM*/2),
- new Talon(/*PWM*/3));
- private PIDOutput fBallM = new PIDOutputSplitter(new Talon(/*PWM*/4), new Talon(/*PWM*/5));
- private PIDOutput bBallM = new PIDOutputSplitter(new Talon(/*PWM*/6), new Talon(/*PWM*/7));
+ //public Encoder lDriveE = new Encoder(/*DIO*/2,/*DIO*/3);
+ //public Encoder rDriveE = new Encoder(/*DIO*/0,/*DIO*/1, true);
+ private PIDOutput lDriveM = new PIDOutputSplitter(new Talon(/*PWM*/0), new Talon(/*PWM*/1));
+ private PIDOutput rDriveM = new PIDOutputSplitter(new Talon(/*PWM*/2), new Talon(/*PWM*/3));
+ private PIDOutput armM = new PIDOutputSplitter(new Talon(/*PWM*/4), new Talon(/*PWM*/5));
+ private PIDOutput fBallM = new PIDOutputSplitter(new Talon(/*PWM*/6), new Talon(/*PWM*/7));
+ private PIDOutput bBallM = new PIDOutputSplitter(new Talon(/*PWM*/8), new Talon(/*PWM*/9));
public HwRobot() {
- lDriveE.setPIDSourceType(PIDSourceType.kRate);
- rDriveE.setPIDSourceType(PIDSourceType.kRate);
+ //lDriveE.setPIDSourceType(PIDSourceType.kRate);
+ //rDriveE.setPIDSourceType(PIDSourceType.kRate);
}
public void run(Control c) {
lDriveM.pidWrite( c.lDrive);
rDriveM.pidWrite(-c.rDrive);
+ armM.pidWrite(-c.arm);
fBallM.pidWrite(c.fBall);
bBallM.pidWrite(c.bBall);
}
diff --git a/src/org/usfirst/frc/team4272/robot2016/Robot.java b/src/org/usfirst/frc/team4272/robot2016/Robot.java
index c9ad4c5..fc2eef6 100644
--- a/src/org/usfirst/frc/team4272/robot2016/Robot.java
+++ b/src/org/usfirst/frc/team4272/robot2016/Robot.java
@@ -37,7 +37,6 @@ public class Robot extends IterativeRobot {
public void teleopInit() {
try {
- robot.rDriveE.reset();
teleop = new Teleop();
} catch (Exception e) {}
}
diff --git a/src/org/usfirst/frc/team4272/robot2016/Teleop.java b/src/org/usfirst/frc/team4272/robot2016/Teleop.java
index 4853162..41919fa 100644
--- a/src/org/usfirst/frc/team4272/robot2016/Teleop.java
+++ b/src/org/usfirst/frc/team4272/robot2016/Teleop.java
@@ -1,12 +1,13 @@
package org.usfirst.frc.team4272.robot2016;
-import org.usfirst.frc.team4272.robotlib.PushButton;
+//import org.usfirst.frc.team4272.robotlib.PushButton;
+import org.usfirst.frc.team4272.robotlib.Xbox360Controller.Axis;
import org.usfirst.frc.team4272.robotlib.Xbox360Controller.Button;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj.Joystick;
public class Teleop {
- private PushButton camButton = new PushButton();
+ //private PushButton camButton = new PushButton();
public Teleop() {
}
@@ -21,24 +22,18 @@ public class Teleop {
/* Drive */
control.lDrive = jsScale(oi.lStick);
control.rDrive = jsScale(oi.rStick);
-
- /* Ball intake/shooter */
- if (oi.lStick.getTrigger()) {
- /* intake */
- control.fBall = control.bBall = -SmartDashboard.getNumber("intakeSpeed");
- } else if (oi.rStick.getTrigger()) {
- /* outtake */
- control.fBall = 1;
- if (oi.rStick.getRawButton(3)) {
- control.bBall = 1;
- } else {
- control.bBall = 0;
- }
+ control.arm = -oi.xbox.getAxis(Axis.LY);
+ control.fBall = oi.xbox.getAxis(Axis.RTrigger) - oi.xbox.getAxis(Axis.LTrigger);
+ if (control.fBall < -0.1) {
+ control.bBall = -1;
} else {
- control.fBall = control.bBall = 0;
+ control.bBall = oi.xbox.getButton(Button.A) ? 1 : 0;
}
+ SmartDashboard.putNumber("fBall", control.fBall);
+
/* Take pictures */
+ /*
if (camButton.update(oi.xbox.getButton(Button.RT))) {
try {
ProcessBuilder pb = new ProcessBuilder("/home/lvuser/tweeterbot/bin/snapPhoto");
@@ -46,6 +41,7 @@ public class Teleop {
pb.start();
} catch (Exception e) {};
}
+ */
return control;
}
diff --git a/src/org/usfirst/frc/team4272/robotlib/Xbox360Controller.java b/src/org/usfirst/frc/team4272/robotlib/Xbox360Controller.java
index 8c54b5f..b5c1d13 100644
--- a/src/org/usfirst/frc/team4272/robotlib/Xbox360Controller.java
+++ b/src/org/usfirst/frc/team4272/robotlib/Xbox360Controller.java
@@ -34,7 +34,6 @@
package org.usfirst.frc.team4272.robotlib;
import edu.wpi.first.wpilibj.GenericHID;
-import edu.wpi.first.wpilibj.GenericHID.Hand;
import edu.wpi.first.wpilibj.Joystick;
/**