Skip to content

Commit

Permalink
Merge pull request #59 from frc4911/armsolenoid
Browse files Browse the repository at this point in the history
Added pnuematic control to Arm subsystem
  • Loading branch information
SuperDuperGreen authored Jan 27, 2024
2 parents bcadf21 + 211686b commit aa7afd9
Show file tree
Hide file tree
Showing 4 changed files with 34 additions and 2 deletions.
8 changes: 8 additions & 0 deletions src/main/java/com/cyberknights4911/robot2024/arm/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,14 @@ public void setVoltage(double volts) {
armIO.setVoltage(volts);
}

public void setCollectorAngle(CollectorAngle angle) {
if (angle == CollectorAngle.EIGHTY) {
armIO.setSolenoidState(true);
} else if (angle == CollectorAngle.FORTY_FIVE) {
armIO.setSolenoidState(false);
}
}

@Override
public void periodic() {
armIO.updateInputs(inputs);
Expand Down
2 changes: 2 additions & 0 deletions src/main/java/com/cyberknights4911/robot2024/arm/ArmIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@ public static class ArmIOInputs {
/** Updates the set of loggable inputs. */
public default void updateInputs(ArmIOInputs inputs) {}

public default void setSolenoidState(boolean state) {}

/** Run the motor at the specified voltage. */
public default void setVoltage(double volts) {}

Expand Down
13 changes: 11 additions & 2 deletions src/main/java/com/cyberknights4911/robot2024/arm/ArmIOReal.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,19 +14,22 @@
import com.revrobotics.RelativeEncoder;
import com.revrobotics.SparkPIDController;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.PneumaticsModuleType;
import edu.wpi.first.wpilibj.Solenoid;

public final class ArmIOReal implements ArmIO {
private final CANSparkFlex left;
private final CANSparkFlex right;

private final Solenoid armSolenoid;
private final RelativeEncoder encoder;
private final SparkPIDController pidController;
private final double gearRatio;

public ArmIOReal(ArmConstants armConstants) {
left = new CANSparkFlex(armConstants.motorId1(), MotorType.kBrushless);
right = new CANSparkFlex(armConstants.motorId2(), MotorType.kBrushless);

// TODO verify module type
armSolenoid = new Solenoid(PneumaticsModuleType.REVPH, armConstants.solenoidId());
encoder = right.getEncoder();
pidController = right.getPIDController();
gearRatio = armConstants.gearRatio();
Expand All @@ -42,6 +45,12 @@ public void updateInputs(ArmIOInputs inputs) {
// TODO: read solenoid state and write to inputs
inputs.appliedVolts = right.getAppliedOutput() * right.getBusVoltage();
inputs.currentAmps = new double[] {right.getOutputCurrent(), left.getOutputCurrent()};
inputs.solenoidState = armSolenoid.get();
}

@Override
public void setSolenoidState(boolean state) {
armSolenoid.set(state);
}

@Override
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
// Copyright (c) 2023 FRC 4911
// https://github.com/frc4911
//
// Use of this source code is governed by an MIT-style
// license that can be found in the LICENSE file at
// the root directory of this project.

package com.cyberknights4911.robot2024.arm;

public enum CollectorAngle {
FORTY_FIVE,
EIGHTY
}

0 comments on commit aa7afd9

Please sign in to comment.