Skip to content

Commit

Permalink
Modify commands to be compatible
Browse files Browse the repository at this point in the history
  • Loading branch information
PrathamRawat committed Oct 10, 2018
1 parent 640af34 commit 2c85f08
Show file tree
Hide file tree
Showing 17 changed files with 1,162 additions and 1,163 deletions.
34 changes: 17 additions & 17 deletions src/edu/stuy/robot/OI.java
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,10 @@
import edu.stuy.robot.commands.HoodUpCommand;
import edu.stuy.robot.commands.HopperRunCommand;
import edu.stuy.robot.commands.JionDriveCommand;
import edu.stuy.robot.commands.RotateToAimCommand;
import edu.stuy.robot.commands.RotateToAimMultiCommand;
//import edu.stuy.robot.commands.RotateToAimCommand;
//import edu.stuy.robot.commands.RotateToAimMultiCommand;
import edu.stuy.robot.commands.RunInLowGearCommand;
import edu.stuy.robot.commands.SetupForShotCommand;
//import edu.stuy.robot.commands.SetupForShotCommand;
import edu.stuy.robot.commands.ShooterHopperBackwardsCommand;
import edu.stuy.robot.commands.ShooterHopperStopCommand;
import edu.stuy.robot.commands.ShooterSetLayupCommand;
Expand Down Expand Up @@ -77,20 +77,20 @@ public OI() {
driverGamepad.getLeftBumper().whenPressed(new FlashlightOnCommand());
driverGamepad.getLeftBumper().whenReleased(new FlashlightOffCommand());

// CV controls
GyroRotationalCommand singleRotationTrigger = new RotateToAimCommand(false, 1.7);
singleRotationTrigger.setUseSignalLights(true);
driverGamepad.getRightTrigger().whenPressed(new RunInLowGearCommand(singleRotationTrigger));

driverGamepad.getBottomButton().whenPressed(new RunInLowGearCommand(new RotateToAimMultiCommand()));
driverGamepad.getTopButton().whenPressed(new RunInLowGearCommand(new SetupForShotCommand()));
GyroRotationalCommand singleRotationLeft = new RotateToAimCommand(false, 1.7);
singleRotationLeft.setUseSignalLights(true);
GyroRotationalCommand singleRotationRight = new RotateToAimCommand(false, 1.7);
singleRotationRight.setUseSignalLights(true);
driverGamepad.getRightButton().whenPressed(new RunInLowGearCommand(singleRotationLeft));
driverGamepad.getLeftButton().whenPressed(new RunInLowGearCommand(singleRotationRight));

// // CV controls
// GyroRotationalCommand singleRotationTrigger = new RotateToAimCommand(false, 1.7);
// singleRotationTrigger.setUseSignalLights(true);
// driverGamepad.getRightTrigger().whenPressed(new RunInLowGearCommand(singleRotationTrigger));
//
// driverGamepad.getBottomButton().whenPressed(new RunInLowGearCommand(new RotateToAimMultiCommand()));
// driverGamepad.getTopButton().whenPressed(new RunInLowGearCommand(new SetupForShotCommand()));
// GyroRotationalCommand singleRotationLeft = new RotateToAimCommand(false, 1.7);
// singleRotationLeft.setUseSignalLights(true);
// GyroRotationalCommand singleRotationRight = new RotateToAimCommand(false, 1.7);
// singleRotationRight.setUseSignalLights(true);
// driverGamepad.getRightButton().whenPressed(new RunInLowGearCommand(singleRotationLeft));
// driverGamepad.getLeftButton().whenPressed(new RunInLowGearCommand(singleRotationRight));
//
// OPERATOR BINDINGS
operatorGamepad.getLeftTrigger().whileHeld(new HopperRunCommand(true));
operatorGamepad.getLeftBumper().whileHeld(new HopperRunCommand(false));
Expand Down
10 changes: 5 additions & 5 deletions src/edu/stuy/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
import static edu.stuy.robot.RobotMap.SIGNAL_LIGHT_YELLOW_PORT;
import static edu.stuy.robot.RobotMap.YUBIN_ID;

import edu.stuy.robot.commands.auton.CrossObstacleThenShootCommand;
//import edu.stuy.robot.commands.auton.CrossObstacleThenShootCommand;
import edu.stuy.robot.commands.auton.GoOverMoatCommand;
import edu.stuy.robot.commands.auton.GoOverRampartsCommand;
import edu.stuy.robot.commands.auton.GoOverRockWallBackwardsCommand;
Expand All @@ -16,7 +16,7 @@
import edu.stuy.robot.commands.auton.PassChevalCommand;
import edu.stuy.robot.commands.auton.PassPortcullisCommand;
import edu.stuy.robot.commands.auton.ReachObstacleCommand;
import edu.stuy.robot.cv.StuyVision;
//import edu.stuy.robot.cv.StuyVision;
import edu.stuy.robot.subsystems.Acquirer;
import edu.stuy.robot.subsystems.Drivetrain;
import edu.stuy.robot.subsystems.DropDown;
Expand Down Expand Up @@ -69,7 +69,7 @@ public class Robot extends IterativeRobot {
private double autonStartTime;
private static boolean debugMode;

public static StuyVision vision;
// public static StuyVision vision;
public static BoolBox stopAutoMovement = new BoolBox(false);

// Used to not waste a ball in a shooting auton if CV doesn't
Expand Down Expand Up @@ -120,7 +120,7 @@ public void robotInit() {
flashlight = new Flashlight();

oi = new OI();
vision = new StuyVision();
// vision = new StuyVision();

drivetrain.setDrivetrainBrakeMode(true);
shooter.setShooterBrakeMode(false);
Expand Down Expand Up @@ -211,7 +211,7 @@ public void autonomousInit() {
boolean shoot = (Boolean) autonShootChooser.getSelected();
selectedAutonomousCommand = selected;
if (shoot) {
autonomousCommand = new CrossObstacleThenShootCommand(selectedAutonomousCommand, autonPosition);
// autonomousCommand = new CrossObstacleThenShootCommand(selectedAutonomousCommand, autonPosition);
} else {
autonomousCommand = selectedAutonomousCommand;
}
Expand Down
6 changes: 3 additions & 3 deletions src/edu/stuy/robot/RobotMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,16 +12,16 @@ public interface RobotMap {
int DRIVER_GAMEPAD = 0;
int OPERATOR_GAMEPAD = 1;

// Drivetrain CANTalon channels
// Drivetrain TalonSRX channels
int FRONT_RIGHT_MOTOR_CHANNEL = 1;
int REAR_RIGHT_MOTOR_CHANNEL = 2;
int REAR_LEFT_MOTOR_CHANNEL = 3;
int FRONT_LEFT_MOTOR_CHANNEL = 4;

// CANTalon channels for other subsystems
// TalonSRX channels for other subsystems
int HOPPER_MOTOR_CHANNEL = 5;
int ACQUIRER_MOTOR_CHANNEL = 6;
int SHOOTER_MOTOR_CHANNEL = 7;
int SHOOTER_MOTOR_CHANNEL = 13;
int DROPDOWN_MOTOR_CHANNEL = 8;

// Solenoid ports
Expand Down
130 changes: 65 additions & 65 deletions src/edu/stuy/robot/commands/CVReadAndPrintCommand.java
Original file line number Diff line number Diff line change
@@ -1,65 +1,65 @@
package edu.stuy.robot.commands;

import java.util.Arrays;

import edu.stuy.robot.Robot;
import edu.stuy.robot.cv.StuyVision;
import edu.wpi.first.wpilibj.command.Command;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

/**
*
*/
public class CVReadAndPrintCommand extends Command {
boolean tryToSaveFile;
public CVReadAndPrintCommand() {
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);
}
public CVReadAndPrintCommand(boolean save) {
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);
tryToSaveFile = save;
}

// Called just before this Command runs the first time
protected void initialize() {
try {
long start = System.currentTimeMillis();
double[] cvReading = null;
cvReading = Robot.vision.processImage(Robot.isDebugModeOn() && tryToSaveFile);
System.out.println("\n\n\n\n\n\n\n\n\n\nprocessImage took " + (System.currentTimeMillis() - start) + "ms");
System.out.println(new StuyVision.Report(cvReading));
boolean canProceed = cvReading != null;
SmartDashboard.putString("cv-reading", Arrays.toString(cvReading));
if (canProceed) {
double desiredAngle = StuyVision.frameXPxToDegrees(cvReading[0]);
SmartDashboard.putNumber("cv-angle", desiredAngle);
System.out.println("Desired Angle Delta: " + desiredAngle);
}
SmartDashboard.putBoolean("cv-visible", canProceed);
} catch (Exception e) {
System.err.println("\n\n\n\nGeneric exception caught in CVReadAndPrintCommand:");
e.printStackTrace();
System.err.println("^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^");
}
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
}

// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return true;
}

// Called once after isFinished returns true
protected void end() {
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
}
}
//package edu.stuy.robot.commands;
//
//import java.util.Arrays;
//
//import edu.stuy.robot.Robot;
//import edu.stuy.robot.cv.StuyVision;
//import edu.wpi.first.wpilibj.command.Command;
//import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
//
///**
// *
// */
//public class CVReadAndPrintCommand extends Command {
// boolean tryToSaveFile;
// public CVReadAndPrintCommand() {
// // Use requires() here to declare subsystem dependencies
// // eg. requires(chassis);
// }
// public CVReadAndPrintCommand(boolean save) {
// // Use requires() here to declare subsystem dependencies
// // eg. requires(chassis);
// tryToSaveFile = save;
// }
//
// // Called just before this Command runs the first time
// protected void initialize() {
// try {
// long start = System.currentTimeMillis();
// double[] cvReading = null;
// cvReading = Robot.vision.processImage(Robot.isDebugModeOn() && tryToSaveFile);
// System.out.println("\n\n\n\n\n\n\n\n\n\nprocessImage took " + (System.currentTimeMillis() - start) + "ms");
// System.out.println(new StuyVision.Report(cvReading));
// boolean canProceed = cvReading != null;
// SmartDashboard.putString("cv-reading", Arrays.toString(cvReading));
// if (canProceed) {
// double desiredAngle = StuyVision.frameXPxToDegrees(cvReading[0]);
// SmartDashboard.putNumber("cv-angle", desiredAngle);
// System.out.println("Desired Angle Delta: " + desiredAngle);
// }
// SmartDashboard.putBoolean("cv-visible", canProceed);
// } catch (Exception e) {
// System.err.println("\n\n\n\nGeneric exception caught in CVReadAndPrintCommand:");
// e.printStackTrace();
// System.err.println("^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^");
// }
// }
//
// // Called repeatedly when this Command is scheduled to run
// protected void execute() {
// }
//
// // Make this return true when this Command no longer needs to run execute()
// protected boolean isFinished() {
// return true;
// }
//
// // Called once after isFinished returns true
// protected void end() {
// }
//
// // Called when another command which requires one or more of the same
// // subsystems is scheduled to run
// protected void interrupted() {
// }
//}
68 changes: 34 additions & 34 deletions src/edu/stuy/robot/commands/DriveToCourtyardRangeCommand.java
Original file line number Diff line number Diff line change
@@ -1,34 +1,34 @@
package edu.stuy.robot.commands;

import static edu.stuy.robot.RobotMap.COURTYARD_SHOOTING_DISTANCE;

import edu.stuy.robot.Robot;
import edu.stuy.robot.cv.StuyVision;

/**
*
*/
public class DriveToCourtyardRangeCommand extends EncoderDrivingCommand {

public DriveToCourtyardRangeCommand() {
super(Robot.stopAutoMovement);
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);
requires(Robot.drivetrain);
}

protected void setInchesToMove() {
double[] cvReading = Robot.vision.processImage();
if (cvReading != null) {
double curDistance = StuyVision.findBotDistanceToGoal(cvReading[1]);
initialInchesToMove = curDistance - COURTYARD_SHOOTING_DISTANCE;
} else {
// CV failed!
cancelCommand = true;
}
System.out.println(new StuyVision.Report(cvReading));
if (cvReading != null) {
System.out.println(StuyVision.findBotDistanceToGoal(cvReading[1]));
}
}
}
//package edu.stuy.robot.commands;
//
//import static edu.stuy.robot.RobotMap.COURTYARD_SHOOTING_DISTANCE;
//
//import edu.stuy.robot.Robot;
//import edu.stuy.robot.cv.StuyVision;
//
///**
// *
// */
//public class DriveToCourtyardRangeCommand extends EncoderDrivingCommand {
//
// public DriveToCourtyardRangeCommand() {
// super(Robot.stopAutoMovement);
// // Use requires() here to declare subsystem dependencies
// // eg. requires(chassis);
// requires(Robot.drivetrain);
// }
//
// protected void setInchesToMove() {
// double[] cvReading = Robot.vision.processImage();
// if (cvReading != null) {
// double curDistance = StuyVision.findBotDistanceToGoal(cvReading[1]);
// initialInchesToMove = curDistance - COURTYARD_SHOOTING_DISTANCE;
// } else {
// // CV failed!
// cancelCommand = true;
// }
// System.out.println(new StuyVision.Report(cvReading));
// if (cvReading != null) {
// System.out.println(StuyVision.findBotDistanceToGoal(cvReading[1]));
// }
// }
//}
70 changes: 35 additions & 35 deletions src/edu/stuy/robot/commands/DriveToLayupRangeCommand.java
Original file line number Diff line number Diff line change
@@ -1,35 +1,35 @@
package edu.stuy.robot.commands;

import static edu.stuy.robot.RobotMap.LAYUP_SHOOTING_DISTANCE;

import edu.stuy.robot.Robot;
import edu.stuy.robot.cv.StuyVision;
import edu.stuy.util.BoolBox;

/**
*
*/
public class DriveToLayupRangeCommand extends EncoderDrivingCommand {

public DriveToLayupRangeCommand() {
super(Robot.stopAutoMovement);
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);
requires(Robot.drivetrain);
}

protected void setInchesToMove() {
double[] cvReading = Robot.vision.processImage();
if (cvReading != null) {
double curDistance = StuyVision.findBotDistanceToGoal(cvReading[1]);
initialInchesToMove = curDistance - LAYUP_SHOOTING_DISTANCE;
} else {
// CV failed!
cancelCommand = true;
}
System.out.println(new StuyVision.Report(cvReading));
if (cvReading != null) {
System.out.println(StuyVision.findBotDistanceToGoal(cvReading[1]));
}
}
}
//package edu.stuy.robot.commands;
//
//import static edu.stuy.robot.RobotMap.LAYUP_SHOOTING_DISTANCE;
//
//import edu.stuy.robot.Robot;
//import edu.stuy.robot.cv.StuyVision;
//import edu.stuy.util.BoolBox;
//
///**
// *
// */
//public class DriveToLayupRangeCommand extends EncoderDrivingCommand {
//
// public DriveToLayupRangeCommand() {
// super(Robot.stopAutoMovement);
// // Use requires() here to declare subsystem dependencies
// // eg. requires(chassis);
// requires(Robot.drivetrain);
// }
//
// protected void setInchesToMove() {
// double[] cvReading = Robot.vision.processImage();
// if (cvReading != null) {
// double curDistance = StuyVision.findBotDistanceToGoal(cvReading[1]);
// initialInchesToMove = curDistance - LAYUP_SHOOTING_DISTANCE;
// } else {
// // CV failed!
// cancelCommand = true;
// }
// System.out.println(new StuyVision.Report(cvReading));
// if (cvReading != null) {
// System.out.println(StuyVision.findBotDistanceToGoal(cvReading[1]));
// }
// }
//}
Loading

0 comments on commit 2c85f08

Please sign in to comment.