mirror of
https://github.com/Team4388/2022NoWayHome.git
synced 2026-06-09 08:48:07 -06:00
Merge branch 'swerve' into Shooter
This commit is contained in:
@@ -0,0 +1,107 @@
|
||||
package frc4388.utility;
|
||||
|
||||
import static org.fusesource.jansi.Ansi.ansi;
|
||||
|
||||
import java.io.IOException;
|
||||
import java.io.OutputStream;
|
||||
import java.io.PrintStream;
|
||||
import java.io.PrintWriter;
|
||||
import java.io.StringWriter;
|
||||
import java.time.ZoneId;
|
||||
import java.time.ZonedDateTime;
|
||||
import java.util.logging.ConsoleHandler;
|
||||
import java.util.logging.Formatter;
|
||||
import java.util.logging.Level;
|
||||
import java.util.logging.LogManager;
|
||||
import java.util.logging.LogRecord;
|
||||
import java.util.logging.Logger;
|
||||
|
||||
import org.fusesource.jansi.Ansi;
|
||||
import org.fusesource.jansi.Ansi.Attribute;
|
||||
import org.fusesource.jansi.Ansi.Color;
|
||||
import org.fusesource.jansi.AnsiConsole;
|
||||
|
||||
public class AnsiLogging extends ConsoleHandler {
|
||||
public static void systemInstall() {
|
||||
try {
|
||||
// Configures java.util.logging.Logger to output additional colored information.
|
||||
LogManager.getLogManager().updateConfiguration(key -> (o, n) -> {
|
||||
switch (key) {
|
||||
case ".level": return Level.ALL.getName();
|
||||
case "handlers": return AnsiColorConsoleHandler.class.getName();
|
||||
default: return n;
|
||||
}
|
||||
});
|
||||
// Replaces standard output streams with org.fusesource.jansi.AnsiPrintStreams.
|
||||
AnsiConsole.systemInstall();
|
||||
// Replaces standard output stream with java.util.logging.Logger.
|
||||
System.setOut(printStreamLogger(Logger.getGlobal(), Level.INFO));
|
||||
// Replaces standard error output stream with java.util.logging.Logger.
|
||||
System.setErr(printStreamLogger(Logger.getGlobal(), Level.SEVERE));
|
||||
} catch (IOException exception) {
|
||||
exception.printStackTrace(AnsiConsole.sysErr());
|
||||
}
|
||||
}
|
||||
|
||||
public static class AnsiColorConsoleHandler extends ConsoleHandler {
|
||||
@Override
|
||||
public void publish(LogRecord logRecord) {
|
||||
AnsiConsole.err().print(getFormatter().format(logRecord));
|
||||
AnsiConsole.err().flush();
|
||||
}
|
||||
@Override
|
||||
public Formatter getFormatter() {
|
||||
return formatter;
|
||||
}
|
||||
private static final Formatter formatter = new Formatter() {
|
||||
@Override
|
||||
public String format(LogRecord logRecord) {
|
||||
ZonedDateTime zdt = ZonedDateTime.ofInstant(logRecord.getInstant(), ZoneId.systemDefault());
|
||||
String source;
|
||||
if (logRecord.getSourceClassName() != null && !logRecord.getSourceClassName().startsWith(AnsiLogging.class.getName())) {
|
||||
source = logRecord.getSourceClassName();
|
||||
if (logRecord.getSourceMethodName() != null) {
|
||||
source += " " + logRecord.getSourceMethodName();
|
||||
}
|
||||
} else
|
||||
source = logRecord.getLoggerName();
|
||||
String message = formatMessage(logRecord);
|
||||
String throwable = "";
|
||||
if (logRecord.getThrown() != null) {
|
||||
StringWriter sw = new StringWriter();
|
||||
try (PrintWriter pw = new PrintWriter(sw)) {
|
||||
pw.println();
|
||||
logRecord.getThrown().printStackTrace(pw);
|
||||
}
|
||||
throwable = sw.toString();
|
||||
}
|
||||
Ansi ansi;
|
||||
if (logRecord.getLevel() == Level.SEVERE) ansi = ansi().fgBright(Color.RED);
|
||||
else if (logRecord.getLevel() == Level.WARNING) ansi = ansi().fgBright(Color.YELLOW);
|
||||
else if (logRecord.getLevel() == Level.INFO) ansi = ansi().fg(Color.GREEN);
|
||||
else if (logRecord.getLevel() == Level.CONFIG) ansi = ansi().fgBright(Color.BLUE);
|
||||
else if (logRecord.getLevel() == Level.FINE) ansi = ansi().fg(Color.CYAN);
|
||||
else if (logRecord.getLevel() == Level.FINER) ansi = ansi().fg(Color.MAGENTA);
|
||||
else if (logRecord.getLevel() == Level.FINEST) ansi = ansi().fgBright(Color.BLACK);
|
||||
else ansi = ansi().fg(Color.DEFAULT);
|
||||
String format = ansi.bold().a(Attribute.UNDERLINE).a("%1$tb %1$td, %1$tY %1$tl:%1$tM:%1$tS %1$Tp %2$s %4$s:").boldOff().a(Attribute.UNDERLINE_OFF).a("%n%5$s%6$s").reset().a("%n").toString();
|
||||
return String.format(format, zdt, source, logRecord.getLoggerName(), logRecord.getLevel().getLocalizedName(), message, throwable);
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
private static PrintStream printStreamLogger(Logger logger, Level level) {
|
||||
return new PrintStream(new OutputStream() {
|
||||
private final StringBuilder stringBuilder = new StringBuilder();
|
||||
|
||||
@Override
|
||||
public final void write(int i) throws IOException {
|
||||
if (i == '\n') {
|
||||
logger.log(level, stringBuilder::toString);
|
||||
stringBuilder.setLength(0);
|
||||
} else
|
||||
stringBuilder.appendCodePoint(i);
|
||||
}
|
||||
});
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,12 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc4388.utility;
|
||||
|
||||
/** Add your docs here. */
|
||||
public class DataLogging {
|
||||
public DataLogging() {
|
||||
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,20 @@
|
||||
package frc4388.utility.controller;
|
||||
|
||||
import static frc4388.robot.Constants.OIConstants.LEFT_AXIS_DEADBAND;
|
||||
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
|
||||
public class DeadbandedRawXboxController extends RawXboxController {
|
||||
public DeadbandedRawXboxController(int port) { super(port); }
|
||||
@Override public double getLeftX() { return skewToDeadzonedCircle(super.getLeftX(), super.getLeftY()).getX(); }
|
||||
@Override public double getLeftY() { return skewToDeadzonedCircle(super.getLeftX(), super.getLeftY()).getY(); }
|
||||
@Override public double getRightX() { return skewToDeadzonedCircle(super.getRightX(), super.getRightY()).getX(); }
|
||||
@Override public double getRightY() { return skewToDeadzonedCircle(super.getRightX(), super.getRightY()).getY(); }
|
||||
public static Translation2d skewToDeadzonedCircle(double x, double y) {
|
||||
Translation2d translation2d = new Translation2d(x, y);
|
||||
double magnitude = translation2d.getNorm();
|
||||
if (magnitude >= 1) return translation2d.div(magnitude);
|
||||
if (magnitude < LEFT_AXIS_DEADBAND) return new Translation2d(0,0);
|
||||
return translation2d;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,21 @@
|
||||
package frc4388.utility.controller;
|
||||
|
||||
import static frc4388.robot.Constants.OIConstants.LEFT_AXIS_DEADBAND;
|
||||
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.wpilibj.XboxController;
|
||||
|
||||
public class DeadbandedXboxController extends XboxController {
|
||||
public DeadbandedXboxController(int port) { super(port); }
|
||||
@Override public double getLeftX() { return skewToDeadzonedCircle(super.getLeftX(), super.getLeftY()).getX(); }
|
||||
@Override public double getLeftY() { return skewToDeadzonedCircle(super.getLeftX(), super.getLeftY()).getY(); }
|
||||
@Override public double getRightX() { return skewToDeadzonedCircle(super.getRightX(), super.getRightY()).getX(); }
|
||||
@Override public double getRightY() { return skewToDeadzonedCircle(super.getRightX(), super.getRightY()).getY(); }
|
||||
public static Translation2d skewToDeadzonedCircle(double x, double y) {
|
||||
Translation2d translation2d = new Translation2d(x, y);
|
||||
double magnitude = translation2d.getNorm();
|
||||
if (magnitude >= 1) return translation2d.div(magnitude);
|
||||
if (magnitude < LEFT_AXIS_DEADBAND) return new Translation2d(0,0);
|
||||
return translation2d;
|
||||
}
|
||||
}
|
||||
@@ -1,21 +0,0 @@
|
||||
package frc4388.utility.controller;
|
||||
|
||||
/**
|
||||
* Add your docs here.
|
||||
*/
|
||||
public interface IHandController {
|
||||
|
||||
public double getLeftXAxis();
|
||||
|
||||
public double getLeftYAxis();
|
||||
|
||||
public double getRightXAxis();
|
||||
|
||||
public double getRightYAxis();
|
||||
|
||||
public double getLeftTriggerAxis();
|
||||
|
||||
public double getRightTriggerAxis();
|
||||
|
||||
public int getDpadAngle();
|
||||
}
|
||||
@@ -0,0 +1,241 @@
|
||||
package frc4388.utility.controller;
|
||||
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.XboxController;
|
||||
|
||||
public class RawXboxController extends XboxController {
|
||||
private final int m_port;
|
||||
|
||||
public RawXboxController(int port) {
|
||||
super(port);
|
||||
if (port < 0 || port >= DriverStation.kJoystickPorts)
|
||||
throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
|
||||
m_port = port;
|
||||
}
|
||||
|
||||
private static class HALJoystickButtons {
|
||||
public int m_buttons;
|
||||
public byte m_count;
|
||||
}
|
||||
|
||||
private static class HALJoystickAxes {
|
||||
public float[] m_axes;
|
||||
public short m_count;
|
||||
|
||||
HALJoystickAxes(int count) {
|
||||
m_axes = new float[count];
|
||||
}
|
||||
}
|
||||
|
||||
private static class HALJoystickPOVs {
|
||||
public short[] m_povs;
|
||||
public short m_count;
|
||||
|
||||
HALJoystickPOVs(int count) {
|
||||
m_povs = new short[count];
|
||||
for (int i = 0; i < count; i++) {
|
||||
m_povs[i] = -1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
private static final double JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL = 1.0;
|
||||
private static double m_nextMessageTime;
|
||||
|
||||
private HALJoystickAxes m_joystickAxes = new HALJoystickAxes(HAL.kMaxJoystickAxes);
|
||||
private HALJoystickPOVs m_joystickPOVs = new HALJoystickPOVs(HAL.kMaxJoystickAxes);
|
||||
private HALJoystickButtons m_joystickButtons = new HALJoystickButtons();
|
||||
|
||||
// Joystick button rising/falling edge flags
|
||||
private int m_joystickButtonsPressed = 0;
|
||||
private int m_joystickButtonsReleased = 0;
|
||||
|
||||
private static final ByteBuffer m_buttonCountBuffer = ByteBuffer.allocateDirect(1);
|
||||
|
||||
@Override
|
||||
public double getRawAxis(int axis) {
|
||||
return getStickAxis(axis);
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean getRawButton(int button) {
|
||||
return getStickButton((byte) button);
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean getRawButtonPressed(int button) {
|
||||
return getStickButtonPressed((byte) button);
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean getRawButtonReleased(int button) {
|
||||
return getStickButtonReleased(button);
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getPOV(int pov) {
|
||||
return getStickPOV(pov);
|
||||
}
|
||||
|
||||
/**
|
||||
* The state of one joystick button. Button indexes begin at 1.
|
||||
*
|
||||
* @param button The button index, beginning at 1.
|
||||
* @return The state of the joystick button.
|
||||
*/
|
||||
public boolean getStickButton(final int button) {
|
||||
if (button <= 0) {
|
||||
reportJoystickUnpluggedError();
|
||||
return false;
|
||||
}
|
||||
if (button <= m_joystickButtons.m_count) {
|
||||
return (m_joystickButtons.m_buttons & 1 << (button - 1)) != 0;
|
||||
}
|
||||
reportJoystickUnpluggedWarning(button, m_port);
|
||||
return false;
|
||||
}
|
||||
|
||||
/**
|
||||
* Whether one joystick button was pressed since the last check. Button indexes begin at 1.
|
||||
*
|
||||
* @param button The button index, beginning at 1.
|
||||
* @return Whether the joystick button was pressed since the last check.
|
||||
*/
|
||||
public boolean getStickButtonPressed(final int button) {
|
||||
getData();
|
||||
if (button <= 0) {
|
||||
reportJoystickUnpluggedError();
|
||||
return false;
|
||||
}
|
||||
if (button <= m_joystickButtons.m_count) {
|
||||
// If button was pressed, clear flag and return true
|
||||
if ((m_joystickButtonsPressed & 1 << (button - 1)) != 0) {
|
||||
m_joystickButtonsPressed &= ~(1 << (button - 1));
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
reportJoystickUnpluggedWarning(button, m_port);
|
||||
return false;
|
||||
}
|
||||
|
||||
/**
|
||||
* Whether one joystick button was released since the last check. Button indexes begin at 1.
|
||||
*
|
||||
* @param button The button index, beginning at 1.
|
||||
* @return Whether the joystick button was released since the last check.
|
||||
*/
|
||||
public boolean getStickButtonReleased(final int button) {
|
||||
getData();
|
||||
if (button <= 0) {
|
||||
reportJoystickUnpluggedError();
|
||||
return false;
|
||||
}
|
||||
if (button <= m_joystickButtons.m_count) {
|
||||
// If button was released, clear flag and return true
|
||||
if ((m_joystickButtonsReleased & 1 << (button - 1)) != 0) {
|
||||
m_joystickButtonsReleased &= ~(1 << (button - 1));
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
reportJoystickUnpluggedWarning(button, m_port);
|
||||
return false;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the value of the axis on a joystick. This depends on the mapping of the joystick connected to
|
||||
* the specified port.
|
||||
*
|
||||
* @param axis The analog axis value to read from the joystick.
|
||||
* @return The value of the axis on the joystick.
|
||||
*/
|
||||
public double getStickAxis(int axis) {
|
||||
getData();
|
||||
if (axis < 0 || axis >= HAL.kMaxJoystickAxes) {
|
||||
throw new IllegalArgumentException("Joystick axis is out of range");
|
||||
}
|
||||
if (axis < m_joystickAxes.m_count) {
|
||||
return m_joystickAxes.m_axes[axis];
|
||||
}
|
||||
reportJoystickUnpluggedWarning(axis, m_port);
|
||||
return 0.0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the state of a POV on the joystick.
|
||||
*
|
||||
* @param pov The POV to read.
|
||||
* @return the angle of the POV in degrees, or -1 if the POV is not pressed.
|
||||
*/
|
||||
public int getStickPOV(int pov) {
|
||||
getData();
|
||||
if (pov < 0 || pov >= HAL.kMaxJoystickPOVs) {
|
||||
throw new IllegalArgumentException("Joystick POV is out of range");
|
||||
}
|
||||
if (pov < m_joystickPOVs.m_count) {
|
||||
return m_joystickPOVs.m_povs[pov];
|
||||
}
|
||||
reportJoystickUnpluggedWarning(pov, m_port);
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* The state of the buttons on the joystick.
|
||||
*
|
||||
* @return The state of the buttons on the joystick.
|
||||
*/
|
||||
public int getStickButtons() {
|
||||
getData();
|
||||
return m_joystickButtons.m_buttons;
|
||||
}
|
||||
|
||||
protected void getData() {
|
||||
// Get the status of all of the joysticks
|
||||
byte stick = (byte) m_port;
|
||||
m_joystickAxes.m_count = HAL.getJoystickAxes(stick, m_joystickAxes.m_axes);
|
||||
m_joystickPOVs.m_count = HAL.getJoystickPOVs(stick, m_joystickPOVs.m_povs);
|
||||
m_joystickButtons.m_buttons = HAL.getJoystickButtons(stick, m_buttonCountBuffer);
|
||||
m_joystickButtons.m_count = m_buttonCountBuffer.get(0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Reports errors related to unplugged joysticks Throttles the errors so that they don't overwhelm
|
||||
* the DS.
|
||||
*/
|
||||
private static void reportJoystickUnpluggedError(String message) {
|
||||
double currentTime = Timer.getFPGATimestamp();
|
||||
if (currentTime > m_nextMessageTime) {
|
||||
DriverStation.reportError(message, false);
|
||||
m_nextMessageTime = currentTime + JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Reports errors related to unplugged joysticks Throttles the errors so that they don't overwhelm
|
||||
* the DS.
|
||||
*/
|
||||
private static void reportJoystickUnpluggedWarning(String message) {
|
||||
if (DriverStation.isFMSAttached() || !DriverStation.isJoystickConnectionWarningSilenced()) {
|
||||
double currentTime = Timer.getFPGATimestamp();
|
||||
if (currentTime > m_nextMessageTime) {
|
||||
DriverStation.reportWarning(message, false);
|
||||
m_nextMessageTime = currentTime + JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
private static void reportJoystickUnpluggedWarning(final int pov, final int stick) {
|
||||
reportJoystickUnpluggedWarning("Joystick POV " + pov + " on port " + stick + " not available, check if controller is plugged in");
|
||||
}
|
||||
|
||||
private static void reportJoystickUnpluggedError() {
|
||||
reportJoystickUnpluggedError("Button indexes begin at 1 in WPILib for C++ and Java\n");
|
||||
}
|
||||
}
|
||||
@@ -1,218 +0,0 @@
|
||||
package frc4388.utility.controller;
|
||||
|
||||
import edu.wpi.first.wpilibj.Joystick;
|
||||
|
||||
/**
|
||||
* This is a wrapper for the WPILib Joystick class that represents an XBox
|
||||
* controller.
|
||||
* @author frc1675
|
||||
*/
|
||||
public class XboxController implements IHandController
|
||||
{
|
||||
public static final int LEFT_X_AXIS = 0;
|
||||
public static final int LEFT_Y_AXIS = 1;
|
||||
public static final int LEFT_TRIGGER_AXIS = 2;
|
||||
public static final int RIGHT_TRIGGER_AXIS = 3;
|
||||
public static final int RIGHT_X_AXIS = 4;
|
||||
public static final int RIGHT_Y_AXIS = 5;
|
||||
public static final int LEFT_RIGHT_DPAD_AXIS = 6;
|
||||
public static final int TOP_BOTTOM_DPAD_AXIS = 6;
|
||||
|
||||
public static final int A_BUTTON = 1;
|
||||
public static final int B_BUTTON = 2;
|
||||
public static final int X_BUTTON = 3;
|
||||
public static final int Y_BUTTON = 4;
|
||||
public static final int LEFT_BUMPER_BUTTON = 5;
|
||||
public static final int RIGHT_BUMPER_BUTTON = 6;
|
||||
public static final int BACK_BUTTON = 7;
|
||||
public static final int START_BUTTON = 8;
|
||||
|
||||
public static final int LEFT_JOYSTICK_BUTTON = 9;
|
||||
public static final int RIGHT_JOYSTICK_BUTTON = 10;
|
||||
|
||||
private static final double LEFT_DPAD_TOLERANCE = -0.9;
|
||||
private static final double RIGHT_DPAD_TOLERANCE = 0.9;
|
||||
private static final double BOTTOM_DPAD_TOLERANCE = -0.9;
|
||||
private static final double TOP_DPAD_TOLERANCE = 0.9;
|
||||
|
||||
private static final double LEFT_TRIGGER_TOLERANCE = 0.5;
|
||||
private static final double RIGHT_TRIGGER_TOLERANCE = 0.5;
|
||||
|
||||
private static final double RIGHT_AXIS_UP_TOLERANCE = -0.9;
|
||||
private static final double RIGHT_AXIS_DOWN_TOLERANCE = 0.9;
|
||||
private static final double RIGHT_AXIS_RIGHT_TOLERANCE = 0.9;
|
||||
private static final double RIGHT_AXIS_LEFT_TOLERANCE = -0.9;
|
||||
|
||||
private static final double LEFT_AXIS_UP_TOLERANCE = -0.9;
|
||||
private static final double LEFT_AXIS_DOWN_TOLERANCE = 0.9;
|
||||
private static final double LEFT_AXIS_RIGHT_TOLERANCE = 0.9;
|
||||
private static final double LEFT_AXIS_LEFT_TOLERANCE = -0.9;
|
||||
|
||||
private static final double DEADZONE = 0.1;
|
||||
|
||||
private Joystick m_stick;
|
||||
|
||||
/**
|
||||
* Add your docs here.
|
||||
*/
|
||||
public XboxController(int portNumber){
|
||||
m_stick = new Joystick(portNumber);
|
||||
}
|
||||
|
||||
/**
|
||||
* Add your docs here.
|
||||
*/
|
||||
public Joystick getJoyStick() {
|
||||
return m_stick;
|
||||
}
|
||||
|
||||
/**
|
||||
* Checks if the input falls within the deadzone.
|
||||
* @param input from an axis on the controller
|
||||
* @return true if input falls in deadzone, false if input falls outside deadzone
|
||||
*/
|
||||
private boolean inDeadZone(double input){
|
||||
return (Math.abs(input) < DEADZONE);
|
||||
}
|
||||
|
||||
/**
|
||||
* Updates an input to have a deadzone around the 0 position
|
||||
* @param input from an axis on the controller
|
||||
* @return updated input
|
||||
*/
|
||||
private double getAxisWithDeadZoneCheck(double input){
|
||||
if(inDeadZone(input)){
|
||||
return 0.0;
|
||||
} else {
|
||||
return input;
|
||||
}
|
||||
}
|
||||
|
||||
public boolean getAButton(){
|
||||
return m_stick.getRawButton(A_BUTTON);
|
||||
}
|
||||
|
||||
public boolean getXButton(){
|
||||
return m_stick.getRawButton(X_BUTTON);
|
||||
}
|
||||
|
||||
public boolean getBButton(){
|
||||
return m_stick.getRawButton(B_BUTTON);
|
||||
}
|
||||
|
||||
public boolean getYButton(){
|
||||
return m_stick.getRawButton(Y_BUTTON);
|
||||
}
|
||||
|
||||
public boolean getBackButton(){
|
||||
return m_stick.getRawButton(BACK_BUTTON);
|
||||
}
|
||||
|
||||
public boolean getStartButton(){
|
||||
return m_stick.getRawButton(START_BUTTON);
|
||||
}
|
||||
|
||||
public boolean getLeftBumperButton(){
|
||||
return m_stick.getRawButton(LEFT_BUMPER_BUTTON);
|
||||
}
|
||||
|
||||
public boolean getRightBumperButton(){
|
||||
return m_stick.getRawButton(RIGHT_BUMPER_BUTTON);
|
||||
}
|
||||
|
||||
public boolean getLeftJoystickButton(){
|
||||
return m_stick.getRawButton(LEFT_JOYSTICK_BUTTON);
|
||||
}
|
||||
|
||||
public boolean getRightJoystickButton(){
|
||||
return m_stick.getRawButton(RIGHT_JOYSTICK_BUTTON);
|
||||
}
|
||||
|
||||
public double getLeftXAxis(){
|
||||
return getAxisWithDeadZoneCheck(m_stick.getRawAxis(LEFT_X_AXIS));
|
||||
}
|
||||
|
||||
public double getLeftYAxis(){
|
||||
return getAxisWithDeadZoneCheck(m_stick.getRawAxis(LEFT_Y_AXIS));
|
||||
}
|
||||
|
||||
public double getRightXAxis(){
|
||||
return getAxisWithDeadZoneCheck(m_stick.getRawAxis(RIGHT_X_AXIS));
|
||||
}
|
||||
|
||||
public double getRightYAxis(){
|
||||
return getAxisWithDeadZoneCheck(m_stick.getRawAxis(RIGHT_Y_AXIS));
|
||||
}
|
||||
|
||||
public double getLeftTriggerAxis(){
|
||||
return getAxisWithDeadZoneCheck(m_stick.getRawAxis(LEFT_TRIGGER_AXIS));
|
||||
}
|
||||
|
||||
public double getRightTriggerAxis(){
|
||||
return getAxisWithDeadZoneCheck(m_stick.getRawAxis(RIGHT_TRIGGER_AXIS));
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the angle input from the dpad.
|
||||
* @return -1 if nothing is pressed, or the angle of the button pressed. 0 = up, 90 = right, etc.
|
||||
*/
|
||||
public int getDpadAngle() {
|
||||
return m_stick.getPOV(0);
|
||||
}
|
||||
|
||||
public boolean getDPadLeft(){
|
||||
return (m_stick.getRawAxis(LEFT_RIGHT_DPAD_AXIS) < LEFT_DPAD_TOLERANCE);
|
||||
}
|
||||
|
||||
public boolean getDPadRight(){
|
||||
return (m_stick.getRawAxis(LEFT_RIGHT_DPAD_AXIS) > RIGHT_DPAD_TOLERANCE);
|
||||
}
|
||||
|
||||
public boolean getDPadTop(){
|
||||
return (m_stick.getRawAxis(TOP_BOTTOM_DPAD_AXIS) < TOP_DPAD_TOLERANCE);
|
||||
}
|
||||
|
||||
public boolean getDPadBottom(){
|
||||
return (m_stick.getRawAxis(TOP_BOTTOM_DPAD_AXIS) > BOTTOM_DPAD_TOLERANCE);
|
||||
}
|
||||
|
||||
public boolean getLeftTrigger(){
|
||||
return (getLeftTriggerAxis() > LEFT_TRIGGER_TOLERANCE);
|
||||
}
|
||||
|
||||
public boolean getRightTrigger(){
|
||||
return (getRightTriggerAxis() > RIGHT_TRIGGER_TOLERANCE);
|
||||
}
|
||||
|
||||
public boolean getRightAxisUpTrigger(){
|
||||
return (getRightYAxis() < RIGHT_AXIS_UP_TOLERANCE);
|
||||
}
|
||||
|
||||
public boolean getRightAxisDownTrigger(){
|
||||
return (getRightYAxis() > RIGHT_AXIS_DOWN_TOLERANCE);
|
||||
}
|
||||
|
||||
public boolean getRightAxisLeftTrigger(){
|
||||
return (getRightXAxis() > RIGHT_AXIS_LEFT_TOLERANCE);
|
||||
}
|
||||
|
||||
public boolean getRightAxisRightTrigger(){
|
||||
return (getRightXAxis() > RIGHT_AXIS_RIGHT_TOLERANCE);
|
||||
}
|
||||
|
||||
public boolean getLeftAxisUpTrigger(){
|
||||
return (getLeftYAxis() < LEFT_AXIS_UP_TOLERANCE);
|
||||
}
|
||||
|
||||
public boolean getLeftAxisDownTrigger(){
|
||||
return (getLeftYAxis() > LEFT_AXIS_DOWN_TOLERANCE);
|
||||
}
|
||||
|
||||
public boolean getLeftAxisLeftTrigger(){
|
||||
return (getLeftXAxis() > LEFT_AXIS_LEFT_TOLERANCE);
|
||||
}
|
||||
|
||||
public boolean getLeftAxisRightTrigger(){
|
||||
return (getLeftXAxis() > LEFT_AXIS_RIGHT_TOLERANCE);
|
||||
}
|
||||
}
|
||||
@@ -1,50 +0,0 @@
|
||||
package frc4388.utility.controller;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.button.Button;
|
||||
|
||||
/**
|
||||
* Mapping for the Xbox controller triggers to allow triggers to be defined as
|
||||
* buttons in {@link frc4388.robot.OI}. Checks to see if the given trigger
|
||||
* exceeds a tolerance defined in {@link XboxController}.
|
||||
*/
|
||||
public class XboxTriggerButton extends Button {
|
||||
public static final int RIGHT_TRIGGER = 0;
|
||||
public static final int LEFT_TRIGGER = 1;
|
||||
public static final int RIGHT_AXIS_UP_TRIGGER = 2;
|
||||
public static final int RIGHT_AXIS_DOWN_TRIGGER = 3;
|
||||
public static final int RIGHT_AXIS_RIGHT_TRIGGER = 4;
|
||||
public static final int RIGHT_AXIS_LEFT_TRIGGER = 5;
|
||||
public static final int LEFT_AXIS_UP_TRIGGER = 6;
|
||||
public static final int LEFT_AXIS_DOWN_TRIGGER = 7;
|
||||
public static final int LEFT_AXIS_RIGHT_TRIGGER = 8;
|
||||
public static final int LEFT_AXIS_LEFT_TRIGGER = 9;
|
||||
|
||||
private XboxController m_controller;
|
||||
private int m_trigger;
|
||||
|
||||
/**
|
||||
* Creates a Trigger-Button mapped to a specific Xbox controller and trigger
|
||||
*/
|
||||
public XboxTriggerButton(XboxController controller, int trigger) {
|
||||
m_controller = controller;
|
||||
m_trigger = trigger;
|
||||
}
|
||||
|
||||
/** {@inheritDoc} */
|
||||
@Override
|
||||
public boolean get() {
|
||||
switch (m_trigger) {
|
||||
case RIGHT_TRIGGER: return m_controller.getRightTrigger();
|
||||
case LEFT_TRIGGER: return m_controller.getLeftTrigger();
|
||||
case RIGHT_AXIS_UP_TRIGGER: return m_controller.getRightAxisUpTrigger();
|
||||
case RIGHT_AXIS_DOWN_TRIGGER: return m_controller.getRightAxisDownTrigger();
|
||||
case RIGHT_AXIS_RIGHT_TRIGGER: return m_controller.getRightAxisRightTrigger();
|
||||
case RIGHT_AXIS_LEFT_TRIGGER: return m_controller.getRightAxisLeftTrigger();
|
||||
case LEFT_AXIS_UP_TRIGGER: return m_controller.getLeftAxisUpTrigger();
|
||||
case LEFT_AXIS_DOWN_TRIGGER: return m_controller.getLeftAxisDownTrigger();
|
||||
case LEFT_AXIS_RIGHT_TRIGGER: return m_controller.getLeftAxisRightTrigger();
|
||||
case LEFT_AXIS_LEFT_TRIGGER: return m_controller.getLeftAxisLeftTrigger();
|
||||
default: return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user