Skip to content

Commit

Permalink
Rename AutoAimController.java to HeadingController.java (#23)
Browse files Browse the repository at this point in the history
Use profile for turning in HeadingController
Clear up drive method names

Co-authored-by: Jonah <[email protected]>
  • Loading branch information
suryatho and jwbonner authored Feb 17, 2024
1 parent b842a67 commit 125745d
Show file tree
Hide file tree
Showing 6 changed files with 109 additions and 78 deletions.
13 changes: 8 additions & 5 deletions src/main/java/org/littletonrobotics/frc2024/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -208,21 +208,24 @@ private void configureButtonBindings() {
drive
.run(
() ->
drive.setTeleopDriveGoal(
drive.acceptTeleopInput(
-controller.getLeftY(), -controller.getLeftX(), -controller.getRightX()))
.withName("Drive Teleop Input"));

// Aim and Rev Flywheels
controller
.a()
.whileTrue(
Commands.startEnd(drive::setAutoAimGoal, drive::clearAutoAimGoal)
Commands.startEnd(
() ->
drive.setHeadingGoal(
() -> RobotState.getInstance().getAimingParameters().driveHeading()),
drive::clearHeadingGoal)
.alongWith(superstructure.aim(), flywheels.shootCommand())
.withName("Aim"));
.withName("Prepare Shot"));
// Shoot
Trigger readyToShoot =
new Trigger(
() -> drive.isAutoAimGoalCompleted() && flywheels.atGoal() && superstructure.atGoal());
new Trigger(() -> drive.atHeadingGoal() && superstructure.atGoal() && flywheels.atGoal());
readyToShoot
.whileTrue(
Commands.run(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,12 +30,12 @@ private Command path(String pathName) {

return startEnd(
() -> {
drive.setTrajectoryGoal(trajectory);
drive.setTrajectory(trajectory);
},
() -> {
drive.clearTrajectoryGoal();
drive.clearTrajectory();
})
.until(() -> drive.isTrajectoryGoalCompleted());
.until(() -> drive.isTrajectoryCompleted());
}

private Command reset(String path) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,14 @@
import java.util.concurrent.ArrayBlockingQueue;
import java.util.concurrent.locks.Lock;
import java.util.concurrent.locks.ReentrantLock;
import java.util.function.Supplier;
import java.util.stream.IntStream;
import lombok.Getter;
import lombok.experimental.ExtensionMethod;
import org.littletonrobotics.frc2024.Constants;
import org.littletonrobotics.frc2024.RobotState;
import org.littletonrobotics.frc2024.subsystems.drive.controllers.AutoAimController;
import org.littletonrobotics.frc2024.subsystems.drive.controllers.AutoAlignController;
import org.littletonrobotics.frc2024.subsystems.drive.controllers.HeadingController;
import org.littletonrobotics.frc2024.subsystems.drive.controllers.TeleopDriveController;
import org.littletonrobotics.frc2024.subsystems.drive.controllers.TrajectoryController;
import org.littletonrobotics.frc2024.subsystems.drive.trajectory.HolonomicTrajectory;
Expand Down Expand Up @@ -104,7 +105,7 @@ public static class OdometryTimestampInputs {
private final TeleopDriveController teleopDriveController;
private TrajectoryController trajectoryController = null;
private AutoAlignController autoAlignController = null;
private AutoAimController autoAimController = null;
private HeadingController headingController = null;

public Drive(GyroIO gyroIO, ModuleIO fl, ModuleIO fr, ModuleIO bl, ModuleIO br) {
this.gyroIO = gyroIO;
Expand Down Expand Up @@ -223,8 +224,8 @@ public void periodic() {
// Plain teleop drive
desiredSpeeds = teleopSpeeds;
// Add auto aim if present
if (autoAimController != null) {
desiredSpeeds.omegaRadiansPerSecond = autoAimController.update();
if (headingController != null) {
desiredSpeeds.omegaRadiansPerSecond = headingController.update();
}
}
case TRAJECTORY -> {
Expand Down Expand Up @@ -271,7 +272,7 @@ public void periodic() {
}

/** Pass controller input into teleopDriveController in field relative input */
public void setTeleopDriveGoal(double controllerX, double controllerY, double controllerOmega) {
public void acceptTeleopInput(double controllerX, double controllerY, double controllerOmega) {
if (DriverStation.isTeleopEnabled()) {
if (currentDriveMode != DriveMode.AUTO_ALIGN) {
currentDriveMode = DriveMode.TELEOP;
Expand All @@ -281,22 +282,22 @@ public void setTeleopDriveGoal(double controllerX, double controllerY, double co
}

/** Sets the trajectory for the robot to follow. */
public void setTrajectoryGoal(HolonomicTrajectory trajectory) {
public void setTrajectory(HolonomicTrajectory trajectory) {
if (DriverStation.isAutonomousEnabled()) {
currentDriveMode = DriveMode.TRAJECTORY;
trajectoryController = new TrajectoryController(trajectory);
}
}

/** Clears the current trajectory goal. */
public void clearTrajectoryGoal() {
public void clearTrajectory() {
trajectoryController = null;
currentDriveMode = DriveMode.TELEOP;
}

/** Returns true if the robot is done with trajectory. */
@AutoLogOutput(key = "Drive/TrajectoryCompleted")
public boolean isTrajectoryGoalCompleted() {
public boolean isTrajectoryCompleted() {
return trajectoryController != null && trajectoryController.isFinished();
}

Expand All @@ -321,19 +322,19 @@ public boolean isAutoAlignGoalCompleted() {
}

/** Enable auto aiming on drive */
public void setAutoAimGoal() {
autoAimController = new AutoAimController();
public void setHeadingGoal(Supplier<Rotation2d> goalHeadingSupplier) {
headingController = new HeadingController(goalHeadingSupplier);
}

/** Disable auto aiming on drive */
public void clearAutoAimGoal() {
autoAimController = null;
public void clearHeadingGoal() {
headingController = null;
}

/** Returns true if robot is aimed at speaker */
@AutoLogOutput(key = "Drive/AutoAimCompleted")
public boolean isAutoAimGoalCompleted() {
return autoAimController != null && autoAimController.atSetpoint();
@AutoLogOutput(key = "Drive/AtHeadingGoal")
public boolean atHeadingGoal() {
return headingController != null && headingController.atGoal();
}

/** Runs forwards at the commanded voltage. */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -168,7 +168,7 @@ public final class DriveConstants {
// Swerve Heading Control
public static HeadingControllerConstants headingControllerConstants =
switch (Constants.getRobot()) {
default -> new HeadingControllerConstants(5.0, 0.0);
default -> new HeadingControllerConstants(5.0, 0.0, 8.0, 20.0);
};

public record DriveConfig(
Expand Down Expand Up @@ -225,7 +225,8 @@ public record AutoAlignConstants(
double maxAngularVelocity,
double maxAngularAcceleration) {}

public record HeadingControllerConstants(double kP, double kD) {}
public record HeadingControllerConstants(
double kP, double kD, double maxVelocity, double maxAcceleration) {}

private enum Mk4iReductions {
L2((50.0 / 14.0) * (17.0 / 27.0) * (45.0 / 15.0)),
Expand Down

This file was deleted.

Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
// Copyright (c) 2024 FRC 6328
// http://github.com/Mechanical-Advantage
//
// 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 org.littletonrobotics.frc2024.subsystems.drive.controllers;

import static org.littletonrobotics.frc2024.subsystems.drive.DriveConstants.headingControllerConstants;

import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.math.util.Units;
import java.util.function.Supplier;
import org.littletonrobotics.frc2024.Constants;
import org.littletonrobotics.frc2024.RobotState;
import org.littletonrobotics.frc2024.util.LoggedTunableNumber;
import org.littletonrobotics.junction.AutoLogOutput;
import org.littletonrobotics.junction.Logger;

public class HeadingController {
private static final LoggedTunableNumber kP =
new LoggedTunableNumber("HeadingController/kP", headingControllerConstants.kP());
private static final LoggedTunableNumber kD =
new LoggedTunableNumber("HeadingController/kD", headingControllerConstants.kD());
private static final LoggedTunableNumber maxVelocity =
new LoggedTunableNumber(
"HeadingController/MaxVelocity", headingControllerConstants.maxVelocity());
private static final LoggedTunableNumber maxAcceleration =
new LoggedTunableNumber(
"HeadingController/MaxAcceleration", headingControllerConstants.maxAcceleration());
private static final LoggedTunableNumber toleranceDegrees =
new LoggedTunableNumber("HeadingController/ToleranceDegrees", 4.0);

private final ProfiledPIDController controller;
private final Supplier<Rotation2d> goalHeadingSupplier;

public HeadingController(Supplier<Rotation2d> goalHeadingSupplier) {
controller =
new ProfiledPIDController(
kP.get(),
0,
kD.get(),
new TrapezoidProfile.Constraints(maxVelocity.get(), maxAcceleration.get()),
Constants.loopPeriodSecs);
controller.enableContinuousInput(-Math.PI, Math.PI);
controller.setTolerance(Units.degreesToRadians(toleranceDegrees.get()));
this.goalHeadingSupplier = goalHeadingSupplier;

controller.reset(
RobotState.getInstance().getEstimatedPose().getRotation().getRadians(),
RobotState.getInstance().fieldVelocity().dtheta);
}

/** Returns the rotation rate to turn to aim at speaker */
public double update() {
// Update controller
controller.setPID(kP.get(), 0, kD.get());
controller.setTolerance(Units.degreesToRadians(toleranceDegrees.get()));
controller.setConstraints(
new TrapezoidProfile.Constraints(maxVelocity.get(), maxAcceleration.get()));

var output =
controller.calculate(
RobotState.getInstance().getEstimatedPose().getRotation().getRadians(),
goalHeadingSupplier.get().getRadians());

Logger.recordOutput("Drive/HeadingController/HeadingError", controller.getPositionError());
return output + controller.getSetpoint().velocity;
}

/** Returns true if within tolerance of aiming at speaker */
@AutoLogOutput(key = "Drive/HeadingController/AtGoal")
public boolean atGoal() {
return controller.atGoal();
}
}

0 comments on commit 125745d

Please sign in to comment.