Skip to content

Commit

Permalink
Moves
Browse files Browse the repository at this point in the history
  • Loading branch information
Craptop committed Dec 6, 2023
1 parent 2138d0f commit a110e39
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 13 deletions.
1 change: 1 addition & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@ public static class Intake {

public static final double UNLOADING_WAIT_TIME = 2f;
}

public final class Wrist {
public static final int DRIVER_CONTROLLER_PORT = 0;
public static final int WRIST_MOTOR_DEVICE_NUMBER = 16;
Expand Down
13 changes: 6 additions & 7 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,17 +4,14 @@

package frc.robot;

import frc.robot.subsystems.IntakeSubsystem;
import frc.robot.commands.StopIntakeMotorCommand;
import frc.robot.commands.IntakeCommand;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.commands.SequentialCommands;
import frc.robot.subsystems.WristSubsystem;
import frc.robot.commands.AdvancedIntakeSequence;
import frc.robot.commands.SequentialCommands;
import frc.robot.subsystems.IntakeSubsystem;
import frc.robot.subsystems.WristSubsystem;

/**
* This class is where the bulk of the robot should be declared. Since Command-based is a
Expand All @@ -34,15 +31,15 @@ public class RobotContainer {
/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {
// Configure the button bindings
driverB.y().onTrue(new SequentialCommands(wristSubsystem));

configureButtonBindings();

// } else if (driverB.leftTrigger().getAsBoolean()) {

// driverB.y().onTrue(new WristCommand(wristSubsystem, 0));
// driverB.a().onTrue(new WristCommand(wristSubsystem, 20));
// driverB.b().onTrue(new WristCommand(wristSubsystem, 40));
driverB.x().onTrue(new InstantCommand(() -> {}, wristSubsystem));

}

/**
Expand Down Expand Up @@ -78,6 +75,8 @@ public void containerMatchStarting() {
*/
private void configureButtonBindings() {
// intake and outtake
driverB.y().onTrue(new SequentialCommands(wristSubsystem));
driverB.x().onTrue(new InstantCommand(() -> {}, wristSubsystem));
driverB.rightTrigger().onTrue(new AdvancedIntakeSequence(intakeSubsystem, false, true));
driverB.leftTrigger().onTrue(new AdvancedIntakeSequence(intakeSubsystem, true, true));
driverB.rightBumper().onTrue(new AdvancedIntakeSequence(intakeSubsystem, false, false));
Expand Down
13 changes: 7 additions & 6 deletions src/main/java/frc/robot/subsystems/WristSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,9 @@ public WristSubsystem() {
this.wrist_motor = new TalonFX(Constants.Wrist.WRIST_MOTOR_DEVICE_NUMBER);
this.wrist_motor.configFactoryDefault();
this.wrist_motor.clearStickyFaults();
this.wrist_motor.configForwardSoftLimitThreshold(0);
this.wrist_motor.configReverseSoftLimitThreshold(degreesToTicks(90));
this.wrist_motor.configReverseSoftLimitEnable(true, 0);
//this.wrist_motor.configForwardSoftLimitThreshold(0);
//this.wrist_motor.configReverseSoftLimitThreshold(degreesToTicks(90));
//this.wrist_motor.configReverseSoftLimitEnable(true, 0);
this.wrist_motor.configForwardSoftLimitEnable(true, 0);
this.wrist_motor.setNeutralMode(NeutralMode.Coast);
this.wrist_motor.setSelectedSensorPosition(0);
Expand All @@ -43,12 +43,13 @@ public WristSubsystem() {
pidController = new PIDController(0.1, 0, 0);
WristTab.add(pidController);
WristTab.addNumber("Current Motor Position", wrist_motor::getSelectedSensorPosition);
WristTab.addNumber("Current motor angle", this::getCurrentAngle);
WristTab.addBoolean("Is at target", this::nearTargetAngle);
WristTab.addNumber("Target Angle", () -> this.targetAngle);
}
}

public static double degreesToTicks(double angle) {
return (angle*360d)/((Wrist.GEAR_RATIO * Wrist.TICKS));
return (angle * 360d) / ((Wrist.GEAR_RATIO * Wrist.TICKS));
}

public void setTargetAngle(double targetAngle) {
Expand All @@ -57,7 +58,7 @@ public void setTargetAngle(double targetAngle) {
}

public static double ticksToDegrees(double ticks) {
return ((ticks / Wrist.TICKS) * (Wrist.GEAR_RATIO/360));
return ((ticks / Wrist.TICKS) * (Wrist.GEAR_RATIO) / 360);
}

private double getCurrentAngle() {
Expand Down

0 comments on commit a110e39

Please sign in to comment.