Skip to content

Commit

Permalink
Arm Movement remake
Browse files Browse the repository at this point in the history
  • Loading branch information
JudeTh3Dude committed Feb 9, 2024
1 parent 218b311 commit 37ca977
Show file tree
Hide file tree
Showing 3 changed files with 30 additions and 12 deletions.
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ public static class SwerveDrivetrainConstants {

public static class ArmConstants {

public static final double MAXIMUM_ARM_DEGREES = 3;
public static final double MAXIMUM_ARM_DEGREES = 1;
public static final double MINIMUM_ARM_DEGREES = 0;

public static final double ARM_AMP_SHOOTING_DEGREES = 0;
Expand All @@ -105,6 +105,8 @@ public static class ArmConstants {
//public static final int LEFT_ENCODER_ID = 0;
public static final int RIGHT_MOTOR_ID = 0;
public static final int RIGHT_ENCODER_ID = 0;

public static final double DEGREES_PER_SECOND = 2.0;
}
}

21 changes: 14 additions & 7 deletions src/main/java/frc/robot/commands/ArmJoystickControl.java
Original file line number Diff line number Diff line change
@@ -1,11 +1,13 @@
package frc.robot.commands;

import frc.robot.Constants.ArmConstants;
import frc.robot.subsystems.Arm;

import frc.robot.utils.OptionButton;
import frc.robot.utils.OptionButton.ActivationMode;

import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.button.CommandJoystick;

public class ArmJoystickControl extends Command {
Expand All @@ -15,15 +17,21 @@ public class ArmJoystickControl extends Command {
private final OptionButton raiseArmButton;
private final OptionButton lowerArmButton;



private double armPos;

public ArmJoystickControl(Arm arm, CommandJoystick joystick) {
this.arm = arm;
this.joystick = joystick;


lowerArmButton = new OptionButton(joystick, 101, ActivationMode.HOLD);
raiseArmButton = new OptionButton(joystick, 202, ActivationMode.HOLD);
lowerArmButton = new OptionButton(joystick, 11, ActivationMode.HOLD);
raiseArmButton = new OptionButton(joystick, 12, ActivationMode.HOLD);

joystick.povUp().onTrue(Commands.run(arm::setArmToSpeakerPosition));
joystick.povRight().onTrue(Commands.run(arm::setArmToAmpPosition));
joystick.povDown().onTrue(Commands.run(arm::setArmToIntakePosition));

addRequirements(arm);
}
Expand All @@ -35,10 +43,9 @@ public ArmJoystickControl(Arm arm, CommandJoystick joystick) {
@Override
public void execute() {

armPos += raiseArmButton.getStateAsInt();
armPos -= lowerArmButton.getStateAsInt();


arm.setArmAngleDegrees(armPos);
//two buttons determining the raising and lowering of the arm
arm.changeArmAngleDegreesBy(Double.valueOf(raiseArmButton.getStateAsInt()) * TimedRobot.kDefaultPeriod * ArmConstants.DEGREES_PER_SECOND);
arm.changeArmAngleDegreesBy(Double.valueOf(-lowerArmButton.getStateAsInt()) * TimedRobot.kDefaultPeriod * ArmConstants.DEGREES_PER_SECOND);
}
}
17 changes: 13 additions & 4 deletions src/main/java/frc/robot/subsystems/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -58,13 +58,20 @@ public Arm(int leftMotorId, int rightMotorId, int rightEncoderId) {

}

public void setArmAngleDegrees(double desiredDegree) {
//maximum should ALWAYS be a greater value then minimum
if (desiredDegree < ArmConstants.MAXIMUM_ARM_DEGREES || ArmConstants.MINIMUM_ARM_DEGREES > desiredDegree) {
armRotation2d = Rotation2d.fromDegrees(desiredDegree);
// public void setArmAngleDegrees(double desiredDegree) {
// //maximum should ALWAYS be a greater value then minimum
// if (desiredDegree < ArmConstants.MAXIMUM_ARM_DEGREES || ArmConstants.MINIMUM_ARM_DEGREES > desiredDegree) {
// armRotation2d = Rotation2d.fromDegrees(desiredDegree);
// }
// }

public void changeArmAngleDegreesBy(double desiredDegrees) {
if (armRotation2d.getDegrees() < ArmConstants.MAXIMUM_ARM_DEGREES || ArmConstants.MINIMUM_ARM_DEGREES > armRotation2d.getDegrees()) {
armRotation2d = Rotation2d.fromDegrees(armRotation2d.getDegrees() + desiredDegrees);
}
}


public void setArmToAmpPosition() {
armRotation2d = Rotation2d.fromRadians(ArmConstants.ARM_AMP_SHOOTING_DEGREES);
}
Expand All @@ -84,6 +91,8 @@ public void setArmToIntakePosition() {
public void periodic() {
// This method will be called once per scheduler run



final double armSpeed = armRaisePIDController.calculate(armPosition.refresh().getValueAsDouble(),armRotation2d.getRotations());
leftArmMotor.set(armSpeed);
rightArmMotor.set(armSpeed);
Expand Down

0 comments on commit 37ca977

Please sign in to comment.