Skip to content

Commit

Permalink
up the D, move operator controls to operator
Browse files Browse the repository at this point in the history
  • Loading branch information
IsaacThoman committed Oct 18, 2023
1 parent f08248b commit 47fb704
Show file tree
Hide file tree
Showing 3 changed files with 16 additions and 20 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ public static class ArmConstants {

public static final double stageTwokP = 0.9; //0.8
public static final double stageTwokI = 0.001; //0.001
public static final double stageTwokD = 2; //2
public static final double stageTwokD = 3; //2
public static final double stageTwokF = 0.0;


Expand Down
32 changes: 14 additions & 18 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,21 +4,15 @@

package frc.robot;

import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;
import frc.robot.Constants.OperatorConstants;
import frc.robot.commands.*;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.subsystems.EndEffectorSub;
import frc.robot.subsystems.StateControllerSub;
import frc.robot.subsystems.arm.Arm;
import frc.robot.subsystems.arm.StageOneSub;
import frc.robot.subsystems.arm.StageTwoSub;
import frc.robot.subsystems.drive.SwerveSubsystem;
import frc.robot.subsystems.drive.VisionSubsystem;

Expand All @@ -32,6 +26,7 @@ public class RobotContainer {
// The robot's subsystems and commands are defined here...

CommandXboxController driver = new CommandXboxController(0);
CommandXboxController operator = new CommandXboxController(1);

VisionSubsystem visionSub = new VisionSubsystem();
SwerveSubsystem swerveSubsystem = new SwerveSubsystem(visionSub);
Expand Down Expand Up @@ -68,20 +63,21 @@ public RobotContainer() {
driver.back().onTrue(new InstantCommand(swerveSubsystem::toggleFieldOriented));


driver.a().onTrue(new InstantCommand(stateController::setArmModeToIntaking));
driver.b().onTrue(new InstantCommand(stateController::setArmModeToHolding));
driver.y().onTrue(new InstantCommand(stateController::setArmModeToPlacing));
driver.x().onTrue(new InstantCommand(stateController::setArmModeToPostPlacing));
operator.a().onTrue(new InstantCommand(stateController::setArmModeToIntaking));
operator.b().onTrue(new InstantCommand(stateController::setArmModeToHolding));
operator.y().onTrue(new InstantCommand(stateController::setArmModeToPlacing));
operator.x().onTrue(new InstantCommand(stateController::setArmModeToPostPlacing));

driver.povUp().onTrue(new InstantCommand(stateController::setArmLevelBottom));
driver.povRight().onTrue(new InstantCommand(stateController::setArmLevelMiddle));
driver.povLeft().onTrue(new InstantCommand(stateController::setArmLevelMiddle));
driver.povDown().onTrue(new InstantCommand(stateController::setArmLevelTop));

driver.leftTrigger(0.5).onTrue(new InstantCommand(stateController::setItemConeFallen));
operator.povUp().onTrue(new InstantCommand(stateController::setArmLevelBottom));
operator.povRight().onTrue(new InstantCommand(stateController::setArmLevelMiddle));
operator.povLeft().onTrue(new InstantCommand(stateController::setArmLevelMiddle));
operator.povDown().onTrue(new InstantCommand(stateController::setArmLevelTop));

driver.leftBumper().onTrue(new InstantCommand(stateController::setItemConeUpright));
driver.rightBumper().onTrue(new InstantCommand(stateController::setItemCubeFallen));
operator.leftTrigger(0.5).onTrue(new InstantCommand(stateController::setItemConeFallen));

operator.leftBumper().onTrue(new InstantCommand(stateController::setItemConeUpright));
operator.rightBumper().onTrue(new InstantCommand(stateController::setItemCube));
operator.rightTrigger(0.5).onTrue(new InstantCommand(stateController::setItemCube));


// Configure the trigger bindings
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/StateControllerSub.java
Original file line number Diff line number Diff line change
Expand Up @@ -222,7 +222,7 @@ public void setItemConeUpright() {
}


public void setItemCubeFallen(){
public void setItemCube(){
desiredState.itemType = ItemType.CUBE;
desiredState.itemIsFallen = ItemIsFallen.NOT_FALLEN;
}
Expand Down

0 comments on commit 47fb704

Please sign in to comment.