diff options
author | FRC_4272 <FRC_4272@USER-PC.lan> | 2017-03-23 01:33:38 -0400 |
---|---|---|
committer | FRC_4272 <FRC_4272@USER-PC.lan> | 2017-03-23 01:33:38 -0400 |
commit | 2e328065b7a7d89c15dd7e124d6383c2b61726fd (patch) | |
tree | b2c50eede0ccc4f941a672c8e2a23fe47a2fb2d1 /src/org/usfirst/frc/team4272/robot2016 | |
parent | ed3db134b11bc37d9a4bad77b1e92aea71daf564 (diff) |
Changes sitting on the Dell.dell-1
Diffstat (limited to 'src/org/usfirst/frc/team4272/robot2016')
-rw-r--r-- | src/org/usfirst/frc/team4272/robot2016/Control.java | 6 | ||||
-rw-r--r-- | src/org/usfirst/frc/team4272/robot2016/HwRobot.java | 36 | ||||
-rw-r--r-- | src/org/usfirst/frc/team4272/robot2016/Teleop.java | 11 |
3 files changed, 37 insertions, 16 deletions
diff --git a/src/org/usfirst/frc/team4272/robot2016/Control.java b/src/org/usfirst/frc/team4272/robot2016/Control.java index 40fcb5a..9efdf34 100644 --- a/src/org/usfirst/frc/team4272/robot2016/Control.java +++ b/src/org/usfirst/frc/team4272/robot2016/Control.java @@ -7,7 +7,9 @@ public class Control { rDrive2 = 0, fBall = 0, bBall = 0, - arm = 0; - + arm = 0, + camRotate = 0, + camTilt = 0; + boolean PCM = false; public Control() {} } diff --git a/src/org/usfirst/frc/team4272/robot2016/HwRobot.java b/src/org/usfirst/frc/team4272/robot2016/HwRobot.java index e61d87f..e4e9b2f 100644 --- a/src/org/usfirst/frc/team4272/robot2016/HwRobot.java +++ b/src/org/usfirst/frc/team4272/robot2016/HwRobot.java @@ -9,8 +9,11 @@ import edu.wpi.first.wpilibj.PIDOutput; import edu.wpi.first.wpilibj.PIDSourceType; import edu.wpi.first.wpilibj.PowerDistributionPanel; import edu.wpi.first.wpilibj.Talon; +import edu.wpi.first.wpilibj.Jaguar; +import edu.wpi.first.wpilibj.Solenoid; import org.usfirst.frc.team4272.robotlib.PIDOutputSplitter; +import org.usfirst.frc.team4272.robotlib.PIDServo; public class HwRobot { /* Relay == a Spike */ @@ -33,15 +36,17 @@ public class HwRobot { // naming convention: {side_letter}{Thing}{E|M (encoder/motor)} private final PIDOutput - rDriveM1 = new Talon(/*PWM*/2), /* PDP 2, 3 */ - rDriveM2 = new Talon(/*PWM*/4), /* PDP 4 */ - lDriveM1 = new Talon(/*PWM*/1), /* PDP 12, 13 */ - lDriveM2 = new Talon(/*PWM*/0), /* PDP 11 */ - armM = new Talon(/*PWM*/8), /* PDP 15 */ - rfBallM = new Talon(/*PWM*/3), /* PDP 0 */ - lfBallM = new Talon(/*PWM*/9), /* PDP 14 */ - fBallM = new PIDOutputSplitter(rfBallM, lfBallM), - bBallM = new Talon(/*PWM*/6); /* PDP 10, 5 */ + rDriveM1 = new Jaguar(/*PWM*/0), /* PDP 2, 3 */ + rDriveM2 = new Jaguar(/*PWM*/1), /* PDP 4 */ + lDriveM1 = new Jaguar(/*PWM*/3), /* PDP 12, 13 */ + lDriveM2 = new Jaguar(2),/*PWM*/ /* PDP 11 */ + //armM = new Talon(/*PWM*/8), /* PDP 15 */ + //rfBallM = new Talon(/*PWM*/4), /* PDP 0 */ + //lfBallM = new Talon(/*PWM*/9), /* PDP 14 */ + //fBallM = new PIDOutputSplitter(rfBallM, lfBallM), + //bBallM = new Talon(/*PWM*/6),/* PDP 10, 5 */ + camRotate = new PIDServo(8), + camTilt = new PIDServo(9); public final Encoder armE = new Encoder(/*DIO*/0, /*DIO*/1, /*DIO*/2, true); public final DigitalInput armL = new DigitalInput(/*DIO*/3); @@ -50,6 +55,8 @@ public class HwRobot { public final Encoder lDriveE = new Encoder(/*DIO*/7,/*DIO*/8, true); public final PowerDistributionPanel PDP = new PowerDistributionPanel(); /* via CAN */ + private final Solenoid PCM = new Solenoid(/*PCM*/ 0); + public HwRobot() { armE.setPIDSourceType(PIDSourceType.kDisplacement); lDriveE.setPIDSourceType(PIDSourceType.kRate); @@ -62,10 +69,12 @@ public class HwRobot { lDriveM2.pidWrite( c.lDrive2); rDriveM1.pidWrite(-c.rDrive1); rDriveM2.pidWrite(-c.rDrive2); - armM.pidWrite(c.arm * 0.5); - fBallM.pidWrite(-c.fBall); - bBallM.pidWrite(-c.bBall); - + //armM.pidWrite(c.arm * 0.5); + //fBallM.pidWrite(-c.fBall); + //bBallM.pidWrite(-c.bBall); + camRotate.pidWrite(c.camRotate); + camTilt.pidWrite(c.camTilt); + PCM.set(c.PCM); SmartDashboard.putNumber("fBall", c.fBall); SmartDashboard.putNumber("bBall", c.bBall); SmartDashboard.putNumber("armM", c.arm); @@ -81,4 +90,5 @@ public class HwRobot { PDP.updateTable(); SmartDashboard.putData("PDP", PDP); } + } diff --git a/src/org/usfirst/frc/team4272/robot2016/Teleop.java b/src/org/usfirst/frc/team4272/robot2016/Teleop.java index 73b7b60..d07e5ce 100644 --- a/src/org/usfirst/frc/team4272/robot2016/Teleop.java +++ b/src/org/usfirst/frc/team4272/robot2016/Teleop.java @@ -74,8 +74,17 @@ public class Teleop { control.fBall = 1; } } + + if(oi.xbox.getAxis(Axis.RTrigger) > 0) + control.camRotate = 1; + else if(oi.xbox.getAxis(Axis.LTrigger) > 0) + control.camRotate = -1; + else + control.camRotate = 0; + control.camTilt = oi.xbox.getAxis(Axis.RX); - //if (robot.armE.pidGet() > armSoftStop && control.arm > 0) + control.PCM = oi.xbox.getButton(Button.A); + //if (robot.armE.piedGet() > armSoftStop && control.arm > 0) // control.arm = 0; /* Take pictures */ |