Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add amp/trap + lift subsystem #3

Merged
merged 10 commits into from
Jan 26, 2024
2 changes: 2 additions & 0 deletions src/main/java/com/stuypulse/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@

import com.stuypulse.robot.commands.auton.DoNothingAuton;
import com.stuypulse.robot.constants.Ports;
import com.stuypulse.robot.subsystems.amper.Amper;
import com.stuypulse.stuylib.input.Gamepad;
import com.stuypulse.stuylib.input.gamepads.AutoGamepad;

Expand All @@ -21,6 +22,7 @@ public class RobotContainer {
public final Gamepad operator = new AutoGamepad(Ports.Gamepad.OPERATOR);

// Subsystem
public final Amper amper = Amper.getInstance();

// Autons
private static SendableChooser<Command> autonChooser = new SendableChooser<>();
Expand Down
8 changes: 7 additions & 1 deletion src/main/java/com/stuypulse/robot/constants/Motors.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@
import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
import com.ctre.phoenix.motorcontrol.can.WPI_VictorSPX;
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkMax;
import static com.revrobotics.CANSparkMax.IdleMode;

/*-
* File containing all of the configurations that different motors require.
Expand All @@ -21,6 +21,11 @@
* - The Open Loop Ramp Rate
*/
public interface Motors {

public interface Amper {
CANSparkMaxConfig LIFT_MOTOR = new CANSparkMaxConfig(false, IdleMode.kCoast, 80, 0.1);
CANSparkMaxConfig SCORE_MOTOR = new CANSparkMaxConfig(false, IdleMode.kBrake, 80, 0.1);
}

/** Classes to store all of the values a motor needs */

Expand Down Expand Up @@ -119,4 +124,5 @@ public void configure(CANSparkMax motor) {
}

}

}
9 changes: 9 additions & 0 deletions src/main/java/com/stuypulse/robot/constants/Ports.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,4 +12,13 @@ public interface Gamepad {
int OPERATOR = 1;
int DEBUGGER = 2;
}

public interface Amper {
int SCORE = 31;
int LIFT = 30;

int ALIGNED_SWITCH_CHANNEL = 3 ;
int MIN_LIFT_CHANNEL = 4 ;
int AMP_IR_CHANNEL = 2;
}
}
41 changes: 39 additions & 2 deletions src/main/java/com/stuypulse/robot/constants/Settings.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@

package com.stuypulse.robot.constants;

import com.stuypulse.stuylib.network.SmartBoolean;
import com.stuypulse.stuylib.network.SmartNumber;

/*-
Expand All @@ -14,4 +13,42 @@
* We use StuyLib's SmartNumber / SmartBoolean in order to have tunable
* values that we can edit on Shuffleboard.
*/
public interface Settings {}
public interface Settings {

double DT = 0.02; // time between each simulation update

public interface Amper {

public interface Score {
SmartNumber ROLLER_SPEED = new SmartNumber("Amper/Score/Roller Speed", 1.0); // change later
}

public interface Lift {

double CARRIAGE_MASS = 10; // kg

double MIN_HEIGHT = 0;
double MAX_HEIGHT = 1.8475325; // meters

double MAX_HEIGHT_ERROR = 0.03;

SmartNumber VEL_LIMIT = new SmartNumber("Velocity Limit", 3);
SmartNumber ACC_LIMIT = new SmartNumber("Acceleration Limit", 2);

public interface Encoder {
double GEARING = 9; // ~9:1
double DRUM_RADIUS = 0.025; // meters
double DRUM_CIRCUMFERENCE = DRUM_RADIUS * Math.PI * 2;

double POSITION_CONVERSION = GEARING * DRUM_CIRCUMFERENCE;
double VELOCITY_CONVERSION = POSITION_CONVERSION / 60.0;
}

public interface PID {
SmartNumber kP = new SmartNumber("Amper/Lift/kP", 1);
SmartNumber kI = new SmartNumber("Amper/Lift/kI", 0);
SmartNumber kD = new SmartNumber("Amper/Lift/kD", 0);
}
}
}
}
66 changes: 66 additions & 0 deletions src/main/java/com/stuypulse/robot/subsystems/amper/Amper.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
package com.stuypulse.robot.subsystems.amper;

import com.stuypulse.robot.constants.Settings;
import com.stuypulse.robot.constants.Settings.Amper.Lift;
import com.stuypulse.stuylib.control.Controller;
import com.stuypulse.stuylib.control.feedback.PIDController;
import com.stuypulse.stuylib.math.SLMath;
import com.stuypulse.stuylib.network.SmartNumber;

import edu.wpi.first.wpilibj2.command.SubsystemBase;

/*
AMP:
1 motor
1 limit switch
IR Sensor

LIFT:
1 motor
1 encoder
Bottom (shooter) limit switch
*/

public abstract class Amper extends SubsystemBase {

private static Amper instance;

static {
instance = new AmperImpl();
}

public static Amper getInstance() {
return instance;
}

public final SmartNumber targetHeight;
public final Controller liftController;

public Amper() {
liftController = new PIDController(Lift.PID.kP, Lift.PID.kI, Lift.PID.kD);
targetHeight = new SmartNumber("Amp/Target Height", 0); // TODO: determine the default value
}

public void setTargetHeight(double height) {
targetHeight.set(SLMath.clamp(height, Settings.Amper.Lift.MIN_HEIGHT, Settings.Amper.Lift.MAX_HEIGHT));
}

public abstract boolean hasNote();

public abstract void score();
public abstract void intake();
public abstract void stopRoller();

public abstract boolean liftAtBottom();
public abstract double getLiftHeight();
public abstract void stopLift();
public abstract void setLiftVoltageImpl(double voltage);

public abstract boolean touchingAmp();

@Override
public void periodic() {
setLiftVoltageImpl(liftController.update(targetHeight.get(), getLiftHeight()));
}

}
99 changes: 99 additions & 0 deletions src/main/java/com/stuypulse/robot/subsystems/amper/AmperImpl.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
package com.stuypulse.robot.subsystems.amper;
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder;
import com.stuypulse.robot.constants.Motors;
import com.stuypulse.robot.constants.Ports;
import com.stuypulse.robot.constants.Settings;

import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;


public class AmperImpl extends Amper {

private final CANSparkMax scoreMotor;
private final CANSparkMax liftMotor;
private final RelativeEncoder liftEncoder;

private final DigitalInput alignedSwitch;
private final DigitalInput minSwitch;
private final DigitalInput ampIRSensor;

public AmperImpl() {
scoreMotor = new CANSparkMax(Ports.Amper.SCORE, MotorType.kBrushless);
liftMotor = new CANSparkMax(Ports.Amper.LIFT, MotorType.kBrushless);
liftEncoder = liftMotor.getEncoder();

liftEncoder.setPositionConversionFactor(Settings.Amper.Lift.Encoder.POSITION_CONVERSION);
liftEncoder.setVelocityConversionFactor(Settings.Amper.Lift.Encoder.VELOCITY_CONVERSION);

alignedSwitch = new DigitalInput(Ports.Amper.ALIGNED_SWITCH_CHANNEL);
minSwitch = new DigitalInput(Ports.Amper.MIN_LIFT_CHANNEL);
ampIRSensor = new DigitalInput(Ports.Amper.AMP_IR_CHANNEL);

Motors.Amper.LIFT_MOTOR.configure(liftMotor);
Motors.Amper.SCORE_MOTOR.configure(scoreMotor);
}

@Override
public boolean hasNote() {
return !ampIRSensor.get();
}

@Override
public boolean liftAtBottom() {
return !minSwitch.get();
}

@Override
public double getLiftHeight() {
return liftEncoder.getPosition();
}

@Override
public boolean touchingAmp() {
return !alignedSwitch.get();
}

@Override
public void score() {
scoreMotor.set(Settings.Amper.Score.ROLLER_SPEED.get());
}

@Override
public void intake() {
scoreMotor.set(-Settings.Amper.Score.ROLLER_SPEED.get());
}

@Override
public void stopLift() {
liftMotor.stopMotor();
}

@Override
public void stopRoller() {
scoreMotor.stopMotor();
}

@Override
public void setLiftVoltageImpl(double voltage) {
if (liftAtBottom() && voltage < 0) {
stopLift();
}
else {
liftMotor.setVoltage(voltage);
}
}

public void periodic() {
super.periodic();

SmartDashboard.putNumber("Amper/Intake Speed", scoreMotor.get());
SmartDashboard.putNumber("Amper/Lift Speed", liftMotor.get());
SmartDashboard.putNumber("Amper/Intake Current", scoreMotor.getOutputCurrent());
SmartDashboard.putNumber("Amper/Lift Current", liftMotor.getOutputCurrent());
SmartDashboard.putNumber("Amper/Lift Height", getLiftHeight());
}

}
75 changes: 75 additions & 0 deletions src/main/java/com/stuypulse/robot/subsystems/amper/AmperSim.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,75 @@
package com.stuypulse.robot.subsystems.amper;

import static com.stuypulse.robot.constants.Settings.Amper.Lift.*;

import com.stuypulse.robot.constants.Settings;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.wpilibj.simulation.ElevatorSim;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

public class AmperSim extends Amper {

private final ElevatorSim sim;

public AmperSim() {
sim = new ElevatorSim(
DCMotor.getNEO(1),
Encoder.GEARING,
CARRIAGE_MASS,
Encoder.DRUM_RADIUS,
MIN_HEIGHT,
MAX_HEIGHT,
true,
0
);
}

@Override
public boolean hasNote() {
return false;
}

@Override
public void intake() {}

@Override
public void score() {}

@Override
public boolean liftAtBottom() {
return sim.hasHitLowerLimit();
}

@Override
public boolean touchingAmp() {
return false;
}

@Override
public void stopLift() {
sim.setInputVoltage(0.0);
}

@Override
public double getLiftHeight() {
return sim.getPositionMeters();
}

@Override
public void setLiftVoltageImpl(double voltage) {
sim.setInputVoltage(voltage);
}

@Override
public void stopRoller() {}

@Override
public void simulationPeriodic() {
sim.update(Settings.DT);

SmartDashboard.putNumber("Amper/Lift Height", getLiftHeight());
}

}