Skip to content

Commit

Permalink
Merge branch 'master' into Auto/#297-DefensiveOpposite
Browse files Browse the repository at this point in the history
# Conflicts:
#	src/main/java/org/frc5687/powerup/robot/commands/auto/paths/FarLeftToRightScaleDeadPartTwo.java
  • Loading branch information
BenBernardCIS committed Apr 21, 2018
2 parents 0ba647e + e7d269b commit 1821d5e
Show file tree
Hide file tree
Showing 39 changed files with 20,407 additions and 6,070 deletions.
41 changes: 31 additions & 10 deletions src/main/java/org/frc5687/powerup/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,12 @@ public enum typeOfTurn {
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 @@ -69,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 @@ -108,7 +119,7 @@ public class Intake {
public static final double SCALE_DROP_SPEED = -0.9;
public static final double SCALE_SHOOT_SPEED = -0.70;
public static final double SCALE_SHOOT_SPEED_SECOND_CUBE = -0.75;
public static final double SWITCH_DROP_SPEED = -0.42;
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 @@ -188,7 +199,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 @@ -315,21 +326,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 @@ -386,6 +400,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 @@ -431,6 +446,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 @@ -440,11 +456,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 @@ -498,9 +519,9 @@ public class Mode {
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 SCALE_DRIVE = 1003;
public static final int SCALE_ONLY = 1004;
}

public class Coop {
Expand Down
16 changes: 11 additions & 5 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 @@ -44,7 +45,7 @@ public class ButtonNumbers {

private JoystickButton carriageZeroEncoder;

//private JoystickButton servoToggle;
private JoystickButton selfTest;

private JoystickButton driverArmUp;
private JoystickButton driverArmDown;
Expand All @@ -70,14 +71,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());
//servoToggle = new JoystickButton(operatorGamepad, Gamepad.Buttons.START.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 @@ -91,6 +92,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 @@ -152,7 +158,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 @@ -193,7 +199,7 @@ public void initializeButtons(Robot robot) {
operatorArmToSwitchButton.whenPressed(new IntakeToSwitch(robot.getCarriage(), robot.getArm()));
operatorArmToScaleButton.whenPressed(new IntakeToScale(robot.getCarriage(), robot.getArm()));

//servoToggle.whenPressed(new ServoToggle(robot.getIntake()));
selfTest.whenPressed(new SelfTestBootstrapper(robot));

DriverStation.reportError("driverArmToIntakeButton " + (driverArmToIntakeButton ==null), false);
DriverStation.reportError("driverArmToDriveButton " + (driverArmToDriveButton ==null), false);
Expand Down
5 changes: 3 additions & 2 deletions src/main/java/org/frc5687/powerup/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -78,13 +78,13 @@ public void robotInit() {
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 +105,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 Down
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
Expand Up @@ -37,6 +37,8 @@ public class AutoAlign extends Command implements PIDOutput {
private DriveTrain driveTrain;
private AHRS imu;

private Constants.DriveTrainBehavior _driveTrainBehavior;

private double _tolerance;

public AutoAlign(Robot robot, double angle) {
Expand Down Expand Up @@ -64,13 +66,18 @@ public AutoAlign(Robot robot, double angle, double speed, long timeout, double t
}

public AutoAlign(DriveTrain driveTrain, AHRS imu, double angle, double speed, long timeout, double tolerance) {
this(driveTrain, imu, angle, speed, timeout, tolerance, Constants.DriveTrainBehavior.bothSides);
}

public AutoAlign(DriveTrain driveTrain, AHRS imu, double angle, double speed, long timeout, double tolerance, Constants.DriveTrainBehavior driveTrainBehavior) {
requires(driveTrain);
this.angle = angle;
this.speed = speed;
this.driveTrain = driveTrain;
this.imu = imu;
_timeout = timeout;
_tolerance = tolerance;
_driveTrainBehavior = driveTrainBehavior;
}

@Override
Expand Down Expand Up @@ -126,7 +133,15 @@ private void actOnPidOut() {
if (pidOut < 0 && pidOut > -Align.MINIMUM_SPEED) {
pidOut = -Align.MINIMUM_SPEED;
}
driveTrain.setPower(pidOut, -pidOut, true); // positive output is clockwise
if (_driveTrainBehavior == Constants.DriveTrainBehavior.bothSides) {
driveTrain.setPower(pidOut, -pidOut, true); // positive output is clockwise
} else if (_driveTrainBehavior == Constants.DriveTrainBehavior.rightOnly) {
driveTrain.setLeftVelocityIPS(0);
driveTrain.setRightPower(-pidOut);
} else if (_driveTrainBehavior == Constants.DriveTrainBehavior.leftOnly) {
driveTrain.setLeftPower(pidOut);
driveTrain.setRightVelocityIPS(0);
}
}

@Override
Expand Down
Loading

0 comments on commit 1821d5e

Please sign in to comment.