From: Eric Sandoval Date: Sat, 4 Feb 2017 23:06:06 +0000 (-0800) Subject: update code X-Git-Url: http://challenge-bot.com/repos/?p=3501%2F2017steamworks;a=commitdiff_plain;h=01ea28790a3859bc17c0f5db43abb5c95b2cf057 update code --- diff --git a/src/org/usfirst/frc/team3501/robot/Constants.java b/src/org/usfirst/frc/team3501/robot/Constants.java index b84ee2f..47b8959 100644 --- a/src/org/usfirst/frc/team3501/robot/Constants.java +++ b/src/org/usfirst/frc/team3501/robot/Constants.java @@ -70,7 +70,6 @@ public class Constants { public static final int TARGET_DISTANCE_ERROR = -1; public static final SPI.Port GYRO_PORT = SPI.Port.kOnboardCS0; - } public static class Intake { diff --git a/src/org/usfirst/frc/team3501/robot/Robot.java b/src/org/usfirst/frc/team3501/robot/Robot.java index e9b1d4f..003e138 100644 --- a/src/org/usfirst/frc/team3501/robot/Robot.java +++ b/src/org/usfirst/frc/team3501/robot/Robot.java @@ -1,6 +1,5 @@ package org.usfirst.frc.team3501.robot; -import org.usfirst.frc.team3501.robot.commands.driving.DriveDistance; import org.usfirst.frc.team3501.robot.subsystems.DriveTrain; import org.usfirst.frc.team3501.robot.subsystems.Intake; import org.usfirst.frc.team3501.robot.subsystems.Shooter; @@ -51,6 +50,12 @@ public class Robot extends IterativeRobot { SmartDashboard.putNumber(Constants.DriveTrain.DRIVE_TARGET_DIST, 50); SmartDashboard.putNumber(Constants.DriveTrain.MOTOR_VAL, 0.5); + SmartDashboard.putNumber(Constants.DriveTrain.P_Val, 0); + SmartDashboard.putNumber(Constants.DriveTrain.I_Val, 0); + SmartDashboard.putNumber(Constants.DriveTrain.D_Val, 0); + SmartDashboard.putNumber(Constants.DriveTrain.TARGET_DIST, 50); + SmartDashboard.putNumber(Constants.DriveTrain.MOTOR_VAL, 0.5); + } @Override @@ -63,6 +68,18 @@ public class Robot extends IterativeRobot { Constants.DriveTrain.PID_ERROR); double D = SmartDashboard.getNumber(Constants.DriveTrain.DRIVE_D_Val, Constants.DriveTrain.PID_ERROR); + double P = SmartDashboard.getNumber(Constants.DriveTrain.P_Val, + Constants.DriveTrain.PID_ERROR); + double I = SmartDashboard.getNumber(Constants.DriveTrain.I_Val, + Constants.DriveTrain.PID_ERROR); + double D = SmartDashboard.getNumber(Constants.DriveTrain.D_Val, + Constants.DriveTrain.PID_ERROR); + + double SPEED = SmartDashboard.getNumber(Constants.DriveTrain.MOTOR_VAL, 0); + + double SETPOINT = SmartDashboard.getNumber(Constants.DriveTrain.TARGET_DIST, + Constants.DriveTrain.TARGET_DISTANCE); + double SPEED = SmartDashboard.getNumber(Constants.DriveTrain.MOTOR_VAL, 0); double SETPOINT = SmartDashboard.getNumber( @@ -71,7 +88,7 @@ public class Robot extends IterativeRobot { DriveTrain.getDriveTrain().getDriveController().setConstants(P, I, D); - new DriveDistance(SETPOINT, SPEED).start(); + // new DriveDistance(SETPOINT, SPEED).start(); } @Override diff --git a/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java b/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java index 717f151..7e07577 100755 --- a/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java +++ b/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java @@ -40,7 +40,7 @@ public class TurnForAngle extends Command { this.gyroI = driveTrain.turnI; this.gyroD = driveTrain.turnD; - this.gyroController = new PIDController(this.gyroP, this.gyroI, this.gyroD); + this.gyroController = Robot.getDriveTrain().getDriveController(); this.gyroController.setDoneRange(1); this.gyroController.setMinDoneCycles(5); } diff --git a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java index 83f48d5..5a4d4b7 100644 --- a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java +++ b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java @@ -40,6 +40,7 @@ public class DriveTrain extends Subsystem { public boolean shouldBeClimbing = false; private PIDController driveController; + private PIDController gyroController; private DriveTrain() {