Skip to content
This repository has been archived by the owner on Sep 11, 2018. It is now read-only.

Commit

Permalink
Merge branch 'release/v0.0.6'
Browse files Browse the repository at this point in the history
  • Loading branch information
edwanvi committed Apr 21, 2017
2 parents 220ed75 + 2e6693b commit 3a3f5f0
Show file tree
Hide file tree
Showing 214 changed files with 2,236 additions and 11,851 deletions.
108 changes: 81 additions & 27 deletions 3494_2017_repo/src/org/usfirst/frc/team3494/robot/AutoGenerator.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,83 +5,137 @@
import org.usfirst.frc.team3494.robot.commands.auto.DistanceDrive;
import org.usfirst.frc.team3494.robot.commands.auto.PIDAngleDrive;
import org.usfirst.frc.team3494.robot.commands.auto.PIDFullDrive;
import org.usfirst.frc.team3494.robot.commands.auto.SetGearGrasp;
import org.usfirst.frc.team3494.robot.commands.auto.XYDrive;
import org.usfirst.frc.team3494.robot.commands.gears.ToggleGearRamp;

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

/**
* Class containing methods that return valid lists to pass to
* {@link org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto}.
*
*
* @since 0.0.3
* @see org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto
*/
public class AutoGenerator {
/**
* The distance of the first pull in gear placing.
*/
private static final double FIRST_PULL = 101.5 - 35.5 - 17.75 - 5.5;
/**
* The angle to turn after the first pull in gear placing.
*/
private static final double ANGLE = 60;
/**
* After turning {@link AutoGenerator#ANGLE} degrees, drive this distance.
*/
private static final double SECOND_PULL = 35 - 17.75;

/**
* Test method. Drives to XY (36, 36) (inches).
*
*
* @since 0.0.3
* @see org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto
* @see org.usfirst.frc.team3494.robot.commands.auto.XYDrive
* @return A list of commands suitable for use with
* {@link org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto}.
*/
public static ArrayList<Command> autoOne() {
ArrayList<Command> list = new ArrayList<Command>();
ArrayList<Command> list = new ArrayList<>();
list.add(new XYDrive(36, 36));
return list;
}

/**
* Drives to the baseline and earns us five points (hopefully.)
*
* Drives to the baseline.
*
* @see org.usfirst.frc.team3494.robot.commands.auto.DistanceDrive
* @since 0.0.3
* @return A list of commands suitable for use with
* {@link org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto}.
*/
public static ArrayList<Command> crossBaseLine() {
ArrayList<Command> list = new ArrayList<Command>();
list.add(new DistanceDrive(-72, UnitTypes.INCHES));
ArrayList<Command> list = new ArrayList<>();
list.add(new DistanceDrive(72, UnitTypes.INCHES));
return list;
}

public static ArrayList<Command> placeCenterGear() {
ArrayList<Command> list = new ArrayList<Command>();
list.add(new PIDFullDrive(110.5));
ArrayList<Command> list = new ArrayList<>();
list.add(new PIDFullDrive(110.75));
return list;
}

public static ArrayList<Command> gearPlaceAttempt() {
ArrayList<Command> list = new ArrayList<Command>();
list.add(new PIDFullDrive(87.5));
list.add(new PIDAngleDrive(65));
list.add(new PIDFullDrive(54));
/**
* Drives forward, turns right, drives forward again.
*
* @see org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto
* Constructed Auto
* @return A list for use with
* {@link org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto
* ConstructedAuto}
*/
public static ArrayList<Command> gearPassiveRight() {
ArrayList<Command> list = new ArrayList<>();
list.add(new PIDFullDrive(FIRST_PULL));
list.add(new PIDAngleDrive(ANGLE));
list.add(new PIDFullDrive(SECOND_PULL));
// list.add(new DistanceDrive(-60, UnitTypes.INCHES));
return list;
}

public static ArrayList<Command> gearPlaceAttemptLeft() {
ArrayList<Command> list = new ArrayList<Command>();
list.add(new PIDFullDrive(87.5));
list.add(new PIDAngleDrive(-65));
list.add(new PIDFullDrive(54));
/**
* Drives forward, turns left, drives forward again.
*
* @see org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto
* Constructed Auto
* @return A list for use with
* {@link org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto
* ConstructedAuto}
*/
public static ArrayList<Command> gearPassiveLeft() {
ArrayList<Command> list = new ArrayList<>();
list.add(new PIDFullDrive(FIRST_PULL));
list.add(new PIDAngleDrive(-ANGLE));
list.add(new PIDFullDrive(SECOND_PULL));
// list.add(new DistanceDrive(-60, UnitTypes.INCHES));
return list;
}


/**
* Same as {@link AutoGenerator#gearPassiveLeft()}, but drops the gear on
* the peg at the end.
*
* @see org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto
* Constructed Auto
* @return A list for use with
* {@link org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto
* ConstructedAuto}
*/
public static ArrayList<Command> activeLeftGear() {
ArrayList<Command> list = AutoGenerator.gearPlaceAttemptLeft();
list.add(new ToggleGearRamp());
list.add(new PIDFullDrive(10));
ArrayList<Command> list = AutoGenerator.gearPassiveLeft();
list.add(new SetGearGrasp(Value.kForward));
list.add(new PIDFullDrive(-10));
list.add(new SetGearGrasp(Value.kReverse));
return list;
}


/**
* Same as {@link AutoGenerator#gearPassiveRight()}, but drops the gear on
* the peg at the end.
*
* @see org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto
* Constructed Auto
* @return A list for use with
* {@link org.usfirst.frc.team3494.robot.commands.auto.ConstructedAuto
* ConstructedAuto}
*/
public static ArrayList<Command> activeGearRight() {
ArrayList<Command> list = AutoGenerator.gearPlaceAttempt();
list.add(new ToggleGearRamp());
ArrayList<Command> list = AutoGenerator.gearPassiveRight();
list.add(new SetGearGrasp(Value.kForward));
list.add(new PIDFullDrive(-10));
list.add(new SetGearGrasp(Value.kReverse));
return list;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

/**
* Enum of directions to drive in.
*
*
* @since 0.0.0
*/
public enum DriveDirections {
Expand Down
23 changes: 9 additions & 14 deletions 3494_2017_repo/src/org/usfirst/frc/team3494/robot/OI.java
Original file line number Diff line number Diff line change
@@ -1,15 +1,13 @@
package org.usfirst.frc.team3494.robot;

import org.usfirst.frc.team3494.robot.commands.auto.DistanceDrive;
import org.usfirst.frc.team3494.robot.commands.climb.Climb;
import org.usfirst.frc.team3494.robot.commands.climb.ClimberToggle;
import org.usfirst.frc.team3494.robot.commands.climb.ClimberPTOSetter;
import org.usfirst.frc.team3494.robot.commands.climb.StopClimber;
import org.usfirst.frc.team3494.robot.commands.drive.HoldDriveTrain;
import org.usfirst.frc.team3494.robot.commands.gears.HoldInState_Forward;
import org.usfirst.frc.team3494.robot.commands.gears.SetReverse;
import org.usfirst.frc.team3494.robot.commands.gears.SetHolderState;
import org.usfirst.frc.team3494.robot.commands.gears.ToggleGearRamp;
import org.usfirst.frc.team3494.robot.commands.turret.Shoot;

import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.buttons.JoystickButton;
Expand Down Expand Up @@ -52,7 +50,7 @@ public class OI {
public JoystickButton xbox_a = new JoystickButton(xbox, 1);
public JoystickButton xbox_a_2 = new JoystickButton(xbox_2, 1);

public JoystickButton xbox_lt = new JoystickButton(xbox, 5);
public JoystickButton xbox_lt_2 = new JoystickButton(xbox_2, 5);

public JoystickButton xbox_rt = new JoystickButton(xbox, 6);
public JoystickButton xbox_rt_2 = new JoystickButton(xbox_2, 6);
Expand All @@ -71,22 +69,19 @@ public class OI {

public OI() {
// Ready Player One
xbox_a.whenPressed(new DistanceDrive(-12, UnitTypes.INCHES));
// Ready Player Two
// Climb controls
xbox_a_2.whileActive(new Climb(DriveDirections.UP));
xbox_a_2.whenReleased(new StopClimber());

xbox_b_2.whenPressed(new SetReverse());
xbox_b_2.whileHeld(new HoldDriveTrain());

xbox_x_2.whileHeld(new HoldInState_Forward());
xbox_x_2.whenPressed(new SetHolderState(Value.kForward));
xbox_x_2.whenReleased(new SetHolderState(Value.kReverse));

xbox_y_2.whenPressed(new ToggleGearRamp());

xbox_rt_2.whenPressed(new Shoot());
xbox_rt_2.whenReleased(new Shoot(0));

xbox_select_2.whenPressed(new ClimberToggle());
xbox_start_2.whileHeld(new HoldDriveTrain());
xbox_lt_2.whenPressed(new ClimberPTOSetter(true));
xbox_rt_2.whenPressed(new ClimberPTOSetter(false));
}
}
Loading

0 comments on commit 3a3f5f0

Please sign in to comment.