Skip to content

Commit

Permalink
[choreolib] Remove controller function typedef (#852)
Browse files Browse the repository at this point in the history
  • Loading branch information
calcmogul authored Oct 7, 2024
1 parent 24dba6e commit 174b678
Show file tree
Hide file tree
Showing 5 changed files with 28 additions and 40 deletions.
17 changes: 4 additions & 13 deletions choreolib/src/main/java/choreo/Choreo.java
Original file line number Diff line number Diff line change
Expand Up @@ -91,15 +91,6 @@ public static ProjectFile getProjectFile() {
return LAZY_PROJECT_FILE.get();
}

/**
* This interface exists as a type alias. A ControlFunction has a signature of ({@link Pose2d},
* {@link SampleType}).
*
* @param <SampleType> DifferentialSample or SwerveSample.
*/
public interface ControlFunction<SampleType extends TrajectorySample<SampleType>>
extends BiConsumer<Pose2d, SampleType> {}

/**
* This interface exists as a type alias. A TrajectoryLogger has a signature of ({@link
* Trajectory}, {@link Boolean})-&gt;void, where the function consumes a trajectory and a boolean
Expand Down Expand Up @@ -291,7 +282,7 @@ public void clear() {
* Command}s.
* @param poseSupplier A function that returns the current field-relative {@link Pose2d} of the
* robot.
* @param controller A {@link ControlFunction} to follow the current {@link Trajectory}&lt;{@link
* @param controller A {@link BiConsumer} to follow the current {@link Trajectory}&lt;{@link
* SampleType}&gt;.
* @param mirrorTrajectory If this returns true, the path will be mirrored to the opposite side,
* while keeping the same coordinate system origin. This will be called every loop during the
Expand All @@ -304,7 +295,7 @@ public void clear() {
public static <SampleType extends TrajectorySample<SampleType>> AutoFactory createAutoFactory(
Subsystem driveSubsystem,
Supplier<Pose2d> poseSupplier,
ControlFunction<SampleType> controller,
BiConsumer<Pose2d, SampleType> controller,
BooleanSupplier mirrorTrajectory,
AutoBindings bindings) {
return new AutoFactory(
Expand All @@ -324,7 +315,7 @@ public static <SampleType extends TrajectorySample<SampleType>> AutoFactory crea
* Command}s.
* @param poseSupplier A function that returns the current field-relative {@link Pose2d} of the
* robot.
* @param controller A {@link ControlFunction} to follow the current {@link Trajectory}&lt;{@link
* @param controller A {@link BiConsumer} to follow the current {@link Trajectory}&lt;{@link
* SampleType}&gt;.
* @param mirrorTrajectory If this returns true, the path will be mirrored to the opposite side,
* while keeping the same coordinate system origin. This will be called every loop during the
Expand All @@ -339,7 +330,7 @@ public static <SampleType extends TrajectorySample<SampleType>> AutoFactory crea
public static <SampleType extends TrajectorySample<SampleType>> AutoFactory createAutoFactory(
Subsystem driveSubsystem,
Supplier<Pose2d> poseSupplier,
ControlFunction<SampleType> controller,
BiConsumer<Pose2d, SampleType> controller,
BooleanSupplier mirrorTrajectory,
AutoBindings bindings,
TrajectoryLogger<SampleType> trajectoryLogger) {
Expand Down
10 changes: 5 additions & 5 deletions choreolib/src/main/java/choreo/auto/AutoFactory.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
package choreo.auto;

import choreo.Choreo;
import choreo.Choreo.ControlFunction;
import choreo.Choreo.TrajectoryCache;
import choreo.Choreo.TrajectoryLogger;
import choreo.trajectory.SwerveSample;
Expand All @@ -20,6 +19,7 @@
import java.util.HashMap;
import java.util.List;
import java.util.Optional;
import java.util.function.BiConsumer;
import java.util.function.BooleanSupplier;
import java.util.function.Supplier;

Expand Down Expand Up @@ -124,7 +124,7 @@ HashMap<String, Command> getBindings() {

private final TrajectoryCache trajectoryCache = new TrajectoryCache();
private final Supplier<Pose2d> poseSupplier;
private final ControlFunction<? extends TrajectorySample<?>> controller;
private final BiConsumer<Pose2d, ? extends TrajectorySample<?>> controller;
private final BooleanSupplier mirrorTrajectory;
private final Subsystem driveSubsystem;
private final AutoBindings bindings = new AutoBindings();
Expand All @@ -144,7 +144,7 @@ HashMap<String, Command> getBindings() {
*/
public <SampleType extends TrajectorySample<SampleType>> AutoFactory(
Supplier<Pose2d> poseSupplier,
ControlFunction<SampleType> controller,
BiConsumer<Pose2d, SampleType> controller,
BooleanSupplier mirrorTrajectory,
Subsystem driveSubsystem,
AutoBindings bindings,
Expand Down Expand Up @@ -241,8 +241,8 @@ public <SampleType extends TrajectorySample<SampleType>> AutoTrajectory trajecto
Trajectory<SampleType> trajectory, AutoLoop loop) {
// type solidify everything
final Trajectory<SampleType> solidTrajectory = trajectory;
final ControlFunction<SampleType> solidController =
(ControlFunction<SampleType>) this.controller;
final BiConsumer<Pose2d, SampleType> solidController =
(BiConsumer<Pose2d, SampleType>) this.controller;
final Optional<TrajectoryLogger<SampleType>> solidLogger =
this.trajectoryLogger.map(logger -> (TrajectoryLogger<SampleType>) logger);
return new AutoTrajectory(
Expand Down
30 changes: 15 additions & 15 deletions choreolib/src/main/java/choreo/auto/AutoTrajectory.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@

package choreo.auto;

import choreo.Choreo.ControlFunction;
import choreo.Choreo.TrajectoryLogger;
import choreo.auto.AutoFactory.AutoBindings;
import choreo.trajectory.DifferentialSample;
Expand All @@ -21,6 +20,7 @@
import edu.wpi.first.wpilibj2.command.Subsystem;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import java.util.Optional;
import java.util.function.BiConsumer;
import java.util.function.BooleanSupplier;
import java.util.function.Supplier;

Expand All @@ -43,7 +43,7 @@ public class AutoTrajectory {
private final Trajectory<? extends TrajectorySample<?>> trajectory;
private final TrajectoryLogger<? extends TrajectorySample<?>> trajectoryLogger;
private final Supplier<Pose2d> poseSupplier;
private final ControlFunction<? extends TrajectorySample<?>> controller;
private final BiConsumer<Pose2d, ? extends TrajectorySample<?>> controller;
private final BooleanSupplier mirrorTrajectory;
private final Timer timer = new Timer();
private final Subsystem driveSubsystem;
Expand Down Expand Up @@ -80,7 +80,7 @@ <SampleType extends TrajectorySample<SampleType>> AutoTrajectory(
String name,
Trajectory<SampleType> trajectory,
Supplier<Pose2d> poseSupplier,
ControlFunction<SampleType> controller,
BiConsumer<Pose2d, SampleType> controller,
BooleanSupplier mirrorTrajectory,
Optional<TrajectoryLogger<SampleType>> trajectoryLogger,
Subsystem driveSubsystem,
Expand Down Expand Up @@ -155,13 +155,13 @@ private void cmdExecute() {
this.trajectory.sampleAt(timeIntoTrajectory(), mirrorTrajectory.getAsBoolean());

if (sample instanceof SwerveSample) {
ControlFunction<SwerveSample> swerveController =
(ControlFunction<SwerveSample>) this.controller;
BiConsumer<Pose2d, SwerveSample> swerveController =
(BiConsumer<Pose2d, SwerveSample>) this.controller;
SwerveSample swerveSample = (SwerveSample) sample;
swerveController.accept(poseSupplier.get(), swerveSample);
} else if (sample instanceof DifferentialSample) {
ControlFunction<DifferentialSample> differentialController =
(ControlFunction<DifferentialSample>) this.controller;
BiConsumer<Pose2d, DifferentialSample> differentialController =
(BiConsumer<Pose2d, DifferentialSample>) this.controller;
DifferentialSample differentialSample = (DifferentialSample) sample;
differentialController.accept(poseSupplier.get(), differentialSample);
}
Expand All @@ -173,27 +173,27 @@ private void cmdEnd(boolean interrupted) {
timer.stop();
if (interrupted) {
if (currentSample instanceof SwerveSample) {
ControlFunction<SwerveSample> swerveController =
(ControlFunction<SwerveSample>) this.controller;
BiConsumer<Pose2d, SwerveSample> swerveController =
(BiConsumer<Pose2d, SwerveSample>) this.controller;
SwerveSample swerveSample = (SwerveSample) currentSample;
swerveController.accept(currentSample.getPose(), swerveSample);
} else if (currentSample instanceof DifferentialSample) {
ControlFunction<DifferentialSample> differentialController =
(ControlFunction<DifferentialSample>) this.controller;
BiConsumer<Pose2d, DifferentialSample> differentialController =
(BiConsumer<Pose2d, DifferentialSample>) this.controller;
DifferentialSample differentialSample = (DifferentialSample) currentSample;
differentialController.accept(currentSample.getPose(), differentialSample);
}
} else {
TrajectorySample<?> sample = this.trajectory.getFinalSample();

if (sample instanceof SwerveSample) {
ControlFunction<SwerveSample> swerveController =
(ControlFunction<SwerveSample>) this.controller;
BiConsumer<Pose2d, SwerveSample> swerveController =
(BiConsumer<Pose2d, SwerveSample>) this.controller;
SwerveSample swerveSample = (SwerveSample) sample;
swerveController.accept(poseSupplier.get(), swerveSample);
} else if (sample instanceof DifferentialSample) {
ControlFunction<DifferentialSample> differentialController =
(ControlFunction<DifferentialSample>) this.controller;
BiConsumer<Pose2d, DifferentialSample> differentialController =
(BiConsumer<Pose2d, DifferentialSample>) this.controller;
DifferentialSample differentialSample = (DifferentialSample) sample;
differentialController.accept(poseSupplier.get(), differentialSample);
}
Expand Down
4 changes: 2 additions & 2 deletions choreolib/src/main/native/include/choreo/auto/AutoFactory.h
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ class AutoFactory {
* @param trajectoryLogger Choreo::CreateAutoFactory()
*/
AutoFactory(std::function<frc::Pose2d()> poseSupplier,
ControllerFunction<SampleType> controller,
std::function<void(frc::Pose2d, SampleType)> controller,
std::function<bool()> mirrorTrajectory,
const frc2::Subsystem& driveSubsystem, AutoBindings bindings,
std::optional<TrajectoryLogger> trajectoryLogger)
Expand Down Expand Up @@ -236,7 +236,7 @@ class AutoFactory {

private:
std::function<frc::Pose2d()> poseSupplier;
ControllerFunction<SampleType> controller;
std::function<void(frc::Pose2d, SampleType)> controller;
std::function<bool()> mirrorTrajectory;
const frc2::Subsystem& driveSubsystem;
AutoBindings autoBindings{};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,9 +21,6 @@

namespace choreo {

template <choreo::TrajectorySample SampleType>
using ControllerFunction = std::function<void(frc::Pose2d, SampleType)>;

using TrajectoryLogger = std::function<void(frc::Pose2d, bool)>;

static constexpr units::meter_t DEFAULT_TOLERANCE = 3_in;
Expand Down Expand Up @@ -55,7 +52,7 @@ class AutoTrajectory {
AutoTrajectory(std::string_view name,
const choreo::Trajectory<SampleType>& trajectory,
std::function<frc::Pose2d()> poseSupplier,
ControllerFunction<SampleType> controller,
std::function<void(frc::Pose2d, SampleType)> controller,
std::function<bool()> mirrorTrajectory,
std::optional<TrajectoryLogger> trajectoryLogger,
const frc2::Subsystem& driveSubsystem, frc::EventLoop* loop,
Expand Down Expand Up @@ -330,7 +327,7 @@ class AutoTrajectory {
std::string name;
const choreo::Trajectory<SampleType>& trajectory;
std::function<frc::Pose2d()> poseSupplier;
ControllerFunction<SampleType> controller;
std::function<void(frc::Pose2d, SampleType)> controller;
std::function<bool()> mirrorTrajectory;
std::optional<TrajectoryLogger> trajectoryLogger;
const frc2::Subsystem& driveSubsystem;
Expand Down

0 comments on commit 174b678

Please sign in to comment.