Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Alex #2

Open
wants to merge 6 commits into
base: master
Choose a base branch
from
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
8 changes: 5 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -22,14 +22,16 @@
cd ..
mv FRC-2014 2014

NOTE: If you recieve errors when trying "git clone git@github.com:frc604/FRC-2014.git" [read this][5]

6. Go to Netbeans and create a new "Simple Robot Template" project with the
following settings:

| Field | Value |
| ---------------- | -------------------------- |
| Project Name | FRC-2014 |
| Package | com._604robotics.robot2014 |
| Main Robot Class | Robot2014 |
| Project Package | com._604robotics.robot2014 |
| Robot Class | Robot2014 |

If you get strange errors starting up the code after a deploy, it's because
you messed these settings up!
Expand All @@ -51,4 +53,4 @@ If you have any questions, talked to [Michael][4].
[2]: http://wpilib.screenstepslive.com/s/3120/m/7885/l/79407-configuring-the-netbeans-installation
[3]: http://git-scm.com/
[4]: mailto:mdsmtp@gmail.com

[5]: https://help.github.com/articles/generating-ssh-keys/
2 changes: 1 addition & 1 deletion src/com/_604robotics/robot2014/Robot2014.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

public class Robot2014 extends Robot {
public Robot2014 () {
this.set(new ModuleMap() {{
this.set(new ModuleMap() {{ //adds each module to a hashtable named moduleTable. Not sure what a hashtable is exactly. Figure this out.
add("Dashboard", new Dashboard());
add("Vision", new Vision());
add("Drive", new Drive());
Expand Down
20 changes: 10 additions & 10 deletions src/com/_604robotics/robot2014/modes/AutonomousMode.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,12 +14,12 @@ public class AutonomousMode extends Procedure {
public AutonomousMode () {
super(new Coordinator() {
protected void apply (ModuleManager modules) {
this.bind(new Binding(modules.getModule("Shifter").getAction("Low Gear")));
this.bind(new Binding(modules.getModule("Shifter").getAction("Low Gear"))); //set the shifter into low gear

this.bind(new Binding(modules.getModule("Shooter").getAction("Retract")));
this.bind(new Binding(modules.getModule("Shooter").getAction("Retract"))); //retract the shooter
this.bind(new Binding(modules.getModule("Intake").getAction("On"), new TriggerAnd(new TriggerAccess[] {
modules.getModule("Shooter").getTrigger("Charged"),
modules.getModule("Shooter").getTrigger("Deployed").not()
modules.getModule("Shooter").getTrigger("Deployed").not()//turn intake on if shooter is charged and not deployed
})));
}
});
Expand All @@ -34,26 +34,26 @@ protected void apply (ModuleManager modules) {
}));

add("Align", new Step(new TriggerMeasure(new TriggerAnd(new TriggerAccess[] {
modules.getModule("Drive").getTrigger("At Servo Target"),
modules.getModule("Drive").getTrigger("At Servo Target"), //when the servo is at target and the shooter is charged
modules.getModule("Shooter").getTrigger("Charged")
})), new Coordinator() {
protected void apply (ModuleManager modules) {
this.bind(new Binding(modules.getModule("Drive").getAction("Servo")));
this.fill(new DataWire(modules.getModule("Drive").getAction("Servo"), "clicks", 1663));
this.fill(new DataWire(modules.getModule("Drive").getAction("Servo"), "clicks", 1663)); //drive forwards 1663 clicks
}
}));

add("Pause", new Step(new TriggerMeasure(modules.getModule("Vision").getTrigger("Ready")), new Coordinator() {
protected void apply (ModuleManager modules) {
this.bind(new Binding(modules.getModule("Vision").getAction("Pause")));
this.bind(new Binding(modules.getModule("Flower").getAction("Shoot")));
this.bind(new Binding(modules.getModule("Rotation").getAction("Manual Angle")));
this.bind(new Binding(modules.getModule("Vision").getAction("Pause"))); //pause vision
this.bind(new Binding(modules.getModule("Flower").getAction("Shoot"))); //put flower into the shoot position
this.bind(new Binding(modules.getModule("Rotation").getAction("Manual Angle"))); //I can't figure out how rotation works at all. Ask Michael about this.
}
}));

add("Aim", new Step(new TriggerMeasure(new TriggerAnd(new TriggerAccess[] {
modules.getModule("Rotation").getTrigger("At Angle Target"),
modules.getModule("Flower").getTrigger("Travelling").not()
modules.getModule("Flower").getTrigger("Travelling").not() //while the flower isn't traveling
})), new Coordinator() {
protected void apply (ModuleManager modules) {
this.bind(new Binding(modules.getModule("Rotation").getAction("Manual Angle")));
Expand All @@ -63,7 +63,7 @@ protected void apply (ModuleManager modules) {
add("Shoot", new Step(new Coordinator() {
protected void apply (ModuleManager modules) {
this.bind(new Binding(modules.getModule("Rotation").getAction("Manual Angle")));
this.bind(new Binding(modules.getModule("Shooter").getAction("Deploy"), true));
this.bind(new Binding(modules.getModule("Shooter").getAction("Deploy"), true)); //fire the ball
}
}));
}
Expand Down
2 changes: 1 addition & 1 deletion src/com/_604robotics/robot2014/modules/Dashboard.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
public class Dashboard extends Module {
public Dashboard () {
this.set(new DataMap() {{
add("Manual Angle", new DashboardData("Manual Angle", -50D));
add("Manual Angle", new DashboardData("Manual Angle", -50D)); //sets up the angles for each rotation position

add("Stow Angle" , new DashboardData("Stow Angle", 0D));
add("Shoot Angle" , new DashboardData("Shoot Angle", -50D));
Expand Down
36 changes: 18 additions & 18 deletions src/com/_604robotics/robot2014/modules/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -18,14 +18,14 @@
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

public class Drive extends Module {
private final RobotDrive drive = new RobotDrive(2, 1);
private final RobotDrive drive = new RobotDrive(2, 1); //left, right motors on ports 2,1

private final Encoder leftEncoder = new Encoder(2, 1);
private final Encoder rightEncoder = new Encoder(3, 4);
private final Encoder leftEncoder = new Encoder(2, 1); //left encoder on channels 2,1
private final Encoder rightEncoder = new Encoder(3, 4); //right encoder on channels 3,4

private final PIDController pid = new PIDController(0.005, 0D, 0.005, leftEncoder, new PIDOutput () {
public void pidWrite (double output) {
drive.setLeftRightMotorOutputs(output, output);
drive.setLeftRightMotorOutputs(output, output); //set the speed of the left and right motors
}
});

Expand All @@ -36,7 +36,7 @@ public Drive () {
leftEncoder.start();
rightEncoder.start();

pid.setAbsoluteTolerance(25);
pid.setAbsoluteTolerance(25); //set the error range for which onTarget can still return true
SmartDashboard.putData("Drive PID", pid);

this.set(new DataMap() {{
Expand Down Expand Up @@ -66,12 +66,12 @@ public double run () {
}});

this.set(new TriggerMap() {{
add("At Servo Target", new Trigger() {
add("At Servo Target", new Trigger() { //I wanna say this will run the servo for .5 seconds.
private final Timer timer = new Timer();
private boolean timing = false;

public boolean run () {
if (pid.isEnable() && pid.onTarget()) {
if (pid.isEnable() && pid.onTarget()) { //if the pid controller is on and is on within the tolerance
if (!timing) {
timing = true;
timer.start();
Expand All @@ -95,20 +95,20 @@ public boolean run () {
this.set(new ElasticController() {{
addDefault("Off", new Action() {
public void run (ActionData data) {
drive.tankDrive(0D, 0D);
drive.tankDrive(0D, 0D); //leftstick and right stick values. not sure what that means exactly.
}
});

add("Arcade Drive", new Action(new FieldMap () {{
define("throttle", 0D);
define("turn", 0D);
define("throttle", 0D); //the throttle stick value
define("turn", 0D); //the turn stick value
}}) {
public void run (ActionData data) {
drive.arcadeDrive(data.get("throttle"), data.get("turn"));
drive.arcadeDrive(data.get("throttle"), data.get("turn")); //sets the throttle and turn stick values
}

public void end (ActionData data) {
drive.stopMotor();
drive.stopMotor(); //stops the motor I suppose
}
});

Expand All @@ -125,7 +125,7 @@ public void end (ActionData data) {
}
});

add("Stick Drive", new Action(new FieldMap () {{
add("Stick Drive", new Action(new FieldMap () {{ // I'm almost completely sure this is exaclty the same as arcade drive but I could be wrong
define("throttle", 0D);
define("turn", 0D);
}}) {
Expand All @@ -142,22 +142,22 @@ public void end (ActionData data) {
define("clicks", 0D);
}}) {
public void begin (ActionData data) {
pid.setSetpoint(data.get("clicks") + data.data("Left Drive Clicks"));
pid.enable();
pid.setSetpoint(data.get("clicks") + data.data("Left Drive Clicks")); //set the clicks and the clicks to the desired value?
pid.enable(); //start running the pid controller
}

public void end (ActionData data) {
pid.reset();
pid.reset(); //Reset the previous error, the integral term, and disable the controller
}
});

add("Forward", new Action() {
public void run (ActionData data) {
drive.setLeftRightMotorOutputs(1.0, 1.0);
drive.setLeftRightMotorOutputs(1.0, 1.0); // the speeds of the left an right motor become 1
}

public void end (ActionData data) {
drive.stopMotor();
drive.stopMotor(); //stops the motor
}
});
}});
Expand Down
38 changes: 19 additions & 19 deletions src/com/_604robotics/robot2014/modules/Flower.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,67 +10,67 @@
import edu.wpi.first.wpilibj.Timer;

public class Flower extends Module {
private final Solenoid top = new Solenoid(4);
private final Solenoid sides = new Solenoid(5);
private final Solenoid bottom = new Solenoid(3);
private final Solenoid top = new Solenoid(4); //top solenoid in channel 4
private final Solenoid sides = new Solenoid(5); //side solenoids in channel 5
private final Solenoid bottom = new Solenoid(3); //bottom solenoid in channel 3

private final Timer travelTimer = new Timer();

public Flower () {
this.set(new TriggerMap() {{
add("Travelling", new Trigger() {
public boolean run () {
return travelTimer.get() < 0.6;
return travelTimer.get() < 0.6; //petals always travel for at least .6 seconds
}
});
}});

this.set(new StateController () {{
addDefault("Close", new Action() {
public void begin (ActionData data) {
top.set(false);
sides.set(false);
bottom.set(false);
top.set(false); //for the closed polition, the top petal is closed
sides.set(false); //the sides are closed
bottom.set(false); //the bottom is closed

travelTimer.reset();
}
});

add("Open", new Action() {
public void begin (ActionData data) {
top.set(true);
sides.set(true);
bottom.set(true);
top.set(true); //for the open position, the top petal is open
sides.set(true); //the sides are open
bottom.set(true); //and the bottom is open

travelTimer.reset();
}
});

add("Pickup", new Action() {
public void begin (ActionData data) {
top.set(false);
sides.set(false);
bottom.set(false);
top.set(false); //for the pickup position, the top is closed
sides.set(false); //the sides are closed
bottom.set(false); //and the bottom is closed

travelTimer.reset();
}
});

add("Drop", new Action() {
public void begin (ActionData data) {
top.set(true);
sides.set(true);
bottom.set(false);
top.set(true); //for the dropping position, the top petal is open
sides.set(true); //the sides are opened
bottom.set(false); //and the bottom is closed

travelTimer.reset();
}
});

add("Shoot", new Action() {
public void begin (ActionData data) {
top.set(true);
sides.set(false);
bottom.set(false);
top.set(true); //for the shooting position, the top petal is open
sides.set(false); //the sides are closed
bottom.set(false); //and the bottom is closed

travelTimer.reset();
}
Expand Down
8 changes: 4 additions & 4 deletions src/com/_604robotics/robot2014/modules/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,22 +7,22 @@
import edu.wpi.first.wpilibj.Victor;

public class Intake extends Module {
private final Victor motor = new Victor(5);
private final Victor motor = new Victor(5); //adds intake victor to channel 5

public Intake() {
this.set(new ElasticController() {{
addDefault("Off", new Action() {
public void run(ActionData data) {
public void run(ActionData data) { //stops intake
motor.stopMotor();
}
});

add("On", new Action() {
public void run(ActionData data) {
public void run(ActionData data) { //runs the intake
motor.set(-1D);
}

public void end(ActionData data) {
public void end(ActionData data) { //stops the intake
motor.stopMotor();
}
});
Expand Down
9 changes: 5 additions & 4 deletions src/com/_604robotics/robot2014/modules/Regulator.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,25 +8,26 @@
import com._604robotics.robotnik.trigger.TriggerMap;
import edu.wpi.first.wpilibj.Compressor;

/*controls the compressor for pneumatics*/
public class Regulator extends Module {
private final Compressor compressor = new Compressor(5, 1);
private final Compressor compressor = new Compressor(5/*pressure switch channel*/, 1/*compressor Relay Channel*/);

public Regulator () {
this.set(new TriggerMap() {{
add("Charged", new Trigger() {
public boolean run () {
return compressor.getPressureSwitchValue();
return compressor.getPressureSwitchValue(); //how much pressure
}
});
}});

this.set(new ElasticController() {{
addDefault("On", new Action() {
public void begin (ActionData data) {
public void begin (ActionData data) { //starts the compressor
compressor.start();
}

public void end (ActionData data) {
public void end (ActionData data) { //stops the compressor
compressor.stop();
}
});
Expand Down
15 changes: 8 additions & 7 deletions src/com/_604robotics/robot2014/modules/Rotation.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,10 +16,10 @@
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

public class Rotation extends Module {
private final MA3A10 encoder = new MA3A10(1, 1);
private final Victor motor = new Victor(3);
private final MA3A10 encoder = new MA3A10(1, 1); //I have no idea what this device is. Something tossed on the rotation mechanism if I were to guess.
private final Victor motor = new Victor(3); //new victor in channel 3

private final AntiWindupPIDController pid = new AntiWindupPIDController(-0.025, 0, Double.MAX_VALUE, 1, -0.025, encoder, motor);
private final AntiWindupPIDController pid = new AntiWindupPIDController(-0.025, 0, Double.MAX_VALUE, 1, -0.025, encoder/*input*/, motor/*output*/);

private double baseAngle = 185D;

Expand Down Expand Up @@ -91,11 +91,12 @@ public void end (ActionData data) {
}
});

add("Manual Angle", new AngleAction());
//All of this is set in the Dashboard module? But it's not imported. I have no idea man.
add("Manual Angle", new AngleAction()); //Manual angle is set to -50D

add("Stow", new AngleAction());
add("Shoot", new AngleAction());
add("Ground", new AngleAction());
add("Stow", new AngleAction()); //Stow angle is set to 0D
add("Shoot", new AngleAction()); //Shoot angle is set to -50D
add("Ground", new AngleAction()); //Ground angle is set to -108D

add("Hold", new Action() {
public void begin (ActionData data) {
Expand Down
Loading