Skip to content

Commit

Permalink
Merge pull request #314 from frc5687/All/#305-SelfTestFramework
Browse files Browse the repository at this point in the history
All/#305 self test framework
  • Loading branch information
BenBernardCIS authored Apr 21, 2018
2 parents 3884fa7 + b8cfb4e commit e7d269b
Show file tree
Hide file tree
Showing 14 changed files with 759 additions and 7 deletions.
6 changes: 6 additions & 0 deletions src/main/java/org/frc5687/powerup/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -75,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 @@ -392,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
14 changes: 10 additions & 4 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 @@ -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
@@ -0,0 +1,83 @@
package org.frc5687.powerup.robot.commands.testing;

import edu.wpi.first.wpilibj.command.Command;
import org.frc5687.powerup.robot.Constants;
import org.frc5687.powerup.robot.RobotMap;
import org.frc5687.powerup.robot.subsystems.Arm;
import org.frc5687.powerup.robot.subsystems.Carriage;
import org.frc5687.powerup.robot.utils.PDP;
import org.frc5687.powerup.robot.commands.MoveCarriageToSetpointPID;
import edu.wpi.first.wpilibj.DriverStation;

import static java.lang.Math.abs;


public class ArmMotorTest extends Command {
private Arm arm;
private Carriage carriage;
private PDP pdp;
private long upMillis;
private long downMillis;
private long stopMillis;
private boolean finished;
private double amps;
private double bottomAngle;
private double topAngle;
private double startAngle;

public ArmMotorTest(Arm arm, Carriage carriage){
requires(arm);
requires(carriage);

this.arm = arm;
this.carriage = carriage;
}

@Override
protected void initialize() {
finished = false;
upMillis = System.currentTimeMillis() + 125;
stopMillis = System.currentTimeMillis() + 250;
downMillis = System.currentTimeMillis() + 375;
amps = 0;
topAngle = 0;
startAngle = arm.getAngle();
}

@Override
protected void execute() {
if (System.currentTimeMillis()< upMillis){
arm.drive(0.75);
amps = Math.max(amps, pdp.getCurrent(RobotMap.PDP.ARM_SP));
topAngle = Math.max(topAngle, arm.getAngle());

}
else if (System.currentTimeMillis()< stopMillis){
arm.drive(0);
bottomAngle = topAngle;
}
else {
arm.drive(-0.75);
amps = Math.max(amps, pdp.getCurrent(RobotMap.PDP.ARM_SP));
bottomAngle = Math.min(bottomAngle, arm.getAngle());
}
}

@Override
protected void end() {
if (amps < Constants.Arm.MIN_AMPS) {
DriverStation.reportError(amps + " amps drawn", false);
}
if (abs(startAngle - topAngle) < 20) {
DriverStation.reportError("angle change " + (startAngle - topAngle), false);
}
if (abs(topAngle - bottomAngle) > 20) {
DriverStation.reportError("angle change " + (bottomAngle - topAngle), false);
}
}

@Override
public boolean isFinished() {
return System.currentTimeMillis() > downMillis;
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
package org.frc5687.powerup.robot.commands.testing;

import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.command.Command;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

import org.frc5687.powerup.robot.OI;
/**
* Command to prompt the operator to confirm a result using the gamepad buttons.
*/
public class ConfirmTest extends Command {

private String _message;
private String _success;
private String _failure;
private boolean _clear;
private String _key;
private OI _oi;

public ConfirmTest(OI oi, String message, String success, String failure) {
_oi = oi;
_message = message;
_success = success;
_failure = failure;
_clear = false;
}

public ConfirmTest(OI oi, String message, String key) {
_oi = oi;
_message = message;
_key = key;
_clear = false;
}

@Override
protected void initialize() {
DriverStation.reportError(_message, false);
SmartDashboard.putString("SelfTest/Message", _message);
}

@Override
protected void execute() {
if (!_clear) {
_clear = !_oi.isStartPressed();
}
}

@Override
protected boolean isFinished() {
if (_clear) {
if (_oi.isStartPressed()) {
return true;
}
}
return false;
}

@Override
protected void end() {
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
package org.frc5687.powerup.robot.commands.testing;

import edu.wpi.first.wpilibj.command.CommandGroup;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

import org.frc5687.powerup.robot.Robot;
import org.frc5687.powerup.robot.subsystems.Intake;


public class FullSelfTest extends CommandGroup {

public FullSelfTest(Robot robot) {


addSequential(new ConfirmTest(robot.getOI(), "Please ensure the robot is drydocked and press Start to continue.", "Test started.", "Test aborted."));
addSequential(new TestDriveTrain(robot.getDriveTrain(), robot.getPDP(), robot.getLights()));

addSequential(new ConfirmTest(robot.getOI(), "Please be sure that the carriage is clear and press Start to continue.", "Test started.", "Test aborted."));
addSequential(new TestCarriage(robot.getCarriage(), robot.getPDP(), robot.getLights()));

addSequential(new ConfirmTest(robot.getOI(), "Please be sure that the arm is clear and press Start to continue.", "Test started.", "Test aborted."));

addSequential(new ConfirmTest(robot.getOI(), "Please be sure that the intake is clear and press Start to continue.", "Test started.", "Test aborted."));
addSequential(new TestIntake(robot.getIntake(), robot.getPDP(), robot.getLights()));

addSequential(new ConfirmTest(robot.getOI(), "Tests complete.", "Test started.", "Test aborted."));


}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
package org.frc5687.powerup.robot.commands.testing;

import edu.wpi.first.wpilibj.command.Command;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj.command.Scheduler;
import edu.wpi.first.wpilibj.command.Scheduler;
import edu.wpi.first.wpilibj.DriverStation;

import org.frc5687.powerup.robot.OI;
import org.frc5687.powerup.robot.Robot;
import org.frc5687.powerup.robot.subsystems.Intake;

public class SelfTestBootstrapper extends Command {
private Robot _robot;
private boolean done = false;

public SelfTestBootstrapper(Robot robot) {
_robot = robot;
}

@Override
protected void execute(){

if(!done && !DriverStation.getInstance().isFMSAttached()){
Scheduler.getInstance().add(new FullSelfTest(_robot));
done = true;
}

}

@Override
protected boolean isFinished() {
return done;
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
package org.frc5687.powerup.robot.commands.testing;

import edu.wpi.first.wpilibj.command.Command;
import edu.wpi.first.wpilibj.command.CommandGroup;
import org.frc5687.powerup.robot.Constants;
import org.frc5687.powerup.robot.Robot;
import org.frc5687.powerup.robot.subsystems.Arm;
import org.frc5687.powerup.robot.subsystems.Carriage;
import org.frc5687.powerup.robot.commands.testing.ArmMotorTest;
import org.frc5687.powerup.robot.commands.MoveArmToSetpointPID;

public class TestArm extends CommandGroup{
public TestArm(Robot robot){
addSequential(new ArmMotorTest(robot.getArm(), robot.getCarriage()));
addSequential(new MoveArmToSetpointPID(robot.getArm(), Constants.Arm.Encoder.ENCODER_START));
addSequential(new MoveArmToSetpointPID(robot.getArm(), Constants.Arm.Encoder.ENCODER_TOP));

}


}
Loading

0 comments on commit e7d269b

Please sign in to comment.