Skip to content

Newoi #29

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

Open
wants to merge 4 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
23 changes: 3 additions & 20 deletions org/bitbuckets/frc2014/OI.java
Original file line number Diff line number Diff line change
Expand Up @@ -32,34 +32,17 @@ public class OI {
* The button that fires the ball.
*/
public Button fireButton = new JoystickButton(Control, 1);
/**
* The button that runs the intake motor backwards.
*/
public Button retractButton = new JoystickButton(Control, 2);
/**
* The button that deploys the intake.
*/
public Button intakeDeployButton = new JoystickButton(Control, 4);
/**
* The button that deploys the intake and runs the roller in.
*/
public Button outtakeButton = new JoystickButton(Control, 6);
public Button outtakeButton = new JoystickButton(Control, 4);
/**
* The button that deploys the intake and runs the roller.
*/
public Button intakeButton = new JoystickButton(Control, 8);
/**
* The button that makes the intake roller roll in.
*/
public Button intakeRollerButton = new JoystickButton(Control, 12);
public Button intakeButton = new JoystickButton(Control, 3);
/**
* The button that controls the catapult winch
*/
public Button winchButton = new JoystickButton(Control, 3);
/**
* The button that starts and stops the lights
*/
//public Button lightsOnOffButton = new JoystickButton(stick, //needs to be bound to button//;

public Button winchButton = new JoystickButton(Control, 12);
}

2 changes: 1 addition & 1 deletion org/bitbuckets/frc2014/RandomConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ public class RandomConstants {
/** The maximum skim gain. Used in cheesy drive. **/
public static final double SKIM_GAIN = .5;
/** The maximum turn gain. Used in cheesy drive. **/
public static final double TURN_GAIN = 1.0;
public static final double TURN_GAIN = 1.3;
/** The cutoff for the throttle. Used in cheesy drive. **/
public static final double THROTTLE_CUTOFF = .3;

Expand Down
22 changes: 13 additions & 9 deletions org/bitbuckets/frc2014/RobotMain.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
import edu.wpi.first.wpilibj.Compressor;
import edu.wpi.first.wpilibj.IterativeRobot;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.command.Command;
import edu.wpi.first.wpilibj.command.Scheduler;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import org.bitbuckets.frc2014.commands.*;
Expand All @@ -21,30 +22,30 @@
public class RobotMain extends IterativeRobot {
/** The compressor. */
private Compressor compressor = new Compressor(RobotMap.PRESSURE_SWITCH, RobotMap.COMPRESSOR_RELAY);
private Command autonCommand;

/**
* The method that is called when the robot is turned on or code has finished downloading.
*/
public void robotInit() {
// Initialize all subsystems
CommandBase.init();
autonCommand = new TwoBallAuto();
CommandBase.oi.fireButton.whenPressed(new Fire());
CommandBase.oi.retractButton.whenPressed(new ArmCatapult());
CommandBase.oi.intakeRollerButton.whenPressed(new RollerOn());
CommandBase.oi.intakeRollerButton.whenReleased(new RollerOff());
CommandBase.oi.winchButton.whenPressed(new ArmCatapult());
CommandBase.oi.outtakeButton.whenPressed(new OuttakeBall());
CommandBase.oi.outtakeButton.whenReleased(new RollerOff());
CommandBase.oi.intakeDeployButton.whenPressed(new RetractIntake());
CommandBase.oi.intakeDeployButton.whenReleased(new DeployIntake());
CommandBase.oi.intakeButton.whenPressed(new IntakeBall());
CommandBase.oi.intakeButton.whenReleased(new IntakeBallOff());
//CommandBase.oi.lightsOnOffButton.whenPressed(new SimpleLights());
//CommandBase.oi.intakeButton.whenPressed(new DeployIntake());
CommandBase.oi.intakeButton.whenReleased(new RetractIntake());
//CommandBase.oi.intakeButton.whenReleased(new IntakeBallOff());
}

/**
* The method run when autonomous is started.
*/
public void autonomousInit() {
autonCommand.start();
}

/**
Expand All @@ -64,7 +65,7 @@ public void teleopInit() {
// this line or commen tit out.

System.out.print("Teleop Started");

autonCommand.cancel();
compressor.start();
}

Expand All @@ -73,7 +74,10 @@ public void teleopInit() {
*/
public void teleopPeriodic() {
Scheduler.getInstance().run();
CommandBase.driveTrain.tankDrive(CommandBase.oi.JoyRight.getAxis(Joystick.AxisType.kY), CommandBase.oi.JoyLeft.getAxis(Joystick.AxisType.kY));
//CommandBase.driveTrain.tankDrive(CommandBase.oi.JoyRight.getAxis(Joystick.AxisType.kY), CommandBase.oi.JoyLeft.getAxis(Joystick.AxisType.kY));
//CommandBase.driveTrain.drive(CommandBase.oi.Control.getY(), CommandBase.oi.Control.getX());
CommandBase.driveTrain.cheesyDrive(CommandBase.oi.Control.getY(), CommandBase.oi.Control.getX());
//System.out.println(CommandBase.oi.Control.getY()+" "+ CommandBase.oi.Control.getX());
}

/**
Expand Down
50 changes: 50 additions & 0 deletions org/bitbuckets/frc2014/commands/DriveTimeMillis.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
/*
* To change this license header, choose License Headers in Project Properties.
* To change this template file, choose Tools | Templates
* and open the template in the editor.
*/
package org.bitbuckets.frc2014.commands;

/**
*
* @author Cal Miller
*/
public class DriveTimeMillis extends CommandBase {

private double power, rotation;
private long time, timeInit;

public DriveTimeMillis(double power, double rotation, long time) {
requires(driveTrain);

this.power = power;
this.rotation = rotation;
this.time = time;
}

// Called just before this Command runs the first time
protected void initialize() {
timeInit = System.currentTimeMillis();
driveTrain.drive(power, rotation);
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
driveTrain.drive(power, rotation);
}

// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return System.currentTimeMillis() - timeInit >= time;
}

// Called once after isFinished returns true
protected void end() {
driveTrain.drive(0, 0);
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
}
}
2 changes: 1 addition & 1 deletion org/bitbuckets/frc2014/commands/IntakeBall.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ public IntakeBall() {
* Called just before this Command runs the first time.
*/
protected void initialize() {
intake.setDeployed(true);//Makes the intake go down.
intake.setDeployed(false);//Makes the intake go down.
intake.setIntakeRoller(RandomConstants.INTAKE_FORWARDS);//Makes intake pull stuff.
}

Expand Down
1 change: 1 addition & 0 deletions org/bitbuckets/frc2014/commands/RetractIntake.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ public RetractIntake() {
*/
protected void initialize() {
intake.setDeployed(true);//Brings intake the intake.
intake.setIntakeRoller(0);
}

/**
Expand Down
40 changes: 40 additions & 0 deletions org/bitbuckets/frc2014/commands/TwoBallAuto.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
/*
* To change this license header, choose License Headers in Project Properties.
* To change this template file, choose Tools | Templates
* and open the template in the editor.
*/
package org.bitbuckets.frc2014.commands;

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

/**
*
* @author Cal Miller [email protected]
*/
public class TwoBallAuto extends CommandGroup {

public TwoBallAuto() {
addSequential(new RollerOn());
addSequential(new DeployIntake());
addSequential(new WaitMillis(250)); //t = .25
addSequential(new RollerOff());
addSequential(new WaitMillis(750)); //t = 1
addSequential(new Fire()); //t = 1.3
addSequential(new WaitMillis(750)); //t = 1
addSequential(new ArmCatapult()); //t = 2
addSequential(new RollerOn());
addSequential(new WaitMillis(1500)); //t = 3
addSequential(new RetractIntake());
addSequential(new RollerOff());
addSequential(new WaitMillis(750)); //t = 3.8
addSequential(new DeployIntake());
addSequential(new RollerOn());
addSequential(new WaitMillis(1500)); //t = 4.8
addSequential(new RollerOff());
addSequential(new Fire()); //t = 5.2
addSequential(new WaitMillis(750)); //t = 6.2
addSequential(new RetractIntake());
addParallel(new DriveTimeMillis(.5,0,1500)); //t = 8.7
addParallel(new ArmCatapult());
}
}
60 changes: 60 additions & 0 deletions org/bitbuckets/frc2014/commands/WaitMillis.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
/*
* To change this license header, choose License Headers in Project Properties.
* To change this template file, choose Tools | Templates
* and open the template in the editor.
*/
package org.bitbuckets.frc2014.commands;

/**
*
* @author James Wyeth
*/
public class WaitMillis extends CommandBase {
/** The time at the beginning of the command. **/
private long timeInit;
/** The time to wait for. **/
private int time;

/**
* Constructor. Sets the time to wait for.
*
* @param timeMillis The time to wait.
*/
public WaitMillis(int timeMillis) {
time = timeMillis;
}

/**
* Called at the beginning of the command.
*/
protected void initialize() {
timeInit = System.currentTimeMillis();
}

/**
* Called continuously while the command is running. Does nothing.
*/
protected void execute() {
}

/**
* Tells the command whether the tame has passed yet.
*
* @return Whether the time has passed.
*/
protected boolean isFinished() {
return System.currentTimeMillis() - timeInit >= time;
}

/**
* Called when <code>isFinished</code> returns false.
*/
protected void end() {
}

/**
* Called if something else needs the required subsystem. Never called in this command.
*/
protected void interrupted() {
}
}
6 changes: 3 additions & 3 deletions org/bitbuckets/frc2014/subsystems/Catapault.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.Solenoid;
import edu.wpi.first.wpilibj.Victor;
import edu.wpi.first.wpilibj.Talon;
import edu.wpi.first.wpilibj.command.Subsystem;
import org.bitbuckets.frc2014.RandomConstants;
import org.bitbuckets.frc2014.RobotMap;
Expand All @@ -21,7 +21,7 @@
*/
public class Catapault extends Subsystem {
/** Ball-shifter winch powered by two MiniCIMs on Victors */
private Victor winch;
private Talon winch;
/** Double-acting cylinder to shift between low-gear and neutral */
private DoubleSolenoid shifter;

Expand All @@ -38,7 +38,7 @@ public class Catapault extends Subsystem {
*/
public Catapault(){
super();
winch = new Victor(RobotMap.WINCH_MOTOR);
winch = new Talon(RobotMap.WINCH_MOTOR);
shifter = new DoubleSolenoid(RobotMap.WINCH_SHIFTER_1, RobotMap.WINCH_SHIFTER_2);
retracted = new DigitalInput(RobotMap.CATAPAULT_LIMIT_SWITCH);
latch = new Solenoid(RobotMap.CATAPULT_LATCH);
Expand Down
11 changes: 7 additions & 4 deletions org/bitbuckets/frc2014/subsystems/DriveTrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,8 @@ public void initDefaultCommand() {
* @param right The right joystick throttle. Ranges from -1(backwards) to 1(forwards).
*/
public void tankDrive(double left, double right){
throttleLeft = accelerationLimiter(throttleLeft, left, RandomConstants.MAX_TANK_CHANGE);
throttleRight = accelerationLimiter(throttleRight, right, RandomConstants.MAX_TANK_CHANGE);
throttleLeft = accelerationLimiter(throttleLeft, left * Math.abs(left), RandomConstants.MAX_TANK_CHANGE);
throttleRight = accelerationLimiter(throttleRight, right * Math.abs(right), RandomConstants.MAX_TANK_CHANGE);
drive.tankDrive(throttleLeft, throttleRight);
}

Expand All @@ -66,7 +66,7 @@ public void tankDrive(double left, double right){
public void drive(double outputMagnitude, double curve){
throttle = accelerationLimiter(throttle, outputMagnitude, RandomConstants.MAX_MAG_CHANGE);
rotation = accelerationLimiter(rotation, curve, RandomConstants.MAX_CUR_CHANGE);
drive.arcadeDrive(-throttle, -rotation);
drive.arcadeDrive(-throttle, rotation);
}

/**
Expand All @@ -79,7 +79,7 @@ public void drive(double outputMagnitude, double curve){
* @param curve The rotational power from -1 (counterclockwise) to 1 (clockwise).
*/
public void cheesyDrive(double outputMagnitude, double curve) {
if(outputMagnitude >= RandomConstants.THROTTLE_CUTOFF) {
if(Math.abs(outputMagnitude) >= RandomConstants.THROTTLE_CUTOFF) {
curve *= (RandomConstants.TURN_GAIN * Math.abs(outputMagnitude));
}

Expand Down Expand Up @@ -122,5 +122,8 @@ public double accelerationLimiter(double oldValue,
return requestedValue;
}
}
public void setWatchDogEnabled(boolean enabled) {
drive.setSafetyEnabled(enabled);
}
}

14 changes: 7 additions & 7 deletions org/bitbuckets/frc2014/subsystems/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

package org.bitbuckets.frc2014.subsystems;

import edu.wpi.first.wpilibj.Victor;
import edu.wpi.first.wpilibj.Talon;
import edu.wpi.first.wpilibj.command.Subsystem;
import edu.wpi.first.wpilibj.DoubleSolenoid;
import org.bitbuckets.frc2014.RobotMap;
Expand All @@ -19,11 +19,11 @@
*/
public class Intake extends Subsystem {
/** Top ABS intake roller driven by RS550 on a Victor */
private Victor rollerTop;
private Talon rollerTop;
/** Top ABS intake roller driven by RS550 on a Victor */
private Victor rollerLeft;
private Talon rollerLeft;
/** Top ABS intake roller driven by RS550 on a Victor */
private Victor rollerRight;
private Talon rollerRight;
/** Two double-acting cylinders to raise/lower the intake arm */
private DoubleSolenoid deployer;

Expand All @@ -32,9 +32,9 @@ public class Intake extends Subsystem {
*/
public Intake() {
super();
rollerTop = new Victor(RobotMap.TOP_ROLLER_MOTOR);
rollerLeft = new Victor(RobotMap.LEFT_ROLLER_MOTOR);
rollerRight = new Victor(RobotMap.RIGHT_ROLLER_MOTOR);
rollerTop = new Talon(RobotMap.TOP_ROLLER_MOTOR);
rollerLeft = new Talon(RobotMap.LEFT_ROLLER_MOTOR);
rollerRight = new Talon(RobotMap.RIGHT_ROLLER_MOTOR);
deployer = new DoubleSolenoid(RobotMap.INTAKE_SOLENOID_1,
RobotMap.INTAKE_SOLENOID_2);
}
Expand Down