Skip to content

Commit

Permalink
Make AutoBindings package private
Browse files Browse the repository at this point in the history
Signed-off-by: Jade Turner <[email protected]>
  • Loading branch information
spacey-sooty committed Dec 31, 2024
1 parent 71419e9 commit 0b9ddb6
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 25 deletions.
22 changes: 5 additions & 17 deletions choreolib/src/main/java/choreo/auto/AutoFactory.java
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ Optional<Alliance> alliance() {
}

/** A class used to bind commands to events in all trajectories created by this factory. */
public static class AutoBindings {
static class AutoBindings {
private HashMap<String, Command> bindings = new HashMap<>();

/** Default constructor. */
Expand All @@ -71,13 +71,6 @@ public AutoBindings bind(String name, Command cmd) {
return this;
}

private void merge(AutoBindings other) {
if (other == null) {
return;
}
bindings.putAll(other.bindings);
}

/**
* Gets the bindings map.
*
Expand Down Expand Up @@ -112,7 +105,6 @@ HashMap<String, Command> getBindings() {
* Command}s.
* @param useAllianceFlipping If this is true, when on the red alliance, the path will be mirrored
* to the opposite side, while keeping the same coordinate system origin.
* @param bindings Universal trajectory event bindings.
* @param trajectoryLogger A {@link TrajectoryLogger} to log {@link Trajectory} as they start and
* finish.
* @see AutoChooser using this factory with AutoChooser to generate auto routines.
Expand All @@ -123,21 +115,18 @@ public <SampleType extends TrajectorySample<SampleType>> AutoFactory(
Consumer<SampleType> controller,
boolean useAllianceFlipping,
Subsystem driveSubsystem,
AutoBindings bindings,
TrajectoryLogger<SampleType> trajectoryLogger) {
requireNonNullParam(poseSupplier, "poseSupplier", "AutoFactory");
requireNonNullParam(resetOdometry, "resetOdometry", "AutoFactory");
requireNonNullParam(controller, "controller", "AutoFactory");
requireNonNullParam(driveSubsystem, "driveSubsystem", "AutoFactory");
requireNonNullParam(useAllianceFlipping, "useAllianceFlipping", "AutoFactory");
requireNonNullParam(bindings, "bindings", "AutoFactory");

this.poseSupplier = poseSupplier;
this.resetOdometry = resetOdometry;
this.controller = controller;
this.driveSubsystem = driveSubsystem;
this.allianceCtx = new AllianceContext(useAllianceFlipping, DriverStation::getAlliance);
this.bindings.merge(bindings);
this.trajectoryLogger = trajectoryLogger;
HAL.report(tResourceType.kResourceType_ChoreoTrigger, 1);

Expand Down Expand Up @@ -180,23 +169,20 @@ public Trigger active() {
* Command}s.
* @param useAllianceFlipping If this returns true, when on the red alliance, the path will be
* mirrored to the opposite side, while keeping the same coordinate system origin.
* @param bindings Universal trajectory event bindings.
* @see AutoChooser using this factory with AutoChooser to generate auto routines.
*/
public <ST extends TrajectorySample<ST>> AutoFactory(
Supplier<Pose2d> poseSupplier,
Consumer<Pose2d> resetOdometry,
Consumer<ST> controller,
boolean useAllianceFlipping,
Subsystem driveSubsystem,
AutoBindings bindings) {
Subsystem driveSubsystem) {
this(
poseSupplier,
resetOdometry,
controller,
useAllianceFlipping,
driveSubsystem,
bindings,
(sample, isStart) -> {});
}

Expand Down Expand Up @@ -371,9 +357,11 @@ public <ST extends TrajectorySample<ST>> Command resetOdometry(Trajectory<ST> tr
*
* @param name The name of the trajectory to bind the command to.
* @param cmd The command to bind to the trajectory.
* @return The AutoFactory the method was called from.
*/
public void bind(String name, Command cmd) {
public AutoFactory bind(String name, Command cmd) {
bindings.bind(name, cmd);
return this;
}

/**
Expand Down
1 change: 0 additions & 1 deletion choreolib/src/test/java/choreo/auto/AutoTestHelper.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@ public static AutoFactory factory(boolean useAllianceFlipping) {
sample -> pose.set(sample.getPose()),
useAllianceFlipping,
new Subsystem() {},
new AutoFactory.AutoBindings(),
(sample, isStart) -> {});
}

Expand Down
12 changes: 5 additions & 7 deletions docs/choreolib/auto-factory.md
Original file line number Diff line number Diff line change
Expand Up @@ -18,15 +18,13 @@ public class Robot extends TimedRobot {
driveSubsystem::followTrajectory, // The drive subsystem trajectory follower (1)
true, // If alliance flipping should be enabled (2)
driveSubsystem, // The drive subsystem
new AutoBindings() // An empty AutoBindings object (3)
);
}
}
```

1. See [Getting Started](./getting-started.md/#setting-up-the-drive-subsystem) for more details on how to implement a trajectory follower in your drive subsystem.
2. It is recommended for trajectories to be created only on the blue side of the field in the Choreo application. Enabling alliance flipping will automatically mirror trajectories to the red side of the field if the robot is on the red alliance.
3. More information about setting up `AutoBindings` can be found in the [AutoBindings](#autobindings) section of this page.

!!! tip
It is recommended for your `AutoFactory` to be created at the Robot scope (e.g. in the `Robot` or `RobotContainer` constructor), not in the drive subsystem. Some teams may opt to create a separate class (ex `Autos.java`) that is given the robot's subsystems, and contains all code relevant to constructing autonomous routines.
Expand Down Expand Up @@ -229,14 +227,14 @@ public AutoRoutine branching2024Auto() {
2. `AutoRoutine.anyActive()` can be used as a shorthand for checking if any trajectories in a set are active.
3. Similar to `AutoRoutine.anyActive()`, `AutoRoutine.anyDone()` can be used as a shorthand for checking if any trajectories in a set are done.

## AutoBindings
## Auto Bindings

The `AutoBindings` ([Java](/api/choreolib/java/choreo/auto/AutoFactory.AutoBindings.html)) class is used to bind event markers in trajectories made by the `AutoFactory` to commands. Commands added to `AutoBindings` exhibit the same behavior as those bound to `AutoTrajectory.atTime(String)`, except they are applied globally across all routines. This is useful if you have simpler actions that you want to trigger in any trajectory without much thought.
Auto bindings are used to bind event markers in trajectories made by the `AutoFactory` to commands. Commands added to the `AutoFactory` using `bind` exhibit the same behavior as those bound to `AutoTrajectory.atTime(String)`, except they are applied globally across all routines. This is useful if you have simpler actions that you want to trigger in any trajectory without much thought.

```java
AutoBindings bindings = new AutoBindings()
.bind("intake", intakeSubsystem.intake())
.bind("score", scoringSubsystem.score());
autoFactory
.bind("intake", intakeSubsystem.intake())
.bind("score", scoringSubsystem.score());
```

## AutoChooser
Expand Down

0 comments on commit 0b9ddb6

Please sign in to comment.