From 2aed3ffa1d106419de91d2c759b983a76fd46975 Mon Sep 17 00:00:00 2001 From: ryan123rudder <42309874+ryan123rudder@users.noreply.github.com> Date: Sun, 1 Mar 2020 11:24:57 -0700 Subject: [PATCH 1/2] CAN ids maatch Robots --- src/main/java/frc4388/robot/Constants.java | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/main/java/frc4388/robot/Constants.java b/src/main/java/frc4388/robot/Constants.java index dc283e4..f0782cb 100644 --- a/src/main/java/frc4388/robot/Constants.java +++ b/src/main/java/frc4388/robot/Constants.java @@ -110,9 +110,9 @@ public final class Constants { public static final class ShooterConstants { /* Motor IDs */ - public static final int SHOOTER_FALCON_ID = -1; - public static final int SHOOTER_ANGLE_ADJUST_ID = -1; - public static final int SHOOTER_ROTATE_ID = 10; + public static final int SHOOTER_FALCON_ID = 8; + public static final int SHOOTER_ANGLE_ADJUST_ID = 10; + public static final int SHOOTER_ROTATE_ID = 9; /* PID Constants Shooter */ public static final int SHOOTER_SLOT_IDX = 0; @@ -127,15 +127,15 @@ public final class Constants { } public static final class ClimberConstants { - public static final int CLIMBER_SPARK_ID = 10; + public static final int CLIMBER_SPARK_ID = 14; } public static final class LevelerConstants { - public static final int LEVELER_CAN_ID = -1; + public static final int LEVELER_CAN_ID = 15; } public static final class StorageConstants { - public static final int STORAGE_CAN_ID = -1; + public static final int STORAGE_CAN_ID = 11; /* Ball Indexes */ public static final int BEAM_SENSOR_DIO_0 = 0; From 7adb1edb0c323d686ae342ee27c2c075ece51a01 Mon Sep 17 00:00:00 2001 From: ryan123rudder <42309874+ryan123rudder@users.noreply.github.com> Date: Sun, 1 Mar 2020 12:21:03 -0700 Subject: [PATCH 2/2] Add Limit Switches Note: Shooter turret and hood limits are set up on the add-shooter branch. Those are more specific and much better tuned. These currently have no soft limits, and are untested --- src/main/java/frc4388/robot/subsystems/Climber.java | 8 ++++---- src/main/java/frc4388/robot/subsystems/Intake.java | 6 +++--- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/main/java/frc4388/robot/subsystems/Climber.java b/src/main/java/frc4388/robot/subsystems/Climber.java index f6c9339..e9adf86 100644 --- a/src/main/java/frc4388/robot/subsystems/Climber.java +++ b/src/main/java/frc4388/robot/subsystems/Climber.java @@ -31,10 +31,10 @@ public class Climber extends SubsystemBase { m_climberMotor.setIdleMode(IdleMode.kBrake); m_climberMotor.setInverted(false); - m_climberForwardLimit = m_climberMotor.getForwardLimitSwitch(LimitSwitchPolarity.kNormallyClosed); - m_climberReverseLimit = m_climberMotor.getReverseLimitSwitch(LimitSwitchPolarity.kNormallyClosed); - m_climberForwardLimit.enableLimitSwitch(false); - m_climberReverseLimit.enableLimitSwitch(false); + m_climberForwardLimit = m_climberMotor.getForwardLimitSwitch(LimitSwitchPolarity.kNormallyOpen); + m_climberReverseLimit = m_climberMotor.getReverseLimitSwitch(LimitSwitchPolarity.kNormallyOpen); + m_climberForwardLimit.enableLimitSwitch(true); + m_climberReverseLimit.enableLimitSwitch(true); } @Override diff --git a/src/main/java/frc4388/robot/subsystems/Intake.java b/src/main/java/frc4388/robot/subsystems/Intake.java index 6b716f4..f074b33 100644 --- a/src/main/java/frc4388/robot/subsystems/Intake.java +++ b/src/main/java/frc4388/robot/subsystems/Intake.java @@ -41,9 +41,9 @@ public class Intake extends SubsystemBase { m_extenderMotor.setInverted(false); m_extenderForwardLimit = m_extenderMotor.getForwardLimitSwitch(LimitSwitchPolarity.kNormallyClosed); - m_extenderReverseLimit = m_extenderMotor.getReverseLimitSwitch(LimitSwitchPolarity.kNormallyClosed); - m_extenderForwardLimit.enableLimitSwitch(false); - m_extenderReverseLimit.enableLimitSwitch(false); + m_extenderReverseLimit = m_extenderMotor.getReverseLimitSwitch(LimitSwitchPolarity.kNormallyOpen); + m_extenderForwardLimit.enableLimitSwitch(true); + m_extenderReverseLimit.enableLimitSwitch(true); } @Override