diff --git a/src/org/usfirst/frc/team2059/robot/OI.java b/src/org/usfirst/frc/team2059/robot/OI.java index 6af5c4e..f34e93e 100644 --- a/src/org/usfirst/frc/team2059/robot/OI.java +++ b/src/org/usfirst/frc/team2059/robot/OI.java @@ -5,6 +5,7 @@ import edu.wpi.first.wpilibj.command.Command; import edu.wpi.first.wpilibj.buttons.JoystickButton; import org.usfirst.frc.team2059.robot.commands.drivetrain.LogEncoder; import org.usfirst.frc.team2059.robot.commands.drivetrain.PIDDrive; +import org.usfirst.frc.team2059.robot.commands.drivetrain.Drive; import org.usfirst.frc.team2059.robot.commands.shooter.MoveArm; import org.usfirst.frc.team2059.robot.commands.shooter.ResetLower; import org.usfirst.frc.team2059.robot.commands.shooter.ResetUpper; @@ -40,6 +41,7 @@ public class OI { joystickButtons[0][2].whileHeld(new SpinRollers(-0.5, false)); joystickButtons[0][3].whileHeld(new SpinRollers(1, false)); joystickButtons[0][6].whileHeld(new SpinRollers(1, true)); + joystickButtons[0][9].whileHeld(new Drive()); // joystickButtons[0][2].whileHeld(new PIDDrive(400)); joystickButtons[1][0].whileHeld(new MoveArm(1)); joystickButtons[1][1].whileHeld(new MoveArm(-1)); diff --git a/src/org/usfirst/frc/team2059/robot/Robot.java b/src/org/usfirst/frc/team2059/robot/Robot.java index 65cc2ed..7c0b4e4 100644 --- a/src/org/usfirst/frc/team2059/robot/Robot.java +++ b/src/org/usfirst/frc/team2059/robot/Robot.java @@ -78,7 +78,7 @@ public class Robot extends IterativeRobot { SmartDashboard.putNumber("horizontalError", CommandBase.visionHelper.getHorizontalError()); SmartDashboard.putNumber("verticalError", CommandBase.visionHelper.getVerticalError()); SmartDashboard.putNumber("horizontalErrorCorrected", CommandBase.visionHelper.getHorizontalError() + 5); - SmartDashboard.putNumber("goalDistance", 72 / Math.tan(0.0175 * (35 + CommandBase.visionHelper.getVerticalError()))); + SmartDashboard.putNumber("goalDistance", 71 / Math.tan((52.7 - CommandBase.visionHelper.getVerticalError()))); if (Robot.oi.getJoysticks()[1].getRawButton(3)) { CommandBase.pneumatics.setArmStopState(true); } else { diff --git a/src/org/usfirst/frc/team2059/robot/subsystems/DriveBase.java b/src/org/usfirst/frc/team2059/robot/subsystems/DriveBase.java index 2fef2b5..f5f6b18 100644 --- a/src/org/usfirst/frc/team2059/robot/subsystems/DriveBase.java +++ b/src/org/usfirst/frc/team2059/robot/subsystems/DriveBase.java @@ -21,7 +21,7 @@ public class DriveBase extends Subsystem { PIDController leftEncoderController = new PIDController(0.02, 0.002, 0.017, leftEncoder, new MotorsPIDOutput()); double encoderGyroCorrection = 1; public void initDefaultCommand() { - setDefaultCommand(new Drive()); +// setDefaultCommand(new Drive()); } public void stopDriving() { leftMotorOne.set(0); diff --git a/src/org/usfirst/frc/team2059/robot/subsystems/VisionHelper.java b/src/org/usfirst/frc/team2059/robot/subsystems/VisionHelper.java index 2d4c342..2442e2f 100644 --- a/src/org/usfirst/frc/team2059/robot/subsystems/VisionHelper.java +++ b/src/org/usfirst/frc/team2059/robot/subsystems/VisionHelper.java @@ -8,8 +8,6 @@ import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj.networktables.NetworkTable; public class VisionHelper { NetworkTable contoursTable; - double hfieldOfView = 67; - double vfieldOfView = 51; double imageWidth = 640; double imageHeight = 480; public VisionHelper() { @@ -30,9 +28,9 @@ public class VisionHelper { } } public double getHorizontalError() { - return Math.atan2(getCenterX() - RobotMap.imageWidth / 2, RobotMap.fWidth); + return (180/Math.PI) * (Math.atan((getCenterX() - (RobotMap.imageWidth / 2)) / RobotMap.fWidth)); } public double getVerticalError() { - return Math.atan2(getCenterY() - RobotMap.imageHeight / 2, RobotMap.fHeight); + return (180/Math.PI) * (Math.atan((getCenterY() - (RobotMap.imageHeight / 2)) / RobotMap.fHeight)); } }