Skip to content
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

New Glacier Peak Harvester #87

Open
wants to merge 7 commits into
base: master
Choose a base branch
from
Open
5 changes: 3 additions & 2 deletions src/com/spartronics4915/frc2018/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ public class Constants extends ConstantsBase
public static final int kHarvesterLeftMotorId = kUseTestbedConstants ? 18 : 8;
public static final int kHarvesterRightMotorId = kUseTestbedConstants ? 16 : 9;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

verify


public static final int kNumTalons = 8; // total talon count on robot (not testbed)
public static final int kNumTalons = 9; // total talon count on robot (not testbed)

public static final int kNumPDPs = 1; // doesn't always show up in CANProbe
public static final int kNumPCMs = 1; // Pressure control module (pneumatics)
Expand All @@ -52,7 +52,8 @@ public class Constants extends ConstantsBase
public static final int kScissorBrakeSolenoidId = 2; //PCM 0
public static final int kGrabberSetupSolenoidId = 3; //PCM 0
public static final int kGrabberSolenoidId = 4; //PCM 0
public static final int kHarvesterSolenoidId = 5; //PCM 0
public static final int kHarvesterSolenoid1Id = 5; //PCM 0
public static final int kHarvesterSolenoid2Id = 8; //PCM 0
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

verify

public static final int kClimberStabilizationSolenoidId1 = 6; //PCM 0
public static final int kClimberStabilizationSolenoidId2 = 7; //PCM 0

Expand Down
3 changes: 3 additions & 0 deletions src/com/spartronics4915/frc2018/ControlBoard.java
Original file line number Diff line number Diff line change
Expand Up @@ -114,6 +114,9 @@ public boolean readButton(Buttons b)
case HARVESTER_EJECT:
result = mButtonBoard.getRawButtonPressed(4) || mDrivestick.getRawButtonPressed(3);
break;
case HARVESTER_PARTIALLY_CLOSE:
result = mButtonBoard.getRawButtonPressed(9);
break;
case SUPERSTRUCTURE_CARRY_CUBE:
result = mButtonBoard.getRawButtonPressed(6) || mDrivestick.getRawButtonPressed(13);
break;
Expand Down
1 change: 1 addition & 0 deletions src/com/spartronics4915/frc2018/ControlBoardInterface.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@ enum Buttons
HARVESTER_OPEN,
HARVESTER_CLOSE,
HARVESTER_EJECT,
HARVESTER_PARTIALLY_CLOSE,
SUPERSTRUCTURE_CARRY_CUBE,
CLIMBER_TOGGLE,
GRABBER_FAST_OPEN,
Expand Down
50 changes: 37 additions & 13 deletions src/com/spartronics4915/frc2018/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -268,7 +268,10 @@ public void teleopInit()

mEnabledLooper.start(); // starts subsystem loopers.
mDrive.setOpenLoop(DriveSignal.NEUTRAL);

mLED.setVisionLampOn();
mLED.setBlingState(BlingState.SOLID);
mLED.setBlingState(BlingState.BLUE);
mLED.setVisionLampOff(); // Vision not used in teleop yet TODO
mLED.setVisionLampOn(); // Vision not used in teleop yet TODO
}
catch (Throwable t)
Expand Down Expand Up @@ -301,19 +304,22 @@ public void teleopPeriodic()
{
mLifter.setWantedState(ScissorLift.WantedState.OFF);
mGrabber.setWantedState(ArticulatedGrabber.WantedState.TRANSPORT);
mLED.setBlingState(BlingState.SCISSOR_OFF);
mLED.setBlingState(BlingState.SOLID);
mLED.setBlingState(BlingState.YELLOW);
}

if (mControlBoard.readButton(Buttons.SCISSOR_SWITCH))
{
mLifter.setWantedState(ScissorLift.WantedState.SWITCH);
mLED.setBlingState(BlingState.SCISSOR_SWITCH);
mLED.setBlingState(BlingState.BLINK);
mLED.setBlingState(BlingState.YELLOW);
}

if (mControlBoard.readButton(Buttons.SCISSOR_SCALE))
{
mLifter.setWantedState(ScissorLift.WantedState.SCALE);
mLED.setBlingState(BlingState.SCISSOR_SCALE);
mLED.setBlingState(BlingState.FAST_BLINK);
mLED.setBlingState(BlingState.YELLOW);
}

if (mControlBoard.readButton(Buttons.GRABBER_DROP_CUBE))
Expand All @@ -328,37 +334,51 @@ public void teleopPeriodic()
else
mGrabber.setWantedState(ArticulatedGrabber.WantedState.MANUAL_OPEN);
}

if (mControlBoard.readButton(Buttons.HARVESTER_OPEN))
{
mHarvester.setWantedState(Harvester.WantedState.OPEN);
mLED.setBlingState(BlingState.OPEN_HARVESTER);
mHarvester.setWantedState(Harvester.WantedState.FULLOPEN);
mLED.setBlingState(BlingState.SOLID);
mLED.setBlingState(BlingState.BLUE);
}

if (mControlBoard.readButton(Buttons.HARVESTER_CLOSE))
{
mHarvester.setWantedState(Harvester.WantedState.HARVEST);
mLED.setBlingState(BlingState.CLOSE_HARVESTER);
mLED.setBlingState(BlingState.BLINK);
mLED.setBlingState(BlingState.BLUE);
}

if (mControlBoard.readButton(Buttons.HARVESTER_PARTIALLY_CLOSE))
{
mHarvester.setWantedState(Harvester.WantedState.PARTIALLYCLOSE);
mLED.setBlingState(BlingState.BLINK);
mLED.setBlingState(BlingState.BLUE);
}

if (mControlBoard.readButton(Buttons.HARVESTER_EJECT))
{
mHarvester.setWantedState(Harvester.WantedState.EJECT);
mLED.setBlingState(BlingState.EJECT_HARVESTER);
mLED.setBlingState(BlingState.FAST_BLINK);
mLED.setBlingState(BlingState.BLUE);
}

if (mControlBoard.readButton(Buttons.SUPERSTRUCTURE_CARRY_CUBE))
{
mSuperstructure.setWantedState(Superstructure.WantedState.TRANSFER_CUBE_TO_GRABBER);
mLED.setBlingState(BlingState.CARRY_CUBE);
mLED.setBlingState(BlingState.BLINK);
mLED.setBlingState(BlingState.GREEN);
}

if (mControlBoard.readButton(Buttons.CLIMBER_TOGGLE))
{
mSuperstructure.setWantedState(Superstructure.WantedState.CLIMB);
mLED.setBlingState(BlingState.SOLID);
mLED.setBlingState(BlingState.RED);
if (mClimber.getWantedState() == Climber.WantedState.CLIMB)
{
mClimber.setWantedState(Climber.WantedState.HOLD);
mLED.setBlingState(BlingState.STOP_CLIMBER);
// mLED.setBlingState(BlingState.STOP_CLIMBER);
}
else
{
Expand All @@ -369,6 +389,9 @@ public void teleopPeriodic()

if (mControlBoard.readButton(Buttons.GRABBER_FAST_OPEN))
{
mClimber.setWantedState(Climber.WantedState.HOLD);
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

dont set climber state

mLED.setBlingState(BlingState.BLINK);
mLED.setBlingState(BlingState.RED);
mGrabber.setWantedState(ArticulatedGrabber.WantedState.FAST_OPENED);
}

Expand Down Expand Up @@ -415,6 +438,7 @@ else if (SmartDashboard.getString("CameraView", "").equals("LiftCam"))
mGrabber.setWantedState(ArticulatedGrabber.WantedState.PREPARE_INTAKE);
}


// Drive control buttons
if (mControlBoard.readButton(Buttons.VISION_CUBE_HARVEST))
{
Expand All @@ -428,14 +452,14 @@ else if (SmartDashboard.getString("CameraView", "").equals("LiftCam"))
}

// Bling settings
if (DriverStation.getInstance().getMatchTime() < kMatchDurationSeconds)
/* if (DriverStation.getInstance().getMatchTime() < kMatchDurationSeconds)
{
mLED.setBlingState(BlingState.TELEOP);
}
if (DriverStation.getInstance().getMatchTime() < kEndgameDurationSeconds)
{
mLED.setBlingState(BlingState.ENDGAME);
}
} */
allButTestPeriodic();
}
catch (Throwable t)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ else if (Util.getGameSpecificMessage().charAt(0) == 'R')
if (Util.getGameSpecificMessage().charAt(0) == 'R') // TODO: Add a way to pick up a second cube if we went to the scale
{
PathContainer secondPath = new DriveSecondCubeToCScalePath();
runAction(new ParallelAction(new SeriesAction(new WaitForPathMarkerAction("openharvester"), new ActuateHarvesterAction(Harvester.WantedState.OPEN)),
runAction(new ParallelAction(new SeriesAction(new WaitForPathMarkerAction("openharvester"), new ActuateHarvesterAction(Harvester.WantedState.PARTIALLYCLOSE)),
new DrivePathAction(new DriveReverseToSecondCubeFromCSwitchPath())));
runAction(new TurnToHeadingAction(Rotation2d.fromDegrees(180)));
runAction(new ParallelAction(new SeriesAction(new WaitForPathMarkerAction("aquirecube"), new ForceEndPathAction()),
Expand Down
Loading