Skip to content

Commit

Permalink
close 4 auto
Browse files Browse the repository at this point in the history
  • Loading branch information
r4stered committed Oct 20, 2024
1 parent 6355b9e commit 2a7514b
Show file tree
Hide file tree
Showing 5 changed files with 111 additions and 107 deletions.
15 changes: 8 additions & 7 deletions src/main/cpp/RobotContainer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
#include <frc/RobotBase.h>
#include <frc2/command/Commands.h>
#include <str/DriverstationUtils.h>
#include <frc2/command/button/RobotModeTriggers.h>

RobotContainer::RobotContainer() {
ConfigureBindings();
Expand Down Expand Up @@ -37,19 +38,19 @@ void RobotContainer::ConfigureBindings() {
driverController.Start().WhileTrue(intakeSubsystem.FakeNote());
}

driverController.LeftTrigger().OnTrue(IntakeNote());
(!driverController.LeftTrigger() && !intakeSubsystem.TouchedNote())
(driverController.LeftTrigger() && frc2::RobotModeTriggers::Teleop()).OnTrue(IntakeNote());
(!driverController.LeftTrigger() && !intakeSubsystem.TouchedNote() && frc2::RobotModeTriggers::Teleop())
.OnTrue(frc2::cmd::Sequence(intakeSubsystem.Stop(),
frc2::cmd::Print("Cancelled")));

(shooterSubsystem.UpToSpeed() && driverController.RightTrigger())
(shooterSubsystem.UpToSpeed() && driverController.RightTrigger() && frc2::RobotModeTriggers::Teleop())
.OnTrue(feederSubsystem.Feed())
.OnFalse(feederSubsystem.Stop());

intakeSubsystem.TouchedNote().OnTrue(RumbleDriver([] { return .1_s; }));
feederSubsystem.GotNote().OnTrue(frc2::cmd::Parallel(
intakeSubsystem.Stop(), feederSubsystem.Stop(),
RumbleDriver([] { return .5_s; }), RumbleOperator([] { return .5_s; })));
// intakeSubsystem.TouchedNote().OnTrue(RumbleDriver([] { return .1_s; }));
// feederSubsystem.GotNote().OnTrue(frc2::cmd::Parallel(
// intakeSubsystem.Stop(), feederSubsystem.Stop(),
// RumbleDriver([] { return .5_s; }), RumbleOperator([] { return .5_s; })));

driverController.A().WhileTrue(swerveSubsystem.AlignToAmp());

Expand Down
2 changes: 1 addition & 1 deletion src/main/cpp/pathplanner/lib/path/PathPlannerPath.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -265,7 +265,7 @@ void PathPlannerPath::loadChoreoTrajectoryIntoCache(
size_t splitStartIdx = splits[i];

size_t splitEndIdx = fullTrajStates.size();
if (i < splits.size()) {
if (i < splits.size() - 1) {
splitEndIdx = splits[i + 1];
}

Expand Down
Loading

0 comments on commit 2a7514b

Please sign in to comment.