Skip to content

Commit

Permalink
Merge pull request #22 from Team708/develop
Browse files Browse the repository at this point in the history
Tested on BC and cleaned up
  • Loading branch information
Nam Tran committed Feb 11, 2015
2 parents c272e1d + bc0cf9d commit 04b879a
Show file tree
Hide file tree
Showing 20 changed files with 468 additions and 472 deletions.
65 changes: 65 additions & 0 deletions src/org/team708/robot/Constants.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
package org.team708.robot;

import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.Relay;

/**
* Class containing all the code-related constants, so wiring and
* gamepad controls are not included
* @author omn0mn0m
*/
public final class Constants {

/*
* Motor Controllers
*/
public static final Relay.Value SPIKE_FORWARD = Relay.Value.kForward;
public static final Relay.Value SPIKE_REVERSE = Relay.Value.kReverse;
public static final Relay.Value SPIKE_OFF = Relay.Value.kOff;
public static final double MOTOR_FORWARD = 1.0;
public static final double MOTOR_REVERSE = -1.0;
public static final double MOTOR_OFF = 0.0;

/*
* Double Solenoids
*/
public static final DoubleSolenoid.Value OPEN = DoubleSolenoid.Value.kReverse;
public static final DoubleSolenoid.Value CLOSED = DoubleSolenoid.Value.kForward;
public static final DoubleSolenoid.Value VERTICAL = DoubleSolenoid.Value.kReverse;
public static final DoubleSolenoid.Value HORIZONTAL = DoubleSolenoid.Value.kForward;
public static final DoubleSolenoid.Value RETRACTED = DoubleSolenoid.Value.kReverse;
public static final DoubleSolenoid.Value DEPLOYED = DoubleSolenoid.Value.kForward;

/*
* Smart Dashboard
*/
public static final double SEND_STATS_INTERVAL = .25; // Interval between statistic reporting in seconds

/*
* Sensors
*/
public static final double IR_HAS_TOTE_DISTANCE = 5.0;
public static final double ENCODER_BOTTOM_POSITION = 0.0;

/*
* Game Elements
*/
public static final double TOTE_HEIGHT = 12.1;

/*
* Indexer
*/
public static final double INDEXER_ENCODER_PULSES_PER_REV = 7.0;
public static final double INDEXER_GEARING = 0.32;
public static final double INDEXER_SPROCKET_DIAMETER = 2.0;
public static final int TOTE_LIMIT = 6;

/*
* Drivetrain
*/
public static final double TANK_STICK_TOLERANCE = .025;

/*
* Vision Processor
*/
}
34 changes: 24 additions & 10 deletions src/org/team708/robot/OI.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,10 @@
import org.team708.robot.commands.clawElevator.IncrementClawOne;
import org.team708.robot.commands.drivetrain.ToggleBrakeMode;
import org.team708.robot.commands.hockeyStick.ToggleHockeyStick;
import org.team708.robot.commands.indexer.IndexerDown;
import org.team708.robot.commands.indexer.IndexerUp;
import org.team708.robot.commands.intake.ToggleDirection;
import org.team708.robot.commands.intake.TogglePower;
import org.team708.robot.commands.toteElevator.ToteElevatorDown;
import org.team708.robot.commands.toteElevator.ToteElevatorUp;
import org.team708.robot.util.Gamepad;
import org.team708.robot.util.triggers.AxisDown;
import org.team708.robot.util.triggers.AxisUp;
Expand All @@ -21,52 +21,66 @@
/**
* This class is the glue that binds the controls on the physical operator
* interface to the commands and command groups that allow control of the robot.
* @author omn0mn0m
* @author kazekitteh
* @author jlwang
* @author frakerman1
*/
public class OI {

// Gamepads
public static Gamepad driverGamepad = new Gamepad(RobotMap.driverGamepad);
public static Gamepad operatorGamepad = new Gamepad(RobotMap.operatorGamepad);
public static Gamepad driverGamepad = new Gamepad(RobotMap.driverGamepad); // Driver gamepad
public static Gamepad operatorGamepad = new Gamepad(RobotMap.operatorGamepad); // Operator gamepad

/*
* Driver Button Assignment
*/
// Drivetrain Buttons
private static final int toggleBrakeModeButton = Gamepad.button_L_Shoulder;

// Hockey Stick Buttons
private static final int toggleHockeyStickButton = Gamepad.button_Y;

// Intake Buttons
private static final int toggleIntakePowerButton = Gamepad.button_L_Shoulder;
private static final int toggleIntakeDirectionButton = Gamepad.button_R_Shoulder;

/*
* Operator Button Assignment
*/
// Indexer Buttons
private static final int toteUpAxis = Gamepad.leftStick_Y;
private static final int toteDownAxis = Gamepad.leftStick_Y;


// Claw Buttons
public static final int toggleClawOpenButton = Gamepad.button_R_Shoulder;
public static final int toggleWristPositionButton = Gamepad.button_L_Shoulder;

// Claw Elevator Buttons
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);
private static final Button toggleBrakeMode = new JoystickButton(driverGamepad, toggleBrakeModeButton); // Toggles whether the drive is in all brake or all coast
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 AxisUp toteUp = new AxisUp(operatorGamepad, toteUpAxis);
private static final AxisDown toteDown = new AxisDown(operatorGamepad, toteDownAxis);
private static final AxisUp toteUp = new AxisUp(operatorGamepad, toteUpAxis); // Increments one tote height up, picking up a tote along the way
private static final AxisDown toteDown = new AxisDown(operatorGamepad, toteDownAxis); // Moves the indexer down to release the tote stack
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
* Assigns commands to be called when each button is pressed.
*/
public OI() {
/*
Expand All @@ -82,8 +96,8 @@ public OI() {
*/
toggleClawOpen.whenPressed(new ToggleClawOpen());
toggleWristPosition.whenPressed(new ToggleWrist());
toteUp.whenActive(new ToteElevatorUp());
toteDown.whenActive(new ToteElevatorDown());
toteUp.whenActive(new IndexerUp());
toteDown.whenActive(new IndexerDown());
clawHeightIncrement.whenPressed(new IncrementClawOne());
clawHeightDecrement.whenPressed(new DecrementClawOne());
}
Expand Down
78 changes: 52 additions & 26 deletions src/org/team708/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,36 +14,35 @@
import org.team708.robot.commands.autonomous.DriveInSquare;
import org.team708.robot.commands.autonomous.OneContainerOneTote;
import org.team708.robot.commands.autonomous.ThreeTotes;
import org.team708.robot.commands.indexer.IndexerDown;
import org.team708.robot.commands.indexer.IndexerUp;
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;
import org.team708.robot.subsystems.Indexer;

/**
* The VM is configured to automatically run this class, and to call the
* functions corresponding to each mode, as described in the IterativeRobot
* documentation. If you change the name of this class or the package after
* creating this project, you must also update the manifest file in the resource
* directory.
*
* @author omn0mn0m
*/
public class Robot extends IterativeRobot {

//SmartDashboard
Preferences robotPreferences;

//creates timer for the SmartDashboard stat sending
Timer statsTimer; // Timer used for Smart Dash statistics
private final double sendStatsIntervalSec = .25; // Interval between statistic reporting
Timer statsTimer; // Timer used for Smart Dash statistics

public static Drivetrain drivetrain;
public static VisionProcessor visionProcessor;
public static Intake intake;
public static HockeyStick hockeyStick;
public static ToteElevator toteElevator;
public static Indexer indexer;
public static Claw claw;
public static ClawElevator clawElevator;
public static OI oi;
Expand All @@ -56,34 +55,37 @@ public class Robot extends IterativeRobot {
* used for any initialization code.
*/
public void robotInit() {
//initialize timer periodic debug messages
statsTimer = new Timer();
statsTimer.start();

statsTimer = new Timer(); // Initialises the timer for sending Smart Dashboard data
statsTimer.start(); // Starts the timer for the Smart Dashboard
// Subsystem Initialisation
drivetrain = new Drivetrain();
visionProcessor = new VisionProcessor();
intake = new Intake();
hockeyStick = new HockeyStick();
toteElevator = new ToteElevator();
indexer = new Indexer();
claw = new Claw();
clawElevator = new ClawElevator();
oi = new OI();

sendDashboardSubsystems();
oi = new OI(); // Initialises the OI. This MUST BE LAST or a NullPointerException will be thrown

LiveWindow.addActuator("PID", "PID", drivetrain.getPIDController());
sendDashboardSubsystems(); // Sends each subsystem's currently running command to the Smart Dashboard

// instantiate the command used for the autonomous period
autonomousMode = new SendableChooser();
queueAutonomousModes();
setPIDPreferences();
autonomousMode = new SendableChooser(); // Initialises the Autonomous selection box
queueAutonomousModes(); // Adds autonomous modes to the selection box
setPIDPreferences(); // Adds PID gain constants to the Robot Preferences
}

/**
* Runs periodically while the robot is enabled
*/
public void disabledPeriodic() {
Scheduler.getInstance().run();
sendStatistics();
}

/**
* Runs at the start of autonomous mode
*/
public void autonomousInit() {
// schedule the autonomous command (example)
autonomousCommand = (Command)autonomousMode.getSelected();
Expand All @@ -98,6 +100,9 @@ public void autonomousPeriodic() {
sendStatistics();
}

/**
* Runs when teleop mode initialises
*/
public void teleopInit() {
// This makes sure that the autonomous stops running when
// teleop starts running. If you want the autonomous to
Expand Down Expand Up @@ -130,19 +135,25 @@ public void testPeriodic() {
sendStatistics();
}

/**
* Sends data from each subsystem periodically as set by sendStatsIntervalSec
*/
private void sendStatistics() {
if (statsTimer.get() >= sendStatsIntervalSec) {
if (statsTimer.get() >= Constants.SEND_STATS_INTERVAL) {
statsTimer.reset();

// Various debug information
drivetrain.sendToDashboard();
visionProcessor.sendToDashboard();
intake.sendToDashboard();
clawElevator.sendToDashboard();
toteElevator.sendToSmartDashboard();
indexer.sendToSmartDashboard();
}
}

/**
* Adds every autonomous mode to the selection box and adds the box to the Smart Dashboard
*/
private void queueAutonomousModes() {
autonomousMode.addDefault("Do Nothing", new DoNothing());
autonomousMode.addObject("Drive in Square", new DriveInSquare());
Expand All @@ -152,19 +163,34 @@ private void queueAutonomousModes() {
SmartDashboard.putData("Autonomous Selection", autonomousMode);
}

/**
* Sends every subsystem to the Smart Dashboard
*/
private void sendDashboardSubsystems() {
SmartDashboard.putData(drivetrain);
SmartDashboard.putData(clawElevator);
SmartDashboard.putData(claw);
SmartDashboard.putData(toteElevator);
SmartDashboard.putData(indexer);
SmartDashboard.putData(visionProcessor);
SmartDashboard.putData(hockeyStick);
SmartDashboard.putData(intake);

SmartDashboard.putData("Move Up", new IndexerUp());
SmartDashboard.putData("Move Down", new IndexerDown());
}

/**
* Adds PID gain constants to the Robot Preferences to allow for faster tuning
*/
private void setPIDPreferences() {
// drivetrain.setPIDGain('p', robotPreferences.getDouble("P", drivetrain.getPIDGain('p')));
// drivetrain.setPIDGain('i', robotPreferences.getDouble("I", drivetrain.getPIDGain('i')));
// drivetrain.setPIDGain('d', robotPreferences.getDouble("D", drivetrain.getPIDGain('d')));
// Attempts to get robot preferences to set for PID, but throws an exception if the SmartDashboard is not found
try {
drivetrain.setPIDGain('p', Preferences.getInstance().getDouble("P", drivetrain.getPIDGain('p')));
drivetrain.setPIDGain('i', Preferences.getInstance().getDouble("I", drivetrain.getPIDGain('i')));
drivetrain.setPIDGain('d', Preferences.getInstance().getDouble("D", drivetrain.getPIDGain('d')));
} catch (NullPointerException e) {
e.printStackTrace();
}

}
}
Loading

0 comments on commit 04b879a

Please sign in to comment.