Skip to content

Commit

Permalink
Merge pull request #61 from jamesdooley4/master
Browse files Browse the repository at this point in the history
Cleanup robot map & fix crashing errors during robot startup
  • Loading branch information
OroArmor authored Feb 23, 2020
2 parents fd47780 + 16d803f commit 8705f0a
Show file tree
Hide file tree
Showing 13 changed files with 229 additions and 265 deletions.
3 changes: 0 additions & 3 deletions src/main/java/frc/team2412/robot/OI.java
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,6 @@ public class OI {
public Joystick codriverStick = new Joystick(CODRIVER_STICK_PORT);

// Buttons
public Button exampleSubsystemMethod = new JoystickButton(driverStick, 1);
public Button indexerShootButton = new JoystickButton(driverStick, 2);
public Button indexerStopButton = new JoystickButton(driverStick, 3);

Expand Down Expand Up @@ -101,8 +100,6 @@ public class OI {

// Constructor to set all of the commands and buttons
public OI(RobotContainer robotContainer) {
// telling the button that when its pressed to execute example command with the
// robot container's instance of example subsystem

// LIFT
liftUpButton.whenPressed(new LiftUpCommand(robotContainer.m_liftSubsystem));
Expand Down
7 changes: 7 additions & 0 deletions src/main/java/frc/team2412/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -92,6 +92,13 @@ public void autonomousInit() {
@Override
public void autonomousPeriodic() {
}

/**
* This function is called once when autonomous is started
*/
@Override
public void teleopInit() {
}

/**
* This function is called periodically during operator control.
Expand Down
1 change: 1 addition & 0 deletions src/main/java/frc/team2412/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,7 @@ public RobotContainer() {

m_controlPanelColorSubsystem = new ControlPanelColorSubsystem(RobotMap.colorSensor, RobotMap.colorSensorMotor);

m_LimelightSubsystem = new LimelightSubsystem(RobotMap.limelight);
m_turretSubsystem = new TurretSubsystem(RobotMap.turretMotor, m_LimelightSubsystem);

m_flywheelSubsystem = new FlywheelSubsystem(RobotMap.flywheelLeftMotor, RobotMap.flywheelRightMotor);
Expand Down
173 changes: 100 additions & 73 deletions src/main/java/frc/team2412/robot/RobotMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -29,9 +29,77 @@
//remember to declare robot container at the bottom of this class
public class RobotMap {

public static enum CANBus {
INTAKE1(11),
INDEX1(12),
INTAKE2(21),
INDEX2(22),
INTAKE3(31),
INDEX3(32),
INDEX_MID(40),
DRIVE_LEFT_FRONT(1),
DRIVE_LEFT_BACK(2),
DRIVE_RIGHT_FRONT(3),
DRIVE_RIGHT_BACK(4),
CLIMB1(5),
CLIMB2(6),
TURRET(7),
FLYWHEEL_LEFT(8),
FLYWHEEL_RIGHT(9),
CONTROL_PANEL(10);

public final int id;
private CANBus(int canBusId) {
id = canBusId;
}
}

public static enum PneumaticPort {
DRIVE(0),
CLIMB_LEFT(1),
CLIMB_RIGHT(2),
INTAKE_FRONT_UP(3),
INTAKE_BACK_UP(4),
LIFT_UP(5),
LIFT_DOWN(6);

public final int id;
private PneumaticPort(int pneumaticPortId) {
id = pneumaticPortId;
}
}

public static enum DIOPort {
BACK_SENSOR(6),
BACK_MID_SENSOR(5),
BACK_INNER_SENSOR(4),
FRONT_INNER_SENSOR(3),
FRONT_MID_SENSOR(2),
FRONT_SENSOR(1),
INTAKE_FRONT_SENSOR(0),
INTAKE_BACK_SENSOR(7);

public final int id;
private DIOPort(int dioPortId) {
id = dioPortId;
}
}

public static enum PWMPort {
HOOD_SERVO_1(0),
HOOD_SERVO_2(1);

public final int id;
private PWMPort(int pwmPortId) {
id = pwmPortId;
}
}

//CHOICE FOR INDEX/INTAKE MODULE
public static enum IndexIntakeModule{
ONE(11, 12), TWO(21, 22), THREE(31, 32);
ONE(CANBus.INTAKE1.id, CANBus.INDEX1.id),
TWO(CANBus.INTAKE2.id, CANBus.INDEX2.id),
THREE(CANBus.INTAKE3.id, CANBus.INDEX3.id);
private int indexCANID, intakeCANID;
IndexIntakeModule(int intakeID, int indexID){
indexCANID = indexID;
Expand All @@ -54,19 +122,12 @@ public int getIndexCANID(){

// DRIVEBASE SUBSYSTEM
// -------------------------------------------------------------------------
// DriveBase Motor ports
public static final int DRIVE_LEFT_FRONT_ID = 14;
public static final int DRIVE_LEFT_BACK_ID = 15;
public static final int DRIVE_RIGHT_FRONT_ID = 1;
public static final int DRIVE_RIGHT_BACK_ID = 0;

private static final int DRIVE_SOLENOID_PORT = 0;

// DriveBase Motors
public static WPI_TalonFX driveLeftFront = new WPI_TalonFX(DRIVE_LEFT_FRONT_ID);
public static WPI_TalonFX driveLeftBack = new WPI_TalonFX(DRIVE_LEFT_BACK_ID);
public static WPI_TalonFX driveRightFront = new WPI_TalonFX(DRIVE_RIGHT_FRONT_ID);
public static WPI_TalonFX driveRightBack = new WPI_TalonFX(DRIVE_RIGHT_BACK_ID);
public static WPI_TalonFX driveLeftFront = new WPI_TalonFX(CANBus.DRIVE_LEFT_FRONT.id);
public static WPI_TalonFX driveLeftBack = new WPI_TalonFX(CANBus.DRIVE_LEFT_BACK.id);
public static WPI_TalonFX driveRightFront = new WPI_TalonFX(CANBus.DRIVE_RIGHT_FRONT.id);
public static WPI_TalonFX driveRightBack = new WPI_TalonFX(CANBus.DRIVE_RIGHT_BACK.id);

// DriveBase SpeedControllerGroups
public static SpeedControllerGroup driveLeftSide = new SpeedControllerGroup(driveLeftFront, driveLeftBack);
Expand All @@ -79,48 +140,33 @@ public int getIndexCANID(){
public static ADXRS450_Gyro driveGyro = new ADXRS450_Gyro();

// DriveBase Solenoid
public static Solenoid driveSolenoid = new Solenoid(DRIVE_SOLENOID_PORT);
public static Solenoid driveSolenoid = new Solenoid(PneumaticPort.DRIVE.id);


// climb Pneumatics
private static final int pneumatic1Open = 1;
private static final int pneumatic2Open = 3;
public static Solenoid climbLeftPneumatic = new Solenoid(pneumatic1Open);
public static Solenoid climbRightPneumatic = new Solenoid(pneumatic2Open);
public static Solenoid climbLeftPneumatic = new Solenoid(PneumaticPort.CLIMB_LEFT.id);
public static Solenoid climbRightPneumatic = new Solenoid(PneumaticPort.CLIMB_RIGHT.id);

// Motors
private static final int climbMotor1 = 1;
private static final int climbMotor2 = 2;
public static CANSparkMax leftClimbMotor = new CANSparkMax(climbMotor1, MotorType.kBrushless);
public static CANSparkMax rightClimbMotor = new CANSparkMax(climbMotor2, MotorType.kBrushless);
public static CANSparkMax leftClimbMotor = new CANSparkMax(CANBus.CLIMB1.id, MotorType.kBrushless);
public static CANSparkMax rightClimbMotor = new CANSparkMax(CANBus.CLIMB2.id, MotorType.kBrushless);

// INDEX SUBSYSTEM
// ---------------------------------------------------------------------------
// IDs
private final static int indexMidMotorID = 3;

private final static int backSensorID = 6;
private final static int backMidSensorID = 5;
private final static int backInnerSensorID = 4;
private final static int frontInnerSensorID = 3;
private final static int frontMidSensorID = 2;
private final static int frontSensorID = 1;
private final static int intakeFrontSensorID = 0;
private final static int intakeBackSensorID = 7;

// motors
public static CANSparkMax indexFrontMotor, indexBackMotor;
public static CANSparkMax indexMidMotor = new CANSparkMax(indexMidMotorID, MotorType.kBrushless);
public static CANSparkMax indexMidMotor = new CANSparkMax(CANBus.INDEX_MID.id, MotorType.kBrushless);

public static CANSparkMax intakeFrontMotor, intakeBackMotor;

// sensors
public static DigitalInput back = new DigitalInput(backSensorID);
public static DigitalInput backMid = new DigitalInput(backMidSensorID);
public static DigitalInput backInner = new DigitalInput(backInnerSensorID);
public static DigitalInput frontInner= new DigitalInput(frontInnerSensorID);
public static DigitalInput frontMid = new DigitalInput(frontMidSensorID);
public static DigitalInput front = new DigitalInput(frontSensorID);
public static DigitalInput back = new DigitalInput(DIOPort.BACK_SENSOR.id);
public static DigitalInput backMid = new DigitalInput(DIOPort.BACK_MID_SENSOR.id);
public static DigitalInput backInner = new DigitalInput(DIOPort.BACK_INNER_SENSOR.id);
public static DigitalInput frontInner= new DigitalInput(DIOPort.FRONT_INNER_SENSOR.id);
public static DigitalInput frontMid = new DigitalInput(DIOPort.FRONT_MID_SENSOR.id);
public static DigitalInput front = new DigitalInput(DIOPort.FRONT_SENSOR.id);

private static class IndexIntakeSelector {
IndexIntakeSelector() {
Expand Down Expand Up @@ -149,49 +195,31 @@ private CANSparkMax tryGetMotor(int motorId) {
public static IndexIntakeSelector indexSelector = new IndexIntakeSelector();

// INDEXER CONTROLS THESE NOT INTAKE FYI
public static DigitalInput intakeFront = new DigitalInput(intakeFrontSensorID);
public static DigitalInput intakeBack = new DigitalInput(intakeBackSensorID);
public static final int exampleID = 1;
public static DigitalInput intakeFront = new DigitalInput(DIOPort.INTAKE_FRONT_SENSOR.id);
public static DigitalInput intakeBack = new DigitalInput(DIOPort.INTAKE_BACK_SENSOR.id);

// Turret Subsystem
// ------------------------------------------------------------------------------
public static final int turretMotorID = 1;
public static WPI_TalonSRX turretMotor = new WPI_TalonSRX(turretMotorID);
public static WPI_TalonSRX turretMotor = new WPI_TalonSRX(CANBus.TURRET.id);

// Flywheel subsystem
// Flywheel Subsystem
// ------------------------------------------------------------------------------
public static final int flywheelLeftMotorID = 0;
public static final int flywheelRightMotorID = 2;

public static CANSparkMax flywheelLeftMotor = new CANSparkMax(flywheelLeftMotorID, MotorType.kBrushless);
public static CANSparkMax flywheelRightMotor = new CANSparkMax(flywheelRightMotorID, MotorType.kBrushless);
public static CANSparkMax flywheelLeftMotor = new CANSparkMax(CANBus.FLYWHEEL_LEFT.id, MotorType.kBrushless);
public static CANSparkMax flywheelRightMotor = new CANSparkMax(CANBus.FLYWHEEL_RIGHT.id, MotorType.kBrushless);

// Hood Subsystem
// -----------------------------------------------------------------------------
public static final int HOOD_SERVO_PORT_1 = 0;
public static final int HOOD_SERVO_PORT_2 = 1;
public static Servo hoodServo1 = new Servo(HOOD_SERVO_PORT_1);
public static Servo hoodServo2 = new Servo(HOOD_SERVO_PORT_2);
public static Servo hoodServo1 = new Servo(PWMPort.HOOD_SERVO_1.id);
public static Servo hoodServo2 = new Servo(PWMPort.HOOD_SERVO_2.id);

// INTAKE SUBSYSTEM

// Intake DoubleSolenoid Ports
public static final int INTAKE_FRONT_UP_PORT = 1;
public static final int INTAKE_FRONT_DOWN_PORT = 1;
public static final int INTAKE_BACK_UP_PORT = 1;
public static final int INTAKE_BACK_DOWN_PORT = 1;

public static Solenoid frontIntakeliftSolenoid = new Solenoid(INTAKE_FRONT_UP_PORT);
public static Solenoid backIntakeLiftSolenoid = new Solenoid(INTAKE_BACK_UP_PORT);


// LIFT SUBSYSTEM
// Intake Subsystem
// -------------------------------------------------------------------------------
// Lift DoubleSolenoid Ports
public static final int LIFT_UP_PORT = 1;
public static final int LIFT_DOWN_PORT = 1;
public static Solenoid frontIntakeliftSolenoid = new Solenoid(PneumaticPort.INTAKE_FRONT_UP.id);
public static Solenoid backIntakeLiftSolenoid = new Solenoid(PneumaticPort.INTAKE_BACK_UP.id);

public static DoubleSolenoid liftUpDown = new DoubleSolenoid(LIFT_UP_PORT, LIFT_DOWN_PORT);
// Lift Subsystem
// -------------------------------------------------------------------------------
public static DoubleSolenoid liftUpDown = new DoubleSolenoid(PneumaticPort.LIFT_UP.id, PneumaticPort.LIFT_DOWN.id);

// CONTROL PANEL SUBSYSTEM
// ----------------------------------------------------------------------
Expand All @@ -201,8 +229,7 @@ private CANSparkMax tryGetMotor(int motorId) {
public static ColorSensorV3 colorSensor = new ColorSensorV3(COLOR_SESNOR_PORT);
public static ColorMatch colorMatcher = new ColorMatch();

public static final int CONTROL_PANEL_MOTOR_PORT = 1;
public static WPI_TalonFX colorSensorMotor = new WPI_TalonFX(CONTROL_PANEL_MOTOR_PORT);
public static WPI_TalonFX colorSensorMotor = new WPI_TalonFX(CANBus.CONTROL_PANEL.id);

// Limelight subsystem
// ----------------------------------------------------------------------------------------------
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,12 @@ public class DriveCommand extends CommandBase {
private Joystick m_joystick2;
private Button m_button;

public DriveCommand(DriveBaseSubsystem driveBaseSubsystem, Joystick joystick, Joystick joystick2, Button button) {
public DriveCommand(DriveBaseSubsystem driveBaseSubsystem, Joystick joystick, Joystick joystick2, Button indexerShootButton) {
addRequirements(driveBaseSubsystem);
this.m_driveBaseSubsystem = driveBaseSubsystem;
this.m_joystick = joystick;
m_joystick2 = joystick2;
m_button = button;
m_button = indexerShootButton;
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,18 +5,10 @@
import frc.team2412.robot.subsystems.IntakeUpDownSubsystem;

public class IntakeBackBothOffCommandGroup extends ParallelCommandGroup {

private IntakeUpDownSubsystem m_intakeUpDownSubsystem;
private IntakeOnOffSubsystem m_intakeOnOffSubsystem;

public IntakeBackBothOffCommandGroup(IntakeUpDownSubsystem intakeUpDownSubsystem,
IntakeOnOffSubsystem intakeOnOffSubsystem) {
addRequirements(intakeUpDownSubsystem, intakeOnOffSubsystem);
m_intakeUpDownSubsystem = intakeUpDownSubsystem;
m_intakeOnOffSubsystem = intakeOnOffSubsystem;

addCommands(new IntakeBackDownCommand(m_intakeUpDownSubsystem),
new IntakeBackOffCommand(m_intakeOnOffSubsystem));
addCommands(new IntakeBackDownCommand(intakeUpDownSubsystem),
new IntakeBackOffCommand(intakeOnOffSubsystem));
}

}
Original file line number Diff line number Diff line change
Expand Up @@ -5,17 +5,10 @@
import frc.team2412.robot.subsystems.IntakeUpDownSubsystem;

public class IntakeBackBothOnCommandGroup extends ParallelCommandGroup {

private IntakeUpDownSubsystem m_intakeUpDownSubsystem;
private IntakeOnOffSubsystem m_intakeOnOffSubsystem;

public IntakeBackBothOnCommandGroup(IntakeUpDownSubsystem intakeUpDownSubsystem,
IntakeOnOffSubsystem intakeOnOffSubsystem) {
addRequirements(intakeUpDownSubsystem, intakeOnOffSubsystem);
m_intakeUpDownSubsystem = intakeUpDownSubsystem;
m_intakeOnOffSubsystem = intakeOnOffSubsystem;

addCommands(new IntakeBackUpCommand(m_intakeUpDownSubsystem), new IntakeBackOnCommand(m_intakeOnOffSubsystem));
addCommands(new IntakeBackUpCommand(intakeUpDownSubsystem),
new IntakeBackOnCommand(intakeOnOffSubsystem));
}

}
Original file line number Diff line number Diff line change
Expand Up @@ -5,18 +5,10 @@
import frc.team2412.robot.subsystems.IntakeUpDownSubsystem;

public class IntakeFrontBothOffCommandGroup extends ParallelCommandGroup {

private IntakeUpDownSubsystem m_intakeUpDownSubsystem;
private IntakeOnOffSubsystem m_intakeOnOffSubsystem;

public IntakeFrontBothOffCommandGroup(IntakeUpDownSubsystem intakeUpDownSubsystem,
IntakeOnOffSubsystem intakeOnOffSubsystem) {
addRequirements(intakeUpDownSubsystem, intakeOnOffSubsystem);
m_intakeUpDownSubsystem = intakeUpDownSubsystem;
m_intakeOnOffSubsystem = intakeOnOffSubsystem;

addCommands(new IntakeFrontDownCommand(m_intakeUpDownSubsystem),
new IntakeFrontOffCommand(m_intakeOnOffSubsystem));
addCommands(new IntakeFrontDownCommand(intakeUpDownSubsystem),
new IntakeFrontOffCommand(intakeOnOffSubsystem));
}

}
Original file line number Diff line number Diff line change
Expand Up @@ -5,18 +5,10 @@
import frc.team2412.robot.subsystems.IntakeUpDownSubsystem;

public class IntakeFrontBothOnCommandGroup extends ParallelCommandGroup {

private IntakeUpDownSubsystem m_intakeUpDownSubsystem;
private IntakeOnOffSubsystem m_intakeOnOffSubsystem;

public IntakeFrontBothOnCommandGroup(IntakeUpDownSubsystem intakeUpDownSubsystem,
IntakeOnOffSubsystem intakeOnOffSubsystem) {
addRequirements(intakeUpDownSubsystem, intakeOnOffSubsystem);
m_intakeUpDownSubsystem = intakeUpDownSubsystem;
m_intakeOnOffSubsystem = intakeOnOffSubsystem;

addCommands(new IntakeFrontUpCommand(m_intakeUpDownSubsystem),
new IntakeFrontOnCommand(m_intakeOnOffSubsystem));
addCommands(new IntakeFrontUpCommand(intakeUpDownSubsystem),
new IntakeFrontOnCommand(intakeOnOffSubsystem));
}

}
Original file line number Diff line number Diff line change
Expand Up @@ -413,4 +413,4 @@ public Command getMoveFromPowerCellPathFromPathWeaverCommand() {

}

}
}
Original file line number Diff line number Diff line change
Expand Up @@ -44,4 +44,4 @@ private ClimbState(boolean value) {
public static final InterUnitRatio<RotationUnits, DistanceUnits> MOTOR_REVOLUTIONS_TO_INCHES = new InterUnitRatio<RotationUnits, DistanceUnits>(
RotationUnits.ROTATION, 1, DistanceUnits.INCH);

}
}
Loading

0 comments on commit 8705f0a

Please sign in to comment.