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

Added preset commands to arm #39

Merged
merged 6 commits into from
Feb 13, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 0 additions & 1 deletion src/main/java/frc/robot/CommandSequences.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,6 @@
import frc.robot.subsystems.Drive;
import frc.robot.subsystems.Elevator;
import frc.robot.subsystems.Led;
import frc.robot.subsystems.Outtake;

public class CommandSequences {

Expand Down
64 changes: 62 additions & 2 deletions src/main/java/frc/robot/maps/subsystems/ArmRotateMap.java
Original file line number Diff line number Diff line change
@@ -1,29 +1,89 @@
package frc.robot.maps.subsystems;

import com.chopshop166.chopshoplib.ValueRange;
import com.chopshop166.chopshoplib.logging.DataWrapper;
import com.chopshop166.chopshoplib.logging.LoggableMap;
import com.chopshop166.chopshoplib.logging.data.MotorControllerData;
import com.chopshop166.chopshoplib.motors.SmartMotorController;
import com.chopshop166.chopshoplib.sensors.IEncoder;

import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.controller.ArmFeedforward;

public class ArmRotateMap implements LoggableMap<ArmRotateMap.Data> {

public enum ArmRotatePresets {

OFF,

INTAKE,

SCOREL1,

SCOREL23,

SCOREL4,

STOW,

HOLD

}

public record ArmRotatePresetValues(double intake, double scoreL1, double scoreL23, double scoreL4, double stow) {
public ArmRotatePresetValues() {
this(0, 0, 0, 0, 0);
}

public double getValue(ArmRotatePresets preset) {
switch (preset) {
case OFF:
return Double.NaN;
case INTAKE:
return intake;
case SCOREL1:
return scoreL1;
case SCOREL23:
return scoreL23;
case SCOREL4:
return scoreL4;
case STOW:
return stow;
default:
return 0;
}
}
}

public SmartMotorController motor;
public final IEncoder encoder;
public final ArmRotatePresetValues armRotatePreset;
public final ProfiledPIDController pid;
public final ValueRange hardLimits;
public final ValueRange softLimits;
public final ArmFeedforward armFeedforward;

public ArmRotateMap(SmartMotorController motor, IEncoder encoder) {
public ArmRotateMap(SmartMotorController motor, IEncoder encoder, ArmRotatePresetValues armRotatePreset,
ProfiledPIDController pid, ValueRange hardLimits, ValueRange softLimits, ArmFeedforward armFeedforward) {
this.motor = motor;
this.encoder = encoder;
this.armRotatePreset = armRotatePreset;
this.pid = pid;
this.softLimits = softLimits;
this.hardLimits = hardLimits;
this.armFeedforward = armFeedforward;
}

@Override
public void updateData(Data data) {
data.motor.updateData(motor);
data.rotationAbsAngleDegrees = encoder.getAbsolutePosition();
data.rotatingAngleVelocity = encoder.getRate();
}

public static class Data extends DataWrapper {
public MotorControllerData motor = new MotorControllerData();
public double rotationAbsAngleDegrees;
public double rotatingAngleVelocity;
}
}
}
110 changes: 108 additions & 2 deletions src/main/java/frc/robot/subsystems/ArmRotate.java
Original file line number Diff line number Diff line change
@@ -1,18 +1,124 @@
package frc.robot.subsystems;

import java.util.function.DoubleSupplier;

import org.littletonrobotics.junction.Logger;

import com.chopshop166.chopshoplib.PersistenceCheck;
import com.chopshop166.chopshoplib.logging.LoggedSubsystem;

import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.trajectory.TrapezoidProfile.State;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.maps.subsystems.ArmRotateMap;
import frc.robot.maps.subsystems.ArmRotateMap.ArmRotatePresets;
import frc.robot.maps.subsystems.ArmRotateMap.Data;

public class ArmRotate extends LoggedSubsystem<Data, ArmRotateMap> {
final ProfiledPIDController pid;
private final double RAISE_SPEED = 0.5;
private final double LOWER_SPEED = 0.3;
private final double MANUAL_LOWER_SPEED_COEF = 0.3;
private final double SLOW_DOWN_COEF = 0.3;
private final double ZEROING_SPEED = 0.5;
double holdAngle = 0;

ArmRotatePresets preset = ArmRotatePresets.OFF;

public ArmRotate(ArmRotateMap armRotateMap) {
super(new Data(), armRotateMap);
pid = armRotateMap.pid;
}

public Command move(DoubleSupplier rotateSpeed) {

return run(() -> {
double speed = rotateSpeed.getAsDouble();
double speedCoef = RAISE_SPEED;
if (speed < 0) {
speedCoef = MANUAL_LOWER_SPEED_COEF;
}
if (Math.abs(speed) > 0) {
preset = ArmRotatePresets.OFF;
getData().motor.setpoint = (limits(speed * speedCoef));
} else if (preset == ArmRotatePresets.OFF) {
getData().motor.setpoint = 0.0;
} else {
getData().motor.setpoint = 0.0;
}

});
}

public Command moveTo(ArmRotatePresets level) {
PersistenceCheck setPointPersistenceCheck = new PersistenceCheck(30, pid::atGoal);
return runOnce(() -> {
pid.reset(getArmAngle(), getData().rotatingAngleVelocity);
}).andThen(run(() -> {
Logger.recordOutput("Pid at goal", pid.atGoal());
}).until(setPointPersistenceCheck)).withName("Move To Set Angle");
}

public Command zero() {
return runSafe(() -> {
getData().motor.setpoint = ZEROING_SPEED;
}).until(() -> getMap().motor.validate()).andThen(resetCmd());
}

public Command moveToZero() {
return startSafe(() -> {
getData().motor.setpoint = ZEROING_SPEED;
preset = ArmRotatePresets.OFF;
}).until(() -> {
return getArmAngle() > getMap().armRotatePreset.getValue(ArmRotatePresets.STOW);
});
}

public Command hold() {
return runOnce(() -> {
holdAngle = getArmAngle();
this.preset = ArmRotatePresets.HOLD;
});
}

private double limits(double speed) {
double height = getArmAngle();
speed = getMap().hardLimits.filterSpeed(height, speed);
speed = getMap().softLimits.scaleSpeed(height, speed, SLOW_DOWN_COEF);
return speed;
}

private double getArmAngle() {
return getData().rotationAbsAngleDegrees;
}

@Override
public void safeState() {
public void periodic() {
super.periodic();
if (preset != ArmRotatePresets.OFF) {
double targetHeight = preset == ArmRotatePresets.HOLD ? holdAngle
: getMap().armRotatePreset.getValue(preset);
double setpoint = pid.calculate(getArmAngle(), new State(targetHeight, 0));
setpoint += getMap().armFeedforward.calculate(
pid.getSetpoint().position,
pid.getSetpoint().velocity);
getData().motor.setpoint = setpoint;
}

Logger.recordOutput("Arm preset", preset);
Logger.recordOutput("DesiredArmVelocity", pid.getSetpoint().velocity);
Logger.recordOutput("DesiredArmPosition", pid.getSetpoint().position);

}
}

@Override
public void reset() {
getMap().encoder.reset();
}

@Override
public void safeState() {
getData().motor.setpoint = 0;
preset = ArmRotatePresets.OFF;
}
}
1 change: 0 additions & 1 deletion src/main/java/frc/robot/subsystems/DeepClimb.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.maps.subsystems.DeepClimbMap;
import frc.robot.maps.subsystems.DeepClimbMap.Data;
import frc.robot.maps.subsystems.ElevatorMap.ElevatorPresets;

public class DeepClimb extends LoggedSubsystem<Data, DeepClimbMap> {

Expand Down
3 changes: 1 addition & 2 deletions src/main/java/frc/robot/subsystems/Elevator.java
Original file line number Diff line number Diff line change
Expand Up @@ -130,5 +130,4 @@ public void periodic() {
Logger.recordOutput("DesiredElevatorPosition", pid.getSetpoint().position);

}

}
}