Skip to content

Commit

Permalink
Merged develop-untested
Browse files Browse the repository at this point in the history
  • Loading branch information
Nam Tran committed Feb 4, 2015
2 parents 89600c9 + 702937b commit 15667ec
Show file tree
Hide file tree
Showing 27 changed files with 1,409 additions and 7 deletions.
3 changes: 3 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -58,3 +58,6 @@ $RECYCLE.BIN/
# Windows shortcuts
*.lnk
/bin/
/bin/
/bin/
/bin/
57 changes: 54 additions & 3 deletions src/org/team708/robot/OI.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,15 @@
package org.team708.robot;

import org.team708.robot.commands.ToteElevatorDown;
import org.team708.robot.commands.ToteElevatorUp;
import org.team708.robot.commands.claw.ClawHeightDecrementNoPID;
import org.team708.robot.commands.claw.ClawHeightIncrementNoPID;
import org.team708.robot.commands.claw.ToggleClawOpen;
import org.team708.robot.commands.claw.ToggleWrist;
import org.team708.robot.commands.drivetrain.ToggleBrakeMode;
import org.team708.robot.commands.hockeyStick.ToggleHockeyStick;
import org.team708.robot.commands.intake.ToggleDirection;
import org.team708.robot.commands.intake.TogglePower;
import org.team708.robot.util.Gamepad;

import edu.wpi.first.wpilibj.buttons.Button;
Expand All @@ -12,25 +21,67 @@
*/
public class OI {

// Creates the driver and operator gamepad for use in the code
// Gamepads
public static Gamepad driverGamepad = new Gamepad(RobotMap.driverGamepad);
public static Gamepad operatorGamepad = new Gamepad(RobotMap.operatorGamepad);

/*
* Driver Button Mapping
* Driver Button Assignment
*/
private static final int toggleBrakeModeButton = Gamepad.button_L_Shoulder;
private static final int toggleHockeyStickButton = Gamepad.button_Y;
private static final int toggleIntakePowerButton = Gamepad.button_L_Shoulder;
private static final int toggleIntakeDirectionButton = Gamepad.button_R_Shoulder;

/*
* Driver Buttons
* Operator Button Assignment
*/
private static final int toteUpButton = Gamepad.button_Y;
private static final int toteDownButton = Gamepad.button_A;
public static final int toggleClawOpenButton = Gamepad.button_R_Shoulder;
public static final int toggleWristPositionButton = Gamepad.button_L_Shoulder;
public static final int clawHeightIncrementButton = Gamepad.button_Y;
public static final int clawHeightDecrementButton = Gamepad.button_A;

/*
* Driver Button Commands
*/
private static final Button toggleBrakeMode = new JoystickButton(driverGamepad, toggleBrakeModeButton);
public static final Button toggleHockeyStick = new JoystickButton(driverGamepad, toggleHockeyStickButton); // Toggles the hockey stick
public static final Button toggleIntakePower = new JoystickButton(driverGamepad, toggleIntakePowerButton); // Toggles the intake power on/off
public static final Button toggleIntakeDirection = new JoystickButton(driverGamepad, toggleIntakeDirectionButton); // Toggles the intake direction

/*
* Operator Button Commands
*/
private static final Button toteUp = new JoystickButton(operatorGamepad, toteUpButton);
private static final Button toteDown = new JoystickButton(operatorGamepad, toteDownButton);
public static final Button toggleClawOpen = new JoystickButton(operatorGamepad, toggleClawOpenButton); // Opens and closes the claw on a toggle
public static final Button toggleWristPosition = new JoystickButton(operatorGamepad, toggleWristPositionButton); // Toggles the wrist position (horizontal/vertical)
public static final Button clawHeightIncrement = new JoystickButton(operatorGamepad, clawHeightIncrementButton); // Increases the claw height by the height of a tote
public static final Button clawHeightDecrement = new JoystickButton(operatorGamepad, clawHeightDecrementButton); // Decreases the claw height by the height of a tote

/**
* Constructor
*/
public OI() {
/*
* Driver Commands to be called by button
*/
toggleBrakeMode.whenPressed(new ToggleBrakeMode());
toggleHockeyStick.whenPressed(new ToggleHockeyStick());
toggleIntakePower.whenPressed(new TogglePower());
toggleIntakeDirection.whenPressed(new ToggleDirection());

/*
* Operator Commands to be called by button
*/
toggleClawOpen.whenPressed(new ToggleClawOpen());
toggleWristPosition.whenPressed(new ToggleWrist());
clawHeightIncrement.whenPressed(new ClawHeightIncrementNoPID());
clawHeightDecrement.whenPressed(new ClawHeightDecrementNoPID());
toteUp.whenPressed(new ToteElevatorUp());
toteDown.whenPressed(new ToteElevatorDown());
}

//// CREATING BUTTONS
Expand Down
14 changes: 12 additions & 2 deletions src/org/team708/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,12 +10,15 @@
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

import org.team708.robot.commands.autonomous.DriveInSquare;
import org.team708.robot.commands.autonomous.OneContainer;
import org.team708.robot.commands.autonomous.OneContainerOneTote;
import org.team708.robot.commands.visionProcessor.FollowYellowTote;
import org.team708.robot.subsystems.Drivetrain;
import org.team708.robot.subsystems.VisionProcessor;
import org.team708.robot.subsystems.Claw;
import org.team708.robot.subsystems.ClawElevator;
import org.team708.robot.subsystems.HockeyStick;
import org.team708.robot.subsystems.Intake;
import org.team708.robot.subsystems.ToteElevator;

/**
* The VM is configured to automatically run this class, and to call the
Expand All @@ -37,6 +40,12 @@ public class Robot extends IterativeRobot {
Timer statsTimer; // Timer used for Smart Dash statistics
private final double sendStatsIntervalSec = .5; // Interval between statistic reporting

public static final Intake intake = new Intake();
public static final HockeyStick hockeyStick = new HockeyStick();
public static final ToteElevator toteElevator = new ToteElevator();
public static final Claw claw = new Claw();
public static final ClawElevator clawElevator = new ClawElevator();

Command autonomousCommand;
SendableChooser autonomousMode;

Expand Down Expand Up @@ -120,6 +129,7 @@ private void sendStatistics() {
// Various debug information
drivetrain.sendToDashboard();
visionProcessor.sendToDashboard();
intake.sendToDashboard();
}
}

Expand Down
39 changes: 37 additions & 2 deletions src/org/team708/robot/RobotMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,16 +11,51 @@ public class RobotMap {
public static final int driverGamepad = 1;
public static final int operatorGamepad = 2;

// Relays
public static final int clawFingerMotorSpike = 2;

// Drivetrain CAN Device IDs
public static final int drivetrainLeftMotorMaster = 11;
public static final int drivetrainLeftMotorSlave = 12;
public static final int drivetrainRightMotorMaster = 14;
public static final int drivetrainRightMotorSlave = 15;
public static final int drivetrainRightMotorMaster = 13;
public static final int drivetrainRightMotorSlave = 14;

// Tote Elevator CAN Device IDs
public static final int toteElevatorMotor1 = 21;
public static final int toteElevatorMotor2 = 22;

// Digital Input Output
public static final int toteElevatorEncoderA = 2;
public static final int toteElevatorEncoderB = 3;

// Other CAN Talons
public static final int clawElevatorMotor = 31;

// Digital IO
public static final int clawElevatorEncoderA = 4;
public static final int clawElevatorEncoderB = 5;

//Intake CAN Device IDs
public static final int intakeLeftMotor = 21;
public static final int intakeRightMotor = 22;

// Analog sensor IDs
public static final int gyro = 0;
public static final int drivetrainIRSensor = 1;
public static final int toteElevatorIRSensor = 1;

//Hockey stick Solenoids
public static final int hockeySolenoidA = 4;
public static final int hockeySolenoidB = 5;

// Digital I/O Ports
public static final int toteSwitch = 6;

// PCM Ports
public static final int clawDoubleSolenoidA = 2;
public static final int clawDoubleSolenoidB = 3;
public static final int clawWristDoubleSolenoidA = 4;
public static final int clawWristDoubleSolenoidB = 5;

// For example to map the left and right motors, you could define the
// following variables to use with your drivetrain subsystem.
Expand Down
50 changes: 50 additions & 0 deletions src/org/team708/robot/commands/ToteElevatorDown.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
package org.team708.robot.commands;
import org.team708.robot.Robot;
import org.team708.robot.util.Math708;

import edu.wpi.first.wpilibj.command.Command;

/**
*
*/
public class ToteElevatorDown extends Command {

private final double threshold = 1;

public ToteElevatorDown() {
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);
requires(Robot.toteElevator);
}

// Called just before this Command runs the first time
protected void initialize() {
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
if (!Robot.toteElevator.elevatorDown) {
Robot.toteElevator.lowerTote();
}
}

// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return Math708.isWithinThreshold(Robot.toteElevator.getEncoderDistance(), -Robot.toteElevator.TOP_ENCODER_DISTANCE, threshold)
|| Robot.toteElevator.elevatorDown;
}

// Called once after isFinished returns true
protected void end() {
Robot.toteElevator.stopTote();
Robot.toteElevator.elevatorDown = true;
Robot.toteElevator.setToteCount(0);
Robot.toteElevator.resetEncoder();
}

// Called when another command which requires one or more of the same
// subsystems are scheduled to run
protected void interrupted() {
end();
}
}
54 changes: 54 additions & 0 deletions src/org/team708/robot/commands/ToteElevatorUp.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
package org.team708.robot.commands;

import org.team708.robot.Robot;
import org.team708.robot.util.Math708;

import edu.wpi.first.wpilibj.command.Command;

/**
*
*/
public class ToteElevatorUp extends Command {

private final double threshold = 1;
private boolean atToteLimitMax;

public ToteElevatorUp() {
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);
requires(Robot.toteElevator);
}

// Called just before this Command runs the first time
protected void initialize() {
atToteLimitMax = (Robot.toteElevator.toteCount == Robot.toteElevator.TOTE_UPPER_LIMIT);

}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
if (!atToteLimitMax) {
Robot.toteElevator.raiseTote();
}
}

// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return Math708.isWithinThreshold(Robot.toteElevator.getEncoderDistance(), Robot.toteElevator.TOP_ENCODER_DISTANCE, threshold)
|| atToteLimitMax;
}

// Called once after isFinished returns true
protected void end() {
Robot.toteElevator.stopTote();
Robot.toteElevator.setToteCount(Robot.toteElevator.getToteCount() + 1);
Robot.toteElevator.resetEncoder();
Robot.toteElevator.elevatorDown = false;
}

// Called when another command which requires one or more of the same
// subsystems are scheduled to run
protected void interrupted() {
end();
}
}
52 changes: 52 additions & 0 deletions src/org/team708/robot/commands/claw/ClawHeightDecrement.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
package org.team708.robot.commands.claw;

import org.team708.robot.Robot;
import org.team708.robot.subsystems.ClawElevator;

import edu.wpi.first.wpilibj.command.Command;

/**
*
*/
public class ClawHeightDecrement extends Command {

public ClawHeightDecrement() {
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);
requires(Robot.clawElevator);
}

// Called just before this Command runs the first time
protected void initialize() {
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {

/*
* Sets the PID setpoint to the lower limit if the robot is within a tote height of
* of the lower limit, or decrements it by the height of a tote if it isn't
*/
if(Robot.clawElevator.getPosition() <=
(ClawElevator.LOWER_LIMIT + ClawElevator.TOTE_HEIGHT)) {
Robot.clawElevator.setSetpoint(ClawElevator.LOWER_LIMIT);
} else {
Robot.clawElevator.setSetpoint(Robot.clawElevator.getPosition() - ClawElevator.TOTE_HEIGHT);
}

}

// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return true;
}

// Called once after isFinished returns true
protected void end() {
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
}
}
Loading

0 comments on commit 15667ec

Please sign in to comment.