Skip to content

Commit

Permalink
massive controls change.
Browse files Browse the repository at this point in the history
  • Loading branch information
anorakthegreat committed Jan 17, 2025
1 parent 3548b59 commit 6b302d3
Show file tree
Hide file tree
Showing 5 changed files with 240 additions and 125 deletions.
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
// 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 org.team100.frc2024.Climber;

Expand Down
4 changes: 2 additions & 2 deletions comp/src/main/java/org/team100/frc2024/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ public RobotContainer(TimedRobot100 robot) throws IOException {

final TrajectoryVisualization viz = new TrajectoryVisualization(fieldLogger);
final DriverControl driverControl = new DriverControlProxy(logger, async);
final OperatorControl operatorControl = new OperatorControlProxy(async);
final OperatorControlProxy operatorControl = new OperatorControlProxy(async);
final SwerveKinodynamics swerveKinodynamics = SwerveKinodynamicsFactory.get();


Expand Down Expand Up @@ -216,7 +216,7 @@ public RobotContainer(TimedRobot100 robot) throws IOException {

// DEFAULT COMMANDS
m_drive.setDefaultCommand(driveManually);
m_climber.setDefaultCommand(new ClimberRotate(m_climber, 0.2, operatorControl::ramp));
m_climber.setDefaultCommand(new ClimberRotate(m_climber, 0.2, operatorControl::climb));


//DRIVER BUTTONS
Expand Down
79 changes: 58 additions & 21 deletions lib/src/main/java/org/team100/lib/hid/OperatorControl.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,63 +12,100 @@ default String getHIDName() {
return "No HID Found!!";
}

default boolean pivotToAmpPosition() {
default boolean getButton1() {
return false;
}

default boolean outtake() {
default boolean getButton2() {
return false;
}

default boolean feed() {
default boolean getButton3() {
return false;
}

default boolean intake() {
default boolean getButton4() {
return false;
}

default double ramp() {
return 0.0;
default boolean getButton5() {
return false;
}

// this exists to bind to commands we don't want to run,
// but we don't want them to rot either.
default boolean never() {
default boolean getButton6() {
return false;
}

default boolean homeClimber() {
default boolean getButton7() {
return false;
}

default double leftClimb() {
return 0;
default boolean getButton8() {
return false;
}

default double rightClimb() {
return 0;
default boolean getButton9() {
return false;
}

/** Put the climber hooks in the "up" position. */
default boolean climbUpPosition() {
default boolean getButton10() {
return false;
}

/** Put the climber hooks in the "down" position. */
default boolean climbDownPosition() {
default boolean getButton11() {
return false;
}

default boolean feedToAmp() {
default boolean getButton12() {
return false;
}

default boolean outtakeFromAmp() {
default boolean getButton13() {
return false;
}

default boolean testShoot() {
default boolean getButton14() {
return false;
}

default boolean getButton15() {
return false;
}

default double getAxis1() {
return 0.0;
}

default double getAxis2() {
return 0.0;
}

default double getAxis3() {
return 0.0;
}

default double getAxis4() {
return 0.0;
}

default double getAxis5() {
return 0.0;
}

default double getAxis6() {
return 0.0;
}

default double getAxis7() {
return 0.0;
}

default double getAxis8() {
return 0.0;
}

default double getAxis9() {
return 0.0;
}

}
175 changes: 113 additions & 62 deletions lib/src/main/java/org/team100/lib/hid/OperatorControlProxy.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,8 @@
package org.team100.lib.hid;

import java.util.HashMap;
import java.util.Map;

import org.team100.lib.async.Async;
import org.team100.lib.util.Util;

Expand All @@ -13,21 +16,95 @@ public class OperatorControlProxy implements OperatorControl {
private static class NoOperatorControl implements OperatorControl {
}


public enum GamepadControls {
A(1),
B(2),
X(3),
Y(4),
LeftBumper(5),
RightBumper(6),
RightStickButton(7),
LeftStickButton(8),
Start(9),
POVUp(10),
POVRight(11),
POVDown(12),
POVLeft(13),
RightYAxis(1),
RightXAxis(2),
LeftYAxis(3),
LeftXAxis(4),
RightTriggerAxis(5),
LeftTriggerAxis(6);


private final int value;

GamepadControls(int value) {
this.value = value;
}

public int getValue() {
return value;
}
}

private static final int kPort = 1;
private static final double kFreq = 1;

private String m_name;
private OperatorControl m_operatorControl;

private final Map<String, Integer> genericButtons = new HashMap<>();
private final Map<String, Integer> genericAxis = new HashMap<>();

private final Map<String, GamepadControls> gamepadButtons = new HashMap<>();
private final Map<String, GamepadControls> gamepadAxis = new HashMap<>();



/**
* The async is just to scan for control updates, maybe don't use a whole thread
* for it.
*/
public OperatorControlProxy(Async async) {
populateGenericControls();
populateGamePadControls();

refresh();
async.addPeriodic(this::refresh, kFreq, "OperatorControlProxy");
}



public void populateGenericControls() {
// Map each action name to its corresponding method
genericAxis.put("climb", 1);

}

public void populateGamePadControls() {
// Map each action name to its corresponding method
gamepadAxis.put("climb", GamepadControls.RightYAxis);

}

public boolean retrieveButton(String action){
if(m_name == "F310" || m_name == "Xbox"){
return getButton(gamepadButtons.get(action).getValue());
}
return getButton(genericButtons.get(action));
}

public double retrieveAxis(String action){
if(m_name == "F310" || m_name == "Xbox"){
return getAxis(gamepadAxis.get(action).getValue());
}
return getAxis(genericAxis.get(action));
}


public void refresh() {
// name is blank if not connected
String name = DriverStation.getJoystickName(kPort);
Expand Down Expand Up @@ -60,79 +137,53 @@ private static OperatorControl getOperatorControl(String name) {
return new NoOperatorControl();
}

//MISC
@Override
public String getHIDName() {
return m_operatorControl.getHIDName();
}

@Override
public boolean pivotToAmpPosition() {
return m_operatorControl.pivotToAmpPosition();
}

@Override
public boolean outtake() {
return m_operatorControl.outtake();
}

@Override
public boolean intake() {
return m_operatorControl.intake();
}

@Override
public boolean never() {
return m_operatorControl.never();
}

@Override
public boolean feed() {
return m_operatorControl.feed();
}

@Override
public double ramp() {
return m_operatorControl.ramp();
}

@Override
public boolean homeClimber() {
return m_operatorControl.homeClimber();
}

@Override
public double leftClimb() {
return m_operatorControl.leftClimb();

//Generic Buttons
public boolean getButton(int buttonNumber) {
switch (buttonNumber) {
case 1: return m_operatorControl.getButton1();
case 2: return m_operatorControl.getButton2();
case 3: return m_operatorControl.getButton3();
case 4: return m_operatorControl.getButton4();
case 5: return m_operatorControl.getButton5();
case 6: return m_operatorControl.getButton6();
case 7: return m_operatorControl.getButton7();
case 8: return m_operatorControl.getButton8();
case 9: return m_operatorControl.getButton9();
case 10: return m_operatorControl.getButton10();
case 11: return m_operatorControl.getButton11();
case 12: return m_operatorControl.getButton12();
case 13: return m_operatorControl.getButton13();
default: throw new IllegalArgumentException("Invalid button number: " + buttonNumber);
}
}

@Override
public double rightClimb() {
return m_operatorControl.rightClimb();

//Generic Axis
public double getAxis(int axisNumber) {
switch (axisNumber) {
case 1: return m_operatorControl.getAxis1();
case 2: return m_operatorControl.getAxis2();
case 3: return m_operatorControl.getAxis3();
case 4: return m_operatorControl.getAxis4();
case 5: return m_operatorControl.getAxis5();
default: throw new IllegalArgumentException("Invalid button number: " + axisNumber);
}
}

@Override
public boolean climbUpPosition() {
return m_operatorControl.climbUpPosition();
}
//ACTIONS
public double climb(){
return retrieveAxis("climb");
}

@Override
public boolean climbDownPosition() {
return m_operatorControl.climbDownPosition();
}


@Override
public boolean feedToAmp() {
return m_operatorControl.feedToAmp();
}

@Override
public boolean outtakeFromAmp() {
return m_operatorControl.outtakeFromAmp();
}

@Override
public boolean testShoot() {
return m_operatorControl.testShoot();
}

}
Loading

0 comments on commit 6b302d3

Please sign in to comment.