From 3e7d4eca2c1cbe82002d05e56db7c9740dd93887 Mon Sep 17 00:00:00 2001 From: Luke Shumaker Date: Mon, 20 Feb 2017 14:14:48 -0500 Subject: changes Noah & Thomas made --- .../usfirst/frc/team4272/robot2016/Autonomous.java | 14 +- .../usfirst/frc/team4272/robot2016/Control.java | 11 +- src/org/usfirst/frc/team4272/robot2016/HwOI.java | 5 +- .../usfirst/frc/team4272/robot2016/HwRobot.java | 55 ++-- src/org/usfirst/frc/team4272/robot2016/Teleop.java | 102 +++++-- .../frc/team4272/robotlib/PIDController.java | 216 --------------- .../frc/team4272/robotlib/Xbox360Controller.java | 299 --------------------- 7 files changed, 137 insertions(+), 565 deletions(-) delete mode 100644 src/org/usfirst/frc/team4272/robotlib/PIDController.java delete mode 100644 src/org/usfirst/frc/team4272/robotlib/Xbox360Controller.java (limited to 'src') diff --git a/src/org/usfirst/frc/team4272/robot2016/Autonomous.java b/src/org/usfirst/frc/team4272/robot2016/Autonomous.java index 756c33d..7b2194c 100644 --- a/src/org/usfirst/frc/team4272/robot2016/Autonomous.java +++ b/src/org/usfirst/frc/team4272/robot2016/Autonomous.java @@ -14,17 +14,11 @@ public class Autonomous { } public Control run(Control c) { - if (robot.armL.get()) { - c.arm = -0.5; - } else { - c.arm = 0; - robot.armE.reset(); - } + - if (time.get() < 4) { - c.lDrive1 = c.rDrive1 = -0.4; - } else { - c.lDrive1 = c.rDrive1 = 0; + if (time.get() < 15) { + } + else { } SmartDashboard.putNumber("autoTime", time.get()); diff --git a/src/org/usfirst/frc/team4272/robot2016/Control.java b/src/org/usfirst/frc/team4272/robot2016/Control.java index 40fcb5a..7713c5b 100644 --- a/src/org/usfirst/frc/team4272/robot2016/Control.java +++ b/src/org/usfirst/frc/team4272/robot2016/Control.java @@ -7,7 +7,14 @@ public class Control { rDrive2 = 0, fBall = 0, bBall = 0, - arm = 0; - + arm = 0, + camRotate = 0, + camTilt = 0, + usbCam = 0, + climber = 0; + boolean PCM = true; + boolean PCM2 = false; + boolean PCM3 =true; + boolean PCM4 = false; public Control() {} } diff --git a/src/org/usfirst/frc/team4272/robot2016/HwOI.java b/src/org/usfirst/frc/team4272/robot2016/HwOI.java index fc5cc78..00b0b05 100644 --- a/src/org/usfirst/frc/team4272/robot2016/HwOI.java +++ b/src/org/usfirst/frc/team4272/robot2016/HwOI.java @@ -1,11 +1,10 @@ package org.usfirst.frc.team4272.robot2016; -import org.usfirst.frc.team4272.robotlib.Xbox360Controller; - import edu.wpi.first.wpilibj.Joystick; +import edu.wpi.first.wpilibj.XboxController; public class HwOI { public Joystick lStick = new Joystick(0); public Joystick rStick = new Joystick(1); - public Xbox360Controller xbox = new Xbox360Controller(2); + public XboxController xbox = new XboxController(2); } diff --git a/src/org/usfirst/frc/team4272/robot2016/HwRobot.java b/src/org/usfirst/frc/team4272/robot2016/HwRobot.java index e61d87f..4555adf 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,16 +36,18 @@ 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 */ + rDriveM1 = new Talon(/*PWM*/0), /* PDP 2, 3 */ + climber = new Talon(/*PWM*/3), /* 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 */ - + //lDriveM2 = new Talon(3),/*PWM*/ /* PDP 11 */ + //rDriveM2 = new Talon(1), + //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); public final DigitalInput ballL = new DigitalInput(/*DIO*/4); @@ -50,22 +55,33 @@ public class HwRobot { public final Encoder lDriveE = new Encoder(/*DIO*/7,/*DIO*/8, true); public final PowerDistributionPanel PDP = new PowerDistributionPanel(); /* via CAN */ + public Solenoid PCM = new Solenoid(/*PCM*/ 4); + public Solenoid PCM2 = new Solenoid(5); + public Solenoid PCM3 = new Solenoid(6); + public Solenoid PCM4 = new Solenoid(7); + public HwRobot() { armE.setPIDSourceType(PIDSourceType.kDisplacement); lDriveE.setPIDSourceType(PIDSourceType.kRate); rDriveE.setPIDSourceType(PIDSourceType.kRate); - PDP.initTable(NetworkTable.getTable("PDP")); + //PDP.initTable(NetworkTable.getTable("PDP"));// } public void run(Control c) { lDriveM1.pidWrite( c.lDrive1); - 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); - + rDriveM1.pidWrite(c.rDrive1); + //lDriveM2.pidWrite( c.lDrive2); + climber.pidWrite(c.climber); + //rDriveM2.pidWrite(-c.rDrive2); + //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); + PCM2.set(c.PCM2); + PCM3.set(c.PCM3); + PCM4.set(c.PCM4); SmartDashboard.putNumber("fBall", c.fBall); SmartDashboard.putNumber("bBall", c.bBall); SmartDashboard.putNumber("armM", c.arm); @@ -78,7 +94,8 @@ public class HwRobot { SmartDashboard.putBoolean("ballL", ballL.get()); SmartDashboard.putBoolean("armL", armL.get()); - PDP.updateTable(); - SmartDashboard.putData("PDP", PDP); + //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..a085d91 100644 --- a/src/org/usfirst/frc/team4272/robot2016/Teleop.java +++ b/src/org/usfirst/frc/team4272/robot2016/Teleop.java @@ -2,8 +2,7 @@ package org.usfirst.frc.team4272.robot2016; import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.Timer; -import org.usfirst.frc.team4272.robotlib.Xbox360Controller.Axis; -import org.usfirst.frc.team4272.robotlib.Xbox360Controller.Button; +import edu.wpi.first.wpilibj.GenericHID.Hand; import org.usfirst.frc.team4272.robotlib.PushButton; public class Teleop { @@ -12,6 +11,9 @@ public class Teleop { private final PushButton shootButton = new PushButton(); private final Timer time = new Timer(); + private double lastTime; + private double currentTime; + private boolean state = false; public Teleop(HwRobot robot) { this.robot = robot; @@ -19,8 +21,8 @@ public class Teleop { } private static double jsScale(Joystick j) { - double y = -j.getY();/* +:forward; -:backward */ - double z = -j.getZ();/* +:more-sensitive; -:less-sensitive */ + double y = j.getY();/* +:forward; -:backward */ + double z = j.getZ();/* +:more-sensitive; -:less-sensitive */ return Math.copySign(Math.pow(Math.abs(y), 2.0-z), y); } @@ -31,19 +33,79 @@ public class Teleop { private static double oneIf(boolean b) { return b ? 1 : 0; } - + public Control run(Control control, HwOI oi) { /* Drive */ - control.lDrive1 = jsScale(oi.lStick); + control.lDrive1 = -jsScale(oi.lStick); control.rDrive1 = jsScale(oi.rStick); - control.lDrive2 = oi.lStick.getTrigger() ? control.lDrive1 : 0; - control.rDrive2 = oi.rStick.getTrigger() ? control.rDrive1 : 0; - control.arm = -oi.xbox.getAxis(Axis.LY); + //control.lDrive2 = -jsScale(oi.lStick); + //control.rDrive2 = jsScale(oi.rStick); + if (control.PCM == true) { + control.PCM2 = oi.lStick.getTrigger(); + control.PCM = oi.rStick.getTrigger(); + } + if (oi.lStick.getTrigger()){ + control.PCM2 = false; + control.PCM = true; +// SmartDashboard.putData() + } + if (oi.rStick.getTrigger()) { + control.PCM = false; + control.PCM2 = true; + } + if (oi.rStick.getRawButton(2) || oi.lStick.getRawButton(2)) { + currentTime = Timer.getMatchTime(); + if(currentTime-lastTime > 0.15){ + state = !state; + lastTime = currentTime; + } + if (state){ + control.lDrive1 = 0.5; + control.rDrive1 = 0; + } + else if(!state){ + control.lDrive1 = 0; + control.rDrive1 = 0.5; + } + + } + + if(oi.xbox.getRawAxis(1) > 0.2){ + control.climber = oi.xbox.getRawAxis(1) ; + } + + else if (oi.xbox.getRawAxis(1) < -0.2) { + control.climber = oi.xbox.getRawAxis(1); + } + else { + control.climber = 0; + } + if (oi.xbox.getAButton() == true) { + control.PCM3 = true; + control.PCM4 = false; + } + if(oi.xbox.getBButton()==true) { + control.PCM3 = false; + control.PCM4 =true; + } + +// if(oi.xbox.getTriggerAxis(Hand.kRight/*rTrigger*/) > 0 ){ +// control.PCM3 = false; +// control.PCM4 = true; +// } +// else { +// control.PCM3 = false; +// control.PCM4 =true; +// } + + /*control.lDrive2 = oi.lStick.getTrigger() ? control.lDrive1 : 0; + control.rDrive2 = oi.rStick.getTrigger() ? control.rDrive1 : 0;*/ + control.arm = -oi.xbox.getY(Hand.kLeft); if (control.arm < 0) control.arm = control.arm*0.2; - double fBall = oi.xbox.getAxis(Axis.RTrigger) - oi.xbox.getAxis(Axis.LTrigger); - double bBall = bound(-1, fBall, 0) + oneIf(oi.xbox.getButton(Button.A)) - oneIf(oi.xbox.getButton(Button.B)); + double fBall = oi.xbox.getTriggerAxis(Hand.kRight) - oi.xbox.getTriggerAxis(Hand.kLeft); + double bBall = bound(-1, fBall, 0) + oneIf(oi.xbox.getAButton()) - oneIf(oi.xbox.getBButton()); boolean ballL = robot.ballL.get(); control.fBall = bound(-oneIf(ballL), fBall < 0 ? 0.5*fBall : fBall, 1); @@ -54,16 +116,16 @@ public class Teleop { robot.armE.reset(); } - if (oi.xbox.getButton(Button.LBumper)) + if (oi.xbox.getBumper(Hand.kLeft)) control.arm = 1-(robot.armE.pidGet()/armSoftStop); - else if (oi.xbox.getButton(Button.RBumper)) + else if (oi.xbox.getBumper(Hand.kRight)) control.arm = robot.armE.pidGet()/armSoftStop; - if (shootButton.update(oi.xbox.getButton(Button.X))) { + if (shootButton.update(oi.xbox.getXButton())) { time.reset(); time.start(); } - if (oi.xbox.getButton(Button.X)) { + if (oi.xbox.getXButton()) { if (time.get() < 0.5) { control.fBall = control.bBall = -0.5; } else if (time.get() < 2.5) { @@ -74,8 +136,16 @@ public class Teleop { control.fBall = 1; } } + + if(oi.xbox.getTriggerAxis(Hand.kRight) > 0) + control.camRotate = 1; + else if(oi.xbox.getTriggerAxis(Hand.kLeft) > 0) + control.camRotate = -1; + else + control.camRotate = 0; + control.camTilt = oi.xbox.getX(Hand.kRight); - //if (robot.armE.pidGet() > armSoftStop && control.arm > 0) + //if (robot.armE.piedGet() > armSoftStop && control.arm > 0) // control.arm = 0; /* Take pictures */ diff --git a/src/org/usfirst/frc/team4272/robotlib/PIDController.java b/src/org/usfirst/frc/team4272/robotlib/PIDController.java deleted file mode 100644 index 13f5666..0000000 --- a/src/org/usfirst/frc/team4272/robotlib/PIDController.java +++ /dev/null @@ -1,216 +0,0 @@ -/** - * Copyright (c) FIRST 2008-2012. All Rights Reserved. - * Open Source Software - may be modified and shared by FRC teams. The code - * must be accompanied by the FIRST BSD license file in the root directory of - * the project. - * - * Copyright (c) 2011-2012, 2015-2016 Luke Shumaker - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in the - * documentation and/or other materials provided with the distribution. - * * Neither the name of the FIRST nor the - * names of its contributors may be used to endorse or promote products - * derived from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY FIRST AND CONTRIBUTORS``AS IS'' AND ANY - * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED - * WARRANTIES OF MERCHANTABILITY NONINFRINGEMENT AND FITNESS FOR A PARTICULAR - * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL FIRST OR CONTRIBUTORS BE LIABLE FOR - * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES - * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND - * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT - * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS - * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - * @author Luke Shumaker - */ -package org.usfirst.frc.team4272.robotlib; - -import edu.wpi.first.wpilibj.PIDOutput; -import edu.wpi.first.wpilibj.PIDSource; -import edu.wpi.first.wpilibj.SpeedController; -//import edu.wpi.first.wpilibj.PIDController; - -/** - * An enhanced variant of {@link edu.wpi.first.wpilibj.PIDController wpilibj PIDController} - * (implements a PID Control Loop). - *

- * It is enhanced from - * {@link edu.wpi.first.wpilibj.PIDController wpilibj PIDController} - * in that it that also: - *

- */ -public class PIDController extends edu.wpi.first.wpilibj.PIDController implements SpeedController { - private boolean NaNDisabled = false; - private boolean inverted = false; - public final PIDSource source; - public final PIDOutput output; - - /** - * Allocate a PID object with the given constants for P, I, D, and F - *$ - * @param Kp the proportional coefficient - * @param Ki the integral coefficient - * @param Kd the derivative coefficient - * @param Kf the feed forward term - * @param source The PIDSource object that is used to get values - * @param output The PIDOutput object that is set to the output percentage - * @param period the loop time for doing calculations. This particularly - * effects calculations of the integral and differential terms. The - * default is 50ms. - */ - public PIDController(double Kp, double Ki, double Kd, double Kf, - PIDSource source, PIDOutput output, - double period) { - super(Kp, Ki, Kd, Kf, source, output, period); - this.source = source; - this.output = output; - } - - /* Convenience constructors *******************************************/ - /* `Kf`, and `period` are optional */ - - /** - * Convenience constructor with {@code Kf} defaulting to - * {@code 0.0}. - * - * @param Kp the proportional coefficient - * @param Ki the integral coefficient - * @param Kd the derivative coefficient - * @param source The PIDSource object that is used to get values - * @param output The PIDOutput object that is set to the output percentage - * @param period the loop time for doing calculations. This particularly - * effects calculations of the integral and differential terms. The - * default is 50ms. - */ - public PIDController(double Kp, double Ki, double Kd, - PIDSource source, PIDOutput output, - double period) { - this(Kp, Ki, Kd, 0.0, source, output, period); - } - - /** - * Convenience constructor with {@code period} defaulting to - * {@link #kDefaultPeriod}. - * - * @param Kp the proportional coefficient - * @param Ki the integral coefficient - * @param Kd the derivative coefficient - * @param Kf the feed forward term - * @param source The PIDSource object that is used to get values - * @param output The PIDOutput object that is set to the output percentage - */ - public PIDController(double Kp, double Ki, double Kd, double Kf, - PIDSource source, PIDOutput output) { - this(Kp, Ki, Kd, Kf, source, output, kDefaultPeriod); - } - - /** - * Convenience constructor with {@code Kf} defaulting to - * {@code 0.0}, and {@code period} defaulting to - * {@link #kDefaultPeriod}. - * - * @param Kp the proportional coefficient - * @param Ki the integral coefficient - * @param Kd the derivative coefficient - * @param source The PIDSource object that is used to get values - * @param output The PIDOutput object that is set to the output percentage - */ - public PIDController(double Kp, double Ki, double Kd, - PIDSource source, PIDOutput output) { - this(Kp, Ki, Kd, 0.0, source, output, kDefaultPeriod); - } - - /* Override to auto-disable if setpoint is NaN, and invert ************/ - - /** - * {@inheritDoc} - */ - @Override - public synchronized void setSetpoint(double setpoint) { - if (Double.isNaN(setpoint)) { - NaNDisabled = true; - super.disable(); - } else { - if (NaNDisabled && !isEnabled()) { - enable(); - } - super.setSetpoint((inverted ? -1 : 1) * setpoint); - } - } - - /** - * {@inheritDoc} - */ - @Override - public synchronized void enable() { - NaNDisabled = false; - super.enable(); - } - - /** - * {@inheritDoc} - */ - @Override - public synchronized void disable() { - NaNDisabled = false; - super.disable(); - } - - /* Implement PIDOutput (a parent of SpeedController) *******************/ - - /** - * {@inheritDoc} - */ - @Override - public void pidWrite(double output) { - setSetpoint(output); - } - - /* Implement SpeedController *******************************************/ - - /** - * {@inheritDoc} - */ - @Override - public void set(double output) { - setSetpoint(output); - } - - /** - * Don't use this. - * @deprecated Don't use this; it is leaking up from - * {@link edu.wpi.first.wpilibj.CANJaguar} through - * {@link edu.wpi.first.wpilibj.SpeedController} - */ - @Override - public void set(double output, byte syncGroup) { - set(output); - } - - /** - * {@inheritDoc} - */ - @Override - public void setInverted(boolean isInverted) { - inverted = isInverted; - } - - /** - * {@inheritDoc} - */ - @Override - public boolean getInverted() { - return inverted; - } -} diff --git a/src/org/usfirst/frc/team4272/robotlib/Xbox360Controller.java b/src/org/usfirst/frc/team4272/robotlib/Xbox360Controller.java deleted file mode 100644 index b5c1d13..0000000 --- a/src/org/usfirst/frc/team4272/robotlib/Xbox360Controller.java +++ /dev/null @@ -1,299 +0,0 @@ -/** - * Copyright (c) FIRST 2008-2012. All Rights Reserved. - * Open Source Software - may be modified and shared by FRC teams. The code - * must be accompanied by the FIRST BSD license file in the root directory of - * the project. - * - * Copyright (c) 2015 Luke Shumaker - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in the - * documentation and/or other materials provided with the distribution. - * * Neither the name of the FIRST nor the - * names of its contributors may be used to endorse or promote products - * derived from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY FIRST AND CONTRIBUTORS``AS IS'' AND ANY - * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED - * WARRANTIES OF MERCHANTABILITY NONINFRINGEMENT AND FITNESS FOR A PARTICULAR - * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL FIRST OR CONTRIBUTORS BE LIABLE FOR - * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES - * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND - * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT - * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS - * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - * @author Luke Shumaker - */ -package org.usfirst.frc.team4272.robotlib; - -import edu.wpi.first.wpilibj.GenericHID; -import edu.wpi.first.wpilibj.Joystick; - -/** - * Handle input from a wired Xbox 360 controller connected to the - * Driver Station. - */ -public class Xbox360Controller extends GenericHID { - /* Constants ************************************************/ - - /** - * Represents an analog axis on an Xbox 360 controller. - */ - public static enum Axis { - LX(0), LY(1), LTrigger(2), - RX(4), RY(5), RTrigger(3), - /** D-Pad X */ DX(6), /** D-Pad Y */ DY(7); - - private final int id; - private Axis(int id) { this.id = id; } - public int getId() { return id; } - } - - /** - * Represents a digital button on Xbox 360 controller. - */ - public static enum Button { - A(0), B(1), - X(2), Y(3), - LBumper(4), RBumper( 5), - Back(6), Start(7), /*Home(8),*/ - LThumb(8), RThumb(9); - - public final int id; - private Button(int id) { this.id = id+1; } - } - - /* Constructor **********************************************/ - private final Joystick joystick; - - /** - * Construct an instance of a joystick. - * The joystick index is the USB port on the Driver Station. - * - * @param port The port on the driver station that the joystick is plugged into - */ - public Xbox360Controller(final int port) { - joystick = new Joystick(port); - } - - /* Core functions *******************************************/ - - /** - * Get the raw axis - *$ - * @param axis Index of the axis - * @return The raw value of the selected axis - */ - @Override - public double getRawAxis(int axis) { - return joystick.getRawAxis(axis); - } - - /** - * Is the given button pressed - *$ - * @param button Index of the button - * @return True if the button is pressed - */ - @Override - public boolean getRawButton(int button) { - return joystick.getRawButton(button); - } - - /** - * Get the value of an axis base on an enumerated type. - * - * @param axis The axis to read - * @return The value of the axis - */ - public double getAxis(final Axis axis) { - return getRawAxis(axis.id); - } - - /** - * Get buttons based on an enumerated type. - * - * @param button The button to read - * @return The state of the button - */ - public boolean getButton(final Button button) { - return getRawButton(button.id); - } - - /** - * Ask the Driver Station if this USB joystick is in fact an - * Xbox controller. - * - * @return Whether the controller is an Xbox controller - */ - public boolean getIsXbox() { - return joystick.getIsXbox(); - } - - /* TODO: Outputs? (Rumble, LEDs) */ - - /* Stupid little mathy wrappers *****************************/ - - /** - * Get the magnitude of the direction vector formed by the thumb-stick's - * current position relative to its origin - * - * @param hand Left stick or right? - * @return The magnitude of the direction vector - */ - public double getMagnitude(Hand hand) { - return Math.sqrt(Math.pow(getX(hand), 2) + Math.pow(getY(hand), 2)); - } - - /** - * Get the direction of the vector formed by the thumb-stick and its origin - * in radians - * - * @param hand Left stick or right? - * @return The direction of the vector in radians - */ - public double getDirectionRadians(Hand hand) { - return Math.atan2(getX(hand), -getY(hand)); - } - - /** - * Get the direction of the vector formed by the thumb-stick and its origin - * in degrees - * - * uses acos(-1) to represent Pi due to absence of readily accessable Pi - * constant in C++ - * - * @param hand Left stick or right? - * @return The direction of the vector in degrees - */ - public double getDirectionDegrees(Hand hand) { - return Math.toDegrees(getDirectionRadians(hand)); - } - - /* Stupid aliases for getAxis/getButton *********************/ - - /** - * Get the state of a trigger; whether it is mostly pressed or - * not. - * - * @param hand Left trigger or right? - * @return The state of the trigger. - */ - @Override - public boolean getTrigger(Hand hand) { - return getZ(hand) > 0.75; - } - - /** - * Get the state of a bumper. - * - * @param hand Left bumper or right? - * @return Whether the bumper is pressed - * @deprecated This method is only here to complete the {@link GenericHID} abstract class. - */ - @Override - public boolean getBumper(Hand hand) { - if (hand.value == Hand.kLeft.value) - return getButton(Button.LBumper); - if (hand.value == Hand.kRight.value) - return getButton(Button.RBumper); - return false; - } - - /** - * Get the state of a thumb-stick button. - * - * @param hand Left trigger or right? - * @return the state of the button. - */ - @Override - public boolean getTop(Hand hand) { - if (hand.value == Hand.kLeft.value) - return getButton(Button.LThumb); - if (hand.value == Hand.kRight.value) - return getButton(Button.RThumb); - return false; - } - - /** - * Get the X value of a thumb-stick. - * - * @param hand Left stick or right? - * @return The X value of the thumb-stick. - */ - @Override - public double getX(final Hand hand) { - if (hand.value == Hand.kLeft.value) - return getAxis(Axis.LX); - if (hand.value == Hand.kRight.value) - return getAxis(Axis.RX); - return 0.0; - } - - /** - * Get the Y value of a thumb-stick. - - * @param hand Left stick or right? - * @return The Y value of the thumb-stick. - */ - @Override - public double getY(final Hand hand) { - if (hand.value == Hand.kLeft.value) - return getAxis(Axis.LY); - if (hand.value == Hand.kRight.value) - return getAxis(Axis.RY); - return 0.0; - } - - /** - * Get the value of a trigger. - * - * @param hand Left trigger or right? - * @return The trigger value. - */ - @Override - public double getZ(final Hand hand) { - if (hand.value == Hand.kLeft.value) - return getAxis(Axis.LTrigger); - if (hand.value == Hand.kRight.value) - return getAxis(Axis.RTrigger); - return 0.0; - } - - /* Stupid things I have to implement ************************/ - - /** - * @return Always 0.0 - * @deprecated This method is only here to complete the {@link GenericHID} abstract class. - */ - @Override - public double getTwist() { - return 0.0; - } - - /** - * @return Always 0.0 - * @deprecated This method is only here to complete the {@link GenericHID} abstract class. - */ - @Override - public double getThrottle() { - return 0.0; - } - - /** - * @param pov Unused - * @return Always 0 - * @deprecated This method is only here to complete the {@link GenericHID} abstract class. - */ - @Override - public int getPOV(int pov) { - return 0; - } -} -- cgit v1.2.3