Skip to content

Commit

Permalink
Merge branch 'master' into OI/#252-NewOC
Browse files Browse the repository at this point in the history
# Conflicts:
#	src/main/java/org/frc5687/powerup/robot/OI.java
#	src/main/java/org/frc5687/powerup/robot/commands/auto/AutoGroup.java
#	src/main/java/org/frc5687/powerup/robot/subsystems/Climber.java
  • Loading branch information
BenBernardCIS committed Apr 21, 2018
2 parents e7a7a5f + e7d269b commit 79f14a2
Show file tree
Hide file tree
Showing 57 changed files with 30,342 additions and 10,120 deletions.
315 changes: 8 additions & 307 deletions 2018-robot.iml

Large diffs are not rendered by default.

57 changes: 43 additions & 14 deletions src/main/java/org/frc5687/powerup/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,18 @@ public class Constants {
public static final double END_ALERT = 28;
public static final int HEALTH_CHECK_CYCLES = 10;

public enum typeOfTurn {
shortest,
leftOnly,
rightOnly
}

public enum DriveTrainBehavior {
bothSides,
leftOnly,
rightOnly
}


public class Lights {
// Values obtained from page 16- of http://www.revrobotics.com/content/docs/REV-11-1105-UM.pdf
Expand Down Expand Up @@ -63,6 +75,11 @@ public class Lights {
public static final double CLIMBER_HOLD = -0.89; // Party stobe
public static final double CLIMBER_DOWN = PULSING_BLUE;
public static final double TIME_WARNING = -.07;
public static final double TEST_RUNNING = 0;
public static final double TEST_WAITING = 0;

public static final double TEST_PASSED = SOLID_GREEN;
public static final double TEST_FAILED = SOLID_RED;
}
public class OI {
public static final double RUMBLE_INTENSITY = 1;
Expand Down Expand Up @@ -99,9 +116,10 @@ public class Intake {
public static final double SENSITIVITY = 0.5;
public static final long SETTLE_TIME = 1500;
public static final double PLATE_MINIMUM_CLARANCE = 24.0;
public static final double SCALE_DROP_SPEED = -0.6;
public static final double SCALE_DROP_SPEED = -0.9;
public static final double SCALE_SHOOT_SPEED = -0.70;
public static final double SWITCH_DROP_SPEED = -0.42;
public static final double SCALE_SHOOT_SPEED_SECOND_CUBE = -0.75;
public static final double SWITCH_DROP_SPEED = -0.22;

public static final double HC_MIN_SPEED = 0.1;
public static final double HC_MIN_CURRENT = 0.5;
Expand Down Expand Up @@ -143,7 +161,7 @@ public class Align {
public static final double kI = 0.0;
public static final double kD = 0.3;
public static final double TOLERANCE = 1.0; // 0.5
public static final double MINIMUM_SPEED = 0.35;
public static final double MINIMUM_SPEED = 0.5;
public static final double MAX_OUTPUT = 0;
/*
*time the angle must be on target for to be considered steady
Expand Down Expand Up @@ -178,7 +196,7 @@ public class MaxJerk {

public class TrajectoryFollowing {
public class Talon {
public static final double kP = 0.15; // Talon doesn't use kP
public static final double kP = 0.3; // Talon doesn't use kP
public static final double kI = 0.001;//02;
public static final double kD = 0.0;
public static final double kF = 0.2; // 0.28 works well
Expand Down Expand Up @@ -305,21 +323,24 @@ public class Carriage {
public static final boolean MOTOR_INVERTED = true;
public static final double HC_MIN_SPEED = 0.1; // Minimum speed to triggr the amp/isHalthy check
public class HoldSpeeds {
public static final double PAST_TOP_PROTO = 0.42;
public static final double PAST_TOP_PROTO = 0.5;
public static final double PAST_TOP_GRETA = 0.5;

public static final double PAST_NEG_20_PROTO = 0.42;
public static final double PAST_NEG_20_PROTO = 0.6;
public static final double PAST_NEG_20_GRETA = 0.5;

public static final double PAST_NEG_50_PROTO = 0.42;
public static final double PAST_NEG_50_PROTO = 0.6;
public static final double PAST_NEG_50_GRETA = 0.5;

public static final double PAST_NEG_100_PROTO = 0.42;
public static final double PAST_NEG_100_PROTO = 0.5;
public static final double PAST_NEG_100_GRETA = 0.5;

public static final double PAST_NEG_200_PROTO = 0.3;
public static final double PAST_NEG_200_PROTO = 0.42;
public static final double PAST_NEG_200_GRETA = 0.0;

public static final double PAST_NEG_300_PROTO = 0.42;
public static final double PAST_NEG_300_GRETA = 0.0;

public static final double PAST_NEG_400_PROTO = 0.2;
public static final double PAST_NEG_400_GRETA = 0.0;

Expand Down Expand Up @@ -376,6 +397,7 @@ public class HoldSpeeds {

public class Arm {
public static final double PDP_EXCESSIVE_CURRENT = 40.0;
public static final double MIN_AMPS = 3.5;

public static final boolean MOTOR_INVERTED_PROTO = false;
public static final boolean MOTOR_INVERTED_COMP = true;
Expand Down Expand Up @@ -403,7 +425,7 @@ public class Pot {
public static final double BOTTOM_COMP = 33.0;
public static final double BOTTOM_PROTO = 33.0; // TODO: Tune

public static final double INTAKE_COMP = 50.0;
public static final double INTAKE_COMP = 49.0;
public static final double INTAKE_PROTO = 47.0;

public static final double DRIVE_COMP = 41.0;
Expand All @@ -421,6 +443,7 @@ public class Pot {
public static final double DRIVE = 33.0;

public static final double SCALE = 150.0;
public static final double SCALE_MAX = 163.0;
public static final double SWITCH_HEIGHT_WITH_CARRIAGE = 100;
public static final double SWITCH_HEIGHT_BROKEN_CARRIAGE = 72; // I guess this shouldn't be lower, but I'm just removing a magic number..
public static final double switchHeightWithCarriageHalfwayUp = 91;
Expand All @@ -430,11 +453,16 @@ public class Pot {
public static final double LENGTH = 34.0;

public class HoldSpeeds {
public static final double PAST_160_CUBE_PROTO = 0.0;
public static final double PAST_160_CUBE_PROTO = 0.2;
public static final double PAST_160_CUBE_GRETA = 0.25;
public static final double PAST_160_NO_CUBE_PROTO = 0.0;
public static final double PAST_160_NO_CUBE_PROTO = 0.2;
public static final double PAST_160_NO_CUBE_GRETA = 0.25;

public static final double PAST_150_CUBE_PROTO = 0.2;
public static final double PAST_150_CUBE_GRETA = 0.25;
public static final double PAST_150_NO_CUBE_PROTO = 0.2;
public static final double PAST_150_NO_CUBE_GRETA = 0.25;

public static final double PAST_90_CUBE_PROTO = 0.0;
public static final double PAST_90_CUBE_GRETA = 0.1;
public static final double PAST_90_NO_CUBE_PROTO = 0.0;
Expand Down Expand Up @@ -486,10 +514,11 @@ public class Mode {
public static final int SCALE_THEN_SCALE = 3;
public static final int SWITCH_THEN_SWITCH = 4;
public static final int SCALE_THEN_SWITCH = 5;
public static final int SCALE_THEN_BACKOFF = 6;
public static final int SWITCH_ONLY = 7;
public static final int SCALE_ONLY = 8;
public static final int SWITCH_DRIVE = 1001;
public static final int SWITCH_ONLY = 10002;
public static final int SCALE_DRIVE = 1003;
public static final int SCALE_ONLY = 1004;
}
}
public class Limits {
Expand Down
22 changes: 16 additions & 6 deletions src/main/java/org/frc5687/powerup/robot/OI.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
import edu.wpi.first.wpilibj.buttons.JoystickButton;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import org.frc5687.powerup.robot.commands.*;
import org.frc5687.powerup.robot.commands.testing.*;
import org.frc5687.powerup.robot.commands.actions.IntakeToDrive;
import org.frc5687.powerup.robot.commands.actions.IntakeToFloor;
import org.frc5687.powerup.robot.commands.actions.IntakeToScale;
Expand Down Expand Up @@ -43,6 +44,8 @@ public class ButtonNumbers {

private JoystickButton carriageZeroEncoder;

private JoystickButton selfTest;

private JoystickButton driverArmUp;
private JoystickButton driverArmDown;
private JoystickButton driverCarriageUp;
Expand Down Expand Up @@ -118,13 +121,14 @@ public OI(Robot robot) {
operatorArmToDriveButton = new JoystickButton(operatorGamepad, Gamepad.Buttons.X.getNumber());
operatorArmToIntakeButton = new JoystickButton(operatorGamepad, Gamepad.Buttons.A.getNumber());


climberUnwind = new JoystickButton(driverGamepad, Gamepad.Buttons.BACK.getNumber());
climberWind = new JoystickButton(driverGamepad, Gamepad.Buttons.START.getNumber());

intakeLeftIn = new JoystickButton(operatorGamepad, Gamepad.Buttons.LEFT_BUMPER.getNumber());
intakeRightIn = new JoystickButton(operatorGamepad, Gamepad.Buttons.RIGHT_BUMPER.getNumber());
carriageZeroEncoder = new JoystickButton(operatorGamepad, Gamepad.Buttons.BACK.getNumber());

selfTest = new JoystickButton(operatorGamepad, Gamepad.Buttons.START.getNumber());
driverArmUp = new JoystickButton(driverGamepad, Gamepad.Buttons.RIGHT_BUMPER.getNumber());
driverArmDown = new JoystickButton(driverGamepad, Gamepad.Buttons.RIGHT_STICK.getNumber());

Expand All @@ -138,6 +142,11 @@ public double getLeftSpeed() {
return Helpers.applySensitivityFactor(speed, Constants.DriveTrain.SENSITIVITY);
}


public boolean isStartPressed(){
return operatorGamepad.getRawButton(Gamepad.Buttons.START);
}

public double getRightSpeed() {
double speed = -getSpeedFromAxis(driverGamepad, ButtonNumbers.RIGHT_AXIS);
speed = Helpers.applyDeadband(speed, Constants.DriveTrain.DEADBAND);
Expand Down Expand Up @@ -199,7 +208,7 @@ public double getCarriageSpeed() {
}

public double getArmSpeed() {
double driver = driverArmUp.get() ? -0.75 : (driverArmDown.get() ? 0.5 : 0);
double driver = driverArmUp.get() ? -0.75 : (driverArmDown.get() ? 1.0 : 0);
double operator = getSpeedFromAxis(operatorGamepad, ButtonNumbers.RIGHT_AXIS);
double speed = Helpers.absMax(operator, driver);
speed = Helpers.applySensitivityFactor(speed,Constants.Arm.SENSITIVITY);
Expand Down Expand Up @@ -258,6 +267,7 @@ private void initializeOperatorGamepad(Robot robot) {
operatorArmToSwitchButton.whenPressed(new IntakeToSwitch(robot.getCarriage(), robot.getArm()));
operatorArmToScaleButton.whenPressed(new IntakeToScale(robot.getCarriage(), robot.getArm()));

selfTest.whenPressed(new SelfTestBootstrapper(robot));
}

private void initializeConsole(Robot robot) {
Expand Down Expand Up @@ -328,18 +338,18 @@ public void updateConsole() {
leftIntakeMotorLED.set(!_robot.getIntake().isLeftMotorHealthy());
rightIntakeMotorLED.set(!_robot.getIntake().isRightMotorHealthy());

carriageMotorLED.set(_robot.getCarriage().isMotorHealthy());
carriageMotorLED.set(!_robot.getCarriage().isMotorHealthy());

armMotorLED.set(_robot.getArm().isMotorHealthy());
armMotorLED.set(!_robot.getArm().isMotorHealthy());

leftDriveEncoderLED.set(!_robot.getDriveTrain().isLeftEncoderHealthy());
rightDriveEncoderLED.set(!_robot.getDriveTrain().isRightEncoderHealthy());

intakeBackIRLED.set(!_robot.getIntake().isIRHealthy());

carriageEncoderLED.set(_robot.getCarriage().isEncoderHealthy());
carriageEncoderLED.set(!_robot.getCarriage().isEncoderHealthy());

armPotLED.set(_robot.getArm().isPotHealthy());
armPotLED.set(!_robot.getArm().isPotHealthy());

/* Code used to identify LEDs for testing. s
int pos = (int)SmartDashboard.getNumber("DB/Slider 3", 0);
Expand Down
18 changes: 14 additions & 4 deletions src/main/java/org/frc5687/powerup/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,10 +42,11 @@ public class Robot extends TimedRobot {
private DigitalInput _identityFlag;
private boolean _isCompetitionBot;
private long lastPeriod;
private int ticksPerUpdate = 5;
private int ticksPerUpdate = 20;
private int updateTick = 0;
private boolean hasRumbledForEndgame;
private boolean _manualLightFlashRequested;
private boolean abortAuton;


public Robot() {
Expand All @@ -71,20 +72,20 @@ public void robotInit() {
_arm = new Arm(oi, pdp, intake, _isCompetitionBot);
intake.setArm(_arm);
_lights = new Lights(this);
_climber = new Climber(oi, pdp, _isCompetitionBot);
_climber = new Climber(oi, pdp, intake, _isCompetitionBot);
_autoChooser = new AutoChooser(_isCompetitionBot);
SmartDashboard.putString("Identity", (_isCompetitionBot ? "Diana" : "Jitterbug"));
lastPeriod = System.currentTimeMillis();
setPeriod(1 / Constants.CYCLES_PER_SECOND);

try {
camera0 = CameraServer.getInstance().startAutomaticCapture(0);
// camera0 = CameraServer.getInstance().startAutomaticCapture(0);
} catch (Exception e) {
DriverStation.reportError(e.getMessage(), true);
}

try {
camera1 = CameraServer.getInstance().startAutomaticCapture(1);
// camera1 = CameraServer.getInstance().startAutomaticCapture(1);
} catch (Exception e) {
DriverStation.reportError(e.getMessage(), true);
}
Expand All @@ -105,6 +106,7 @@ public void robotInit() {
public Lights getLights() { return _lights; }
public JeVoisProxy getJeVoisProxy() { return jeVoisProxy; }
public LidarProxy getLidarProxy() { return lidarProxy; }
public OI getOI() { return oi; }



Expand All @@ -121,6 +123,7 @@ public void autonomousInit() {
carriage.zeroEncoder();
_manualLightFlashRequested = false;
hasRumbledForEndgame = false;
abortAuton = false;
// Reset the lights slider in case it was left on
SmartDashboard.putNumber("DB/Slider 0", 0.0);

Expand Down Expand Up @@ -193,6 +196,9 @@ public void disabledPeriodic() {
@Override
public void autonomousPeriodic() {
Scheduler.getInstance().run();
if (abortAuton && autoCommand != null) {
autoCommand.cancel();
}
}

@Override
Expand Down Expand Up @@ -287,4 +293,8 @@ public boolean isInWarningPeriod() {
public boolean isManualLightFlashRequested() {
return _manualLightFlashRequested;
}

public void requestAbortAuton() {
abortAuton = true;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,9 @@ public DriveCarriage(Carriage carriage, OI oi) {
protected void execute() {
double oiSpeed = DriverStation.getInstance().isAutonomous() ? 0 : oi.getCarriageSpeed();
if (oiSpeed != 0.0) {
carriage.disable();
if (carriage.getPIDController().isEnabled()) {
carriage.disable();
}
//DriverStation.reportError("DriveCarriage requesting oiSpeed: " + Double.toString(oiSpeed), false);
carriage.drive(oiSpeed);
} else if (!carriage.getPIDController().isEnabled()) {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
package org.frc5687.powerup.robot.commands;

import edu.wpi.first.wpilibj.command.Command;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import org.frc5687.powerup.robot.Constants;
import org.frc5687.powerup.robot.OI;
import org.frc5687.powerup.robot.subsystems.Climber;
Expand Down Expand Up @@ -31,7 +30,6 @@ protected void execute() {
} else if (_holdOn) {
speed = Constants.Climber.HOLD_SPEED;
}

climber.drive(speed);
}

Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
package org.frc5687.powerup.robot.commands;

import edu.wpi.first.wpilibj.command.Command;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import org.frc5687.powerup.robot.Constants;
import org.frc5687.powerup.robot.OI;
import org.frc5687.powerup.robot.subsystems.Intake;
Expand All @@ -24,11 +25,17 @@ protected void execute() {
double right = oi.getRightIntakeSpeed();

intake.drive(left, right);

if(intake.isEjecting()){
intake.driveServo(1);
} else{
intake.driveServo(0);
}
/*
double val = SmartDashboard.getNumber("DB/Slider 2", 0.5);
intake.driveServo(val);
*/

}

@Override
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
package org.frc5687.powerup.robot.commands;

import edu.wpi.first.wpilibj.command.CommandGroup;
import org.frc5687.powerup.robot.commands.auto.AutoWaitForDistance;
import org.frc5687.powerup.robot.commands.auto.AutoWaitForMillis;
import org.frc5687.powerup.robot.subsystems.Carriage;
import org.frc5687.powerup.robot.subsystems.DriveTrain;

public class MoveCarriageToSetpointPIDButWaitForNInchesFirst extends CommandGroup {
public MoveCarriageToSetpointPIDButWaitForNInchesFirst(DriveTrain drivetrain, Carriage carriage, int target, double inches) {
addSequential(new AutoWaitForDistance(drivetrain, inches, 5000));
addSequential(new MoveCarriageToSetpointPIDButFirstZeroIt(carriage, target));
}
}
Loading

0 comments on commit 79f14a2

Please sign in to comment.