From 66fdec9a2664591f2e4070a14252ad1fa539730f Mon Sep 17 00:00:00 2001 From: Nilesh Agarwalla Date: Wed, 29 Nov 2023 19:49:55 -0500 Subject: [PATCH] Changes based on code review feedback --- src/main/java/frc/robot/commands/ArmCommand.java | 8 ++++---- src/main/java/frc/robot/subsystems/Arm.java | 4 ++-- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/main/java/frc/robot/commands/ArmCommand.java b/src/main/java/frc/robot/commands/ArmCommand.java index 980e113..375b79e 100644 --- a/src/main/java/frc/robot/commands/ArmCommand.java +++ b/src/main/java/frc/robot/commands/ArmCommand.java @@ -16,7 +16,7 @@ public class ArmCommand extends CommandBase { private final double m_speedScale = 16; // to reduce stick sensitivity, this value indicates how much to scale the returned speed // by - private final double m_minBaseRange = -1; // min range for the arm's base + private final double m_minBaseRange = 0; // min range for the arm's base private final double m_maxBaseRange = 1; // max range for the arm's base public ArmCommand(Arm arm, DoubleSupplier baseSpeed) { @@ -38,12 +38,12 @@ public void execute() { // Variable that will store the new calculated arm position double newArmPosition; // Determine the requested speed, but ignoring inputs near-zero (i.e. +/= m_deadband) - double currentShoulderSpeed = MathUtil.applyDeadband(m_baseSpeed.getAsDouble(), m_deadband); + double newBasePositionDelta = MathUtil.applyDeadband(m_baseSpeed.getAsDouble(), m_deadband); // Scale the speed as desired to reduce sensitivity - currentShoulderSpeed /= m_speedScale; + newBasePositionDelta /= m_speedScale; // Calculate the arm position by adding the computer speed to the arm base's current position - newArmPosition = m_arm.getArmBasePosition() + currentShoulderSpeed; + newArmPosition = m_arm.getArmBasePosition() + newBasePositionDelta; // Clamp the arm's upper/lower position to the min/max range allowed newArmPosition = MathUtil.clamp(newArmPosition, m_minBaseRange, m_maxBaseRange); diff --git a/src/main/java/frc/robot/subsystems/Arm.java b/src/main/java/frc/robot/subsystems/Arm.java index 21a023f..e280c4d 100644 --- a/src/main/java/frc/robot/subsystems/Arm.java +++ b/src/main/java/frc/robot/subsystems/Arm.java @@ -14,9 +14,9 @@ public class Arm extends SubsystemBase { // private final Servo m_armElbowServo = new Servo(2); /** - * Moves the arm base to the desired position. -1.0 is max down, and 1.0 is max up + * Moves the arm base to the desired position. 0.0 is max down and 1.0 is max up * - * @param position desired target position for arm base [-1.0 to 1.0] + * @param position desired target position for arm base [0.0 to 1.0] */ public void setArmBasePosition(double position) { // Note: This code doesn't validate the requested position. If we don't want the arm to move