Skip to content

Commit

Permalink
Started working on creating an auto "subsystem"
Browse files Browse the repository at this point in the history
  • Loading branch information
DylanTaylor29 committed Jan 17, 2025
1 parent c25fdf5 commit a6e2138
Show file tree
Hide file tree
Showing 4 changed files with 69 additions and 23 deletions.
File renamed without changes.
File renamed without changes.
46 changes: 46 additions & 0 deletions src/main/java/frc/robot/Auto.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
package frc.robot;

import choreo.auto.AutoFactory;
import choreo.auto.AutoRoutine;
import choreo.auto.AutoTrajectory;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import frc.lib.AllianceSelector;
import frc.robot.Constants.AutoConstants;
import frc.robot.drivetrain.Drivetrain;

public class Auto {
private final AllianceSelector m_allianceSelector;
private final Drivetrain m_swerve;

private final AutoFactory m_autoFactory;

public Auto() {
m_allianceSelector = new AllianceSelector(AutoConstants.kAllianceColorSelectorPort);

m_swerve = new Drivetrain(m_allianceSelector::fieldRotated);

m_autoFactory = new AutoFactory(m_swerve::getPose, m_swerve::setPose, m_swerve::followTrajectory, false, m_swerve);
}

public class RedTraj {}

public class BlueTraj {
Command examplePath = m_autoFactory.trajectoryCmd("examplePath");
}

public AutoRoutine exampleRoutine() {
AutoRoutine exampleRoutine = m_autoFactory.newRoutine("exampleRoutine");

AutoTrajectory exampleTrajectory = exampleRoutine.trajectory("examplePath");

exampleRoutine.active().onTrue(
Commands.sequence(
exampleTrajectory.resetOdometry(),
exampleTrajectory.cmd()
)
);

return exampleRoutine;
}
}
46 changes: 23 additions & 23 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ public class Robot extends TimedRobot {
private final Drivetrain m_swerve;
private final LEDs m_LEDs;

private final AutoFactory m_autoFactory;
// private final AutoFactory m_autoFactory;

private CommandZorroController m_driver;
private CommandXboxController m_operator;
Expand Down Expand Up @@ -67,7 +67,7 @@ public Robot() {
"Align Encoders",
new InstantCommand(() -> m_swerve.zeroAbsTurningEncoderOffsets()).ignoringDisable(true));

m_autoFactory = new AutoFactory(m_swerve::getPose, m_swerve::setPose, m_swerve::followTrajectory, false, m_swerve);
// m_autoFactory = new AutoFactory(m_swerve::getPose, m_swerve::setPose, m_swerve::followTrajectory, false, m_swerve);
}

@Override
Expand Down Expand Up @@ -194,25 +194,25 @@ public double getPDHCurrent(int CANBusPort) {
return m_powerDistribution.getCurrent(CANBusPort - 10);
}

public ChoreoAuto auto = new ChoreoAuto() {

final String getName() {
return "Example Auto";
}

public Command getCommand() {
return Commands.sequence(
m_autoFactory.resetOdometry("pickupGamepiece"),
Commands.deadline(
m_autoFactory.trajectoryCmd("pickupGamepiece")
// intakeSubsystem.intake()
),
Commands.parallel(
m_autoFactory.trajectoryCmd("scoreGamepiece")
// scoringSubsystem.getReady()
)
// scoringSubsystem.score()
);
}
}
// public ChoreoAuto auto = new ChoreoAuto() {

// final String getName() {
// return "Example Auto";
// }

// public Command getCommand() {
// return Commands.sequence(
// m_autoFactory.resetOdometry("pickupGamepiece"),
// Commands.deadline(
// m_autoFactory.trajectoryCmd("pickupGamepiece")
// // intakeSubsystem.intake()
// ),
// Commands.parallel(
// m_autoFactory.trajectoryCmd("scoreGamepiece")
// // scoringSubsystem.getReady()
// )
// // scoringSubsystem.score()
// );
// }
// }
}

0 comments on commit a6e2138

Please sign in to comment.