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

Assisted intaking #68

Merged
merged 15 commits into from
Oct 23, 2024
9 changes: 4 additions & 5 deletions src/main/java/frc/robot/imu/ImuSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,13 +2,12 @@

import com.ctre.phoenix6.hardware.Pigeon2;
import dev.doglog.DogLog;
import edu.wpi.first.math.geometry.Rotation2d;
import frc.robot.util.scheduling.SubsystemPriority;
import frc.robot.util.state_machines.StateMachine;

public class ImuSubsystem extends StateMachine<ImuState> {
private final Pigeon2 imu;
private Rotation2d robotHeading = new Rotation2d();
private double robotHeading = 0;

public ImuSubsystem(Pigeon2 imu) {
super(SubsystemPriority.IMU, ImuState.DEFAULT_STATE);
Expand All @@ -17,16 +16,16 @@ public ImuSubsystem(Pigeon2 imu) {

@Override
protected void collectInputs() {
robotHeading = Rotation2d.fromDegrees(imu.getYaw().getValue());
robotHeading = imu.getYaw().getValue();
jonahsnider marked this conversation as resolved.
Show resolved Hide resolved
}

public Rotation2d getRobotHeading() {
public double getRobotHeading() {
return robotHeading;
}

@Override
public void robotPeriodic() {
super.robotPeriodic();
DogLog.log("Imu/RobotHeading", robotHeading.getDegrees());
DogLog.log("Imu/RobotHeading", robotHeading);
}
}
39 changes: 23 additions & 16 deletions src/main/java/frc/robot/intake_assist/IntakeAssistManager.java
Original file line number Diff line number Diff line change
@@ -1,55 +1,62 @@
package frc.robot.intake_assist;

import dev.doglog.DogLog;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.imu.ImuSubsystem;
import frc.robot.localization.LocalizationSubsystem;
import frc.robot.swerve.SwerveSubsystem;
import frc.robot.util.scheduling.LifecycleSubsystem;
import frc.robot.util.scheduling.SubsystemPriority;
import frc.robot.vision.LimelightHelpers;

public class IntakeAssistManager extends LifecycleSubsystem {
private static final double ASSIST_KP = 0.2;
private static final String LIMELIGHT_NAME = "limelight-note";
private final LocalizationSubsystem localization;
private final SwerveSubsystem swerve;
private final ImuSubsystem imu;
private static final double MAX_ANGLE_CHANGE = -35.0;
private static final double MIN_ANGLE_CHANGE = 35.0;

public IntakeAssistManager(
LocalizationSubsystem localization, SwerveSubsystem swerve, ImuSubsystem imu) {
public IntakeAssistManager(SwerveSubsystem swerve, ImuSubsystem imu) {
super(SubsystemPriority.INTAKE_ASSIST_MANAGER);

this.localization = localization;
this.swerve = swerve;
this.imu = imu;
}



public double getRobotRelativeAssistSpeeds(ChassisSpeeds fieldRelativeInputSpeeds ){
public ChassisSpeeds getRobotRelativeAssistSpeeds(ChassisSpeeds fieldRelativeInputSpeeds ){

double tx = LimelightHelpers.getTX(LIMELIGHT_NAME);

double tx = NetworkTableInstance.getDefault().getTable(LIMELIGHT_NAME).getEntry("tx").getDouble(0);

Rotation2d robotToNoteAngle = Rotation2d.fromDegrees(tx);
if (tx == 0) {
return fieldRelativeInputSpeeds;
}

Rotation2d fieldRelativeNoteAngle = imu.getRobotHeading().plus(robotToNoteAngle);
DogLog.log("IntakeAssist/TX", tx);

Rotation2d driverRequest = fieldRelativeNoteAngle;
double fieldRelativeNoteAngle = imu.getRobotHeading() + tx;

double angleError = imu.getRobotHeading().minus(driverRequest).getDegrees();
double angleError = imu.getRobotHeading() - fieldRelativeNoteAngle;

double angleChange = Math.max(MAX_ANGLE_CHANGE, Math.min(MIN_ANGLE_CHANGE, angleError * 0.2));
double angleChange = MathUtil.clamp(MIN_ANGLE_CHANGE, MAX_ANGLE_CHANGE, angleError * ASSIST_KP);

return angleChange;
Translation2d requestedFieldRelativeDrive = new Translation2d(fieldRelativeInputSpeeds.vxMetersPerSecond,
fieldRelativeInputSpeeds.vyMetersPerSecond);

Translation2d newDriveRequest = requestedFieldRelativeDrive.rotateBy(Rotation2d.fromDegrees(angleChange));

return new ChassisSpeeds(newDriveRequest.getX(), newDriveRequest.getY(), fieldRelativeInputSpeeds.omegaRadiansPerSecond);

}

public void updateSwerveSpeeds() {
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Does this function need to exist? Or should Swerve.sendSwerveRequest call getRobotRelativeAssistSpeeds when in one of the assist modes? Seems easier to me to just call it in one of the assist states in Swerve.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

yeah most likely the way you want to do this is have a collectInputs in swerve which calculates the intake assist offset (but only when in an intake assist state), stores that in a field, and then adds the offset in sendSwerveRequest()

ChassisSpeeds intakeAssistSpeeds = getRobotRelativeAssistSpeeds(swerve.getFieldRelativeSpeeds());
swerve.setIntakeAssistTeleopSpeeds(intakeAssistSpeeds);
swerve.setIntakeAssistAutoSpeeds(intakeAssistSpeeds);
}

}
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import edu.wpi.first.math.VecBuilder;
import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.interpolation.TimeInterpolatableBuffer;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.wpilibj.Timer;
Expand Down Expand Up @@ -33,7 +34,7 @@ public LocalizationSubsystem(ImuSubsystem imu, VisionSubsystem vision, SwerveSub
poseEstimator =
new SwerveDrivePoseEstimator(
SwerveSubsystem.KINEMATICS,
imu.getRobotHeading(),
Rotation2d.fromDegrees(imu.getRobotHeading()),
swerve.getModulePositions().toArray(new SwerveModulePosition[4]),
new Pose2d());
}
Expand Down
21 changes: 21 additions & 0 deletions src/main/java/frc/robot/robot_manager/RobotManager.java
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,7 @@ protected RobotState getNextState(RobotState currentState) {
shooter.atGoal() && arm.atGoal() ? RobotState.SUBWOOFER_SCORING : currentState;
case UNJAM -> currentState;
case INTAKING -> queuer.hasNote() ? RobotState.IDLE_WITH_GP : currentState;
case INTAKE_ASSIST -> queuer.hasNote() ? RobotState.IDLE_WITH_GP : currentState;
fcuellar13 marked this conversation as resolved.
Show resolved Hide resolved
case OUTTAKING -> queuer.hasNote() ? currentState : RobotState.IDLE_NO_GP;
};
}
Expand Down Expand Up @@ -155,6 +156,12 @@ protected void afterTransition(RobotState newState) {
intake.setState(IntakeState.INTAKING);
queuer.setState(QueuerState.INTAKING);
}
case INTAKE_ASSIST -> {
arm.setState(ArmState.IDLE);
shooter.setState(ShooterState.IDLE_STOPPED);
intake.setState(IntakeState.INTAKING);
queuer.setState(QueuerState.INTAKING);
}
fcuellar13 marked this conversation as resolved.
Show resolved Hide resolved
case OUTTAKING -> {
arm.setState(ArmState.IDLE);
shooter.setState(ShooterState.IDLE_STOPPED);
Expand Down Expand Up @@ -252,6 +259,13 @@ public void intakeRequest() {
}
}

public void intakeAssistRequest() {
switch(getState()) {
case CLIMBING_1_LINEUP, CLIMBING_2_HANGING -> {}
default -> setStateFromRequest(RobotState.INTAKE_ASSIST);
}
}

// TODO: This seems like we ended up not really needing it, can remove it in favor of
// stowRequest()
public void stopIntakingRequest() {
Expand All @@ -261,6 +275,13 @@ public void stopIntakingRequest() {
}
}

public void stopIntakeAssistRequest() {
fcuellar13 marked this conversation as resolved.
Show resolved Hide resolved
switch (getState()) {
case INTAKE_ASSIST -> setStateFromRequest(RobotState.IDLE_NO_GP);
default -> {}
}
}

public void outtakeRequest() {
switch (getState()) {
case CLIMBING_1_LINEUP, CLIMBING_2_HANGING -> {}
Expand Down
1 change: 1 addition & 0 deletions src/main/java/frc/robot/robot_manager/RobotState.java
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ public enum RobotState {

INTAKING,
OUTTAKING,
INTAKE_ASSIST,

UNJAM,

Expand Down
35 changes: 31 additions & 4 deletions src/main/java/frc/robot/swerve/SwerveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -117,6 +117,16 @@ public void setFieldRelativeAutoSpeeds(ChassisSpeeds speeds) {
sendSwerveRequest();
}

public void setIntakeAssistTeleopSpeeds(ChassisSpeeds speeds) {
teleopSpeeds = speeds;
sendSwerveRequest();
}

public void setIntakeAssistAutoSpeeds(ChassisSpeeds speeds) {
autoSpeeds = speeds;
sendSwerveRequest();
}

public void driveTeleop(double x, double y, double theta) {
double leftY =
-1.0
Expand Down Expand Up @@ -192,6 +202,7 @@ private boolean calculateMovingSlowEnoughForFloorShot(ChassisSpeeds speeds) {
return linearSpeed < MAX_FLOOR_SPEED_SHOOTING;
}


private void sendSwerveRequest() {
switch (getState()) {
case TELEOP ->
Expand All @@ -209,15 +220,23 @@ private void sendSwerveRequest() {
.withVelocityY(teleopSpeeds.vyMetersPerSecond)
.withTargetDirection(Rotation2d.fromDegrees(goalSnapAngle))
.withDriveRequestType(DriveRequestType.OpenLoopVoltage));
} else {

} else {
drivetrain.setControl(
drive
.withVelocityX(teleopSpeeds.vxMetersPerSecond)
.withVelocityY(teleopSpeeds.vyMetersPerSecond)
.withRotationalRate(teleopSpeeds.omegaRadiansPerSecond)
.withDriveRequestType(DriveRequestType.OpenLoopVoltage));
}
}
case INTAKE_ASSIST_TELEOP ->
drivetrain.setControl(
drive
.withVelocityX(teleopSpeeds.vxMetersPerSecond)
.withVelocityY(teleopSpeeds.vyMetersPerSecond)
.withRotationalRate(teleopSpeeds.omegaRadiansPerSecond)
.withDriveRequestType(DriveRequestType.OpenLoopVoltage));
}
}
case AUTO ->
drivetrain.setControl(
drive
Expand All @@ -232,6 +251,14 @@ private void sendSwerveRequest() {
.withVelocityY(autoSpeeds.vyMetersPerSecond)
.withTargetDirection(Rotation2d.fromDegrees(goalSnapAngle))
.withDriveRequestType(DriveRequestType.Velocity));

case INTAKE_ASSIST_AUTO ->
drivetrain.setControl(
drive
.withVelocityX(teleopSpeeds.vxMetersPerSecond)
.withVelocityY(teleopSpeeds.vyMetersPerSecond)
.withRotationalRate(teleopSpeeds.omegaRadiansPerSecond)
.withDriveRequestType(DriveRequestType.OpenLoopVoltage));
}
jonahsnider marked this conversation as resolved.
Show resolved Hide resolved
}
}
}
Loading