001// Copyright (c) Choreo contributors 002 003package choreo.auto; 004 005import static choreo.util.ChoreoAlert.allianceNotReady; 006import static edu.wpi.first.wpilibj.Alert.AlertType.kError; 007 008import choreo.Choreo.TrajectoryLogger; 009import choreo.auto.AutoFactory.AllianceContext; 010import choreo.auto.AutoFactory.AutoBindings; 011import choreo.trajectory.DifferentialSample; 012import choreo.trajectory.SwerveSample; 013import choreo.trajectory.Trajectory; 014import choreo.trajectory.TrajectorySample; 015import choreo.util.ChoreoAlert; 016import choreo.util.ChoreoAlert.MultiAlert; 017import choreo.util.ChoreoAllianceFlipUtil; 018import edu.wpi.first.math.geometry.Pose2d; 019import edu.wpi.first.math.geometry.Rotation2d; 020import edu.wpi.first.math.geometry.Translation2d; 021import edu.wpi.first.wpilibj.Timer; 022import edu.wpi.first.wpilibj2.command.Command; 023import edu.wpi.first.wpilibj2.command.Commands; 024import edu.wpi.first.wpilibj2.command.FunctionalCommand; 025import edu.wpi.first.wpilibj2.command.ScheduleCommand; 026import edu.wpi.first.wpilibj2.command.Subsystem; 027import edu.wpi.first.wpilibj2.command.button.Trigger; 028import java.util.Optional; 029import java.util.OptionalInt; 030import java.util.function.BooleanSupplier; 031import java.util.function.Consumer; 032import java.util.function.Supplier; 033 034/** 035 * A class that represents a trajectory that can be used in an autonomous routine and have triggers 036 * based off of it. 037 */ 038public class AutoTrajectory { 039 // For any devs looking through this class wondering 040 // about all the type casting and `?` for generics it's intentional. 041 // My goal was to make the sample type minimally leak into user code 042 // so you don't have to retype the sample type everywhere in your auto 043 // code. This also makes the places with generics exposed to users few 044 // and far between. This helps with more novice users 045 046 private static final MultiAlert triggerTimeNegative = 047 ChoreoAlert.multiAlert(causes -> "Trigger time cannot be negative for " + causes, kError); 048 private static final MultiAlert triggerTimeAboveMax = 049 ChoreoAlert.multiAlert( 050 causes -> "Trigger time cannot be greater than total trajectory time for " + causes + ".", 051 kError); 052 private static final MultiAlert eventNotFound = 053 ChoreoAlert.multiAlert(causes -> "Event Markers " + causes + " not found.", kError); 054 private static final MultiAlert noSamples = 055 ChoreoAlert.multiAlert(causes -> "Trajectories " + causes + " have no samples.", kError); 056 private static final MultiAlert noInitialPose = 057 ChoreoAlert.multiAlert( 058 causes -> "Unable to get initial pose for trajectories " + causes + ".", kError); 059 060 private final String name; 061 private final Trajectory<? extends TrajectorySample<?>> trajectory; 062 private final TrajectoryLogger<? extends TrajectorySample<?>> trajectoryLogger; 063 private final Supplier<Pose2d> poseSupplier; 064 private final Consumer<Pose2d> resetOdometry; 065 private final Consumer<? extends TrajectorySample<?>> controller; 066 private final AllianceContext allianceCtx; 067 private final Timer activeTimer = new Timer(); 068 private final Timer inactiveTimer = new Timer(); 069 private final Subsystem driveSubsystem; 070 private final AutoRoutine routine; 071 072 /** 073 * A way to create slightly less triggers for many actions. Not static as to not leak triggers 074 * made here into another static EventLoop. 075 */ 076 private final Trigger offTrigger; 077 078 /** If this trajectory us currently running */ 079 private boolean isActive = false; 080 081 /** If the trajectory ran to completion */ 082 private boolean isCompleted = false; 083 084 /** 085 * Constructs an AutoTrajectory. 086 * 087 * @param name The trajectory name. 088 * @param trajectory The trajectory samples. 089 * @param poseSupplier The pose supplier. 090 * @param controller The controller function. 091 * @param allianceCtx The alliance context. 092 * @param trajectoryLogger Optional trajectory logger. 093 * @param driveSubsystem Drive subsystem. 094 * @param routine Event loop. 095 * @param bindings {@link AutoFactory} 096 */ 097 <SampleType extends TrajectorySample<SampleType>> AutoTrajectory( 098 String name, 099 Trajectory<SampleType> trajectory, 100 Supplier<Pose2d> poseSupplier, 101 Consumer<Pose2d> resetOdometry, 102 Consumer<SampleType> controller, 103 AllianceContext allianceCtx, 104 TrajectoryLogger<SampleType> trajectoryLogger, 105 Subsystem driveSubsystem, 106 AutoRoutine routine, 107 AutoBindings bindings) { 108 this.name = name; 109 this.trajectory = trajectory; 110 this.poseSupplier = poseSupplier; 111 this.resetOdometry = resetOdometry; 112 this.controller = controller; 113 this.allianceCtx = allianceCtx; 114 this.driveSubsystem = driveSubsystem; 115 this.routine = routine; 116 this.offTrigger = new Trigger(routine.loop(), () -> false); 117 this.trajectoryLogger = trajectoryLogger; 118 119 bindings.getBindings().forEach((key, value) -> active().and(atTime(key)).onTrue(value)); 120 } 121 122 @SuppressWarnings("unchecked") 123 private void logTrajectory(boolean starting) { 124 var sampleOpt = trajectory.getInitialSample(false); 125 if (sampleOpt.isEmpty()) { 126 return; 127 } 128 var sample = sampleOpt.get(); 129 if (sample instanceof SwerveSample) { 130 TrajectoryLogger<SwerveSample> swerveLogger = 131 (TrajectoryLogger<SwerveSample>) trajectoryLogger; 132 Trajectory<SwerveSample> swerveTrajectory = (Trajectory<SwerveSample>) trajectory; 133 swerveLogger.accept(swerveTrajectory, starting); 134 } else if (sample instanceof DifferentialSample) { 135 TrajectoryLogger<DifferentialSample> differentialLogger = 136 (TrajectoryLogger<DifferentialSample>) trajectoryLogger; 137 Trajectory<DifferentialSample> differentialTrajectory = 138 (Trajectory<DifferentialSample>) trajectory; 139 differentialLogger.accept(differentialTrajectory, starting); 140 } 141 ; 142 } 143 144 private void cmdInitialize() { 145 activeTimer.start(); 146 inactiveTimer.stop(); 147 inactiveTimer.reset(); 148 isActive = true; 149 isCompleted = false; 150 logTrajectory(true); 151 routine.updateIdle(false); 152 } 153 154 @SuppressWarnings("unchecked") 155 private void cmdExecute() { 156 if (!allianceCtx.allianceKnownOrIgnored()) { 157 allianceNotReady.set(true); 158 return; 159 } 160 var sampleOpt = trajectory.sampleAt(activeTimer.get(), allianceCtx.doFlip()); 161 if (sampleOpt.isEmpty()) { 162 return; 163 } 164 var sample = sampleOpt.get(); 165 if (sample instanceof SwerveSample swerveSample) { 166 var swerveController = (Consumer<SwerveSample>) this.controller; 167 swerveController.accept(swerveSample); 168 } else if (sample instanceof DifferentialSample differentialSample) { 169 var differentialController = (Consumer<DifferentialSample>) this.controller; 170 differentialController.accept(differentialSample); 171 } 172 } 173 174 @SuppressWarnings("unchecked") 175 private void cmdEnd(boolean interrupted) { 176 activeTimer.stop(); 177 activeTimer.reset(); 178 inactiveTimer.start(); 179 isActive = false; 180 isCompleted = !interrupted; 181 182 if (!interrupted && allianceCtx.allianceKnownOrIgnored()) { 183 var sampleOpt = trajectory.getFinalSample(allianceCtx.doFlip()); 184 if (sampleOpt.isPresent()) { 185 var sample = sampleOpt.get(); 186 if (sample instanceof SwerveSample swerveSample) { 187 var swerveController = (Consumer<SwerveSample>) this.controller; 188 swerveController.accept(swerveSample); 189 } else if (sample instanceof DifferentialSample differentialSample) { 190 var differentialController = (Consumer<DifferentialSample>) this.controller; 191 differentialController.accept(differentialSample); 192 } 193 } 194 } 195 196 logTrajectory(false); 197 routine.updateIdle(true); 198 } 199 200 private boolean cmdIsFinished() { 201 return activeTimer.get() > trajectory.getTotalTime() 202 || !routine.active().getAsBoolean() 203 || !allianceCtx.allianceKnownOrIgnored(); 204 } 205 206 /** 207 * Creates a command that allocates the drive subsystem and follows the trajectory using the 208 * factories control function 209 * 210 * @return The command that will follow the trajectory 211 */ 212 public Command cmd() { 213 // if the trajectory is empty, return a command that will print an error 214 if (trajectory.samples().isEmpty()) { 215 return driveSubsystem.runOnce(() -> noSamples.addCause(name)).withName("Trajectory_" + name); 216 } 217 return new FunctionalCommand( 218 this::cmdInitialize, 219 this::cmdExecute, 220 this::cmdEnd, 221 this::cmdIsFinished, 222 driveSubsystem) 223 .withName("Trajectory_" + name); 224 } 225 226 /** 227 * Creates a command that will schedule <b>another</b> command that will follow the trajectory. 228 * 229 * <p>This can be useful when putting {@link AutoTrajectory} commands in sequences that require 230 * subsystems also required by in AutoTrajectory-bound subsystems. 231 * 232 * @return The command that will schedule the trajectory following command. 233 */ 234 public Command spawnCmd() { 235 return new ScheduleCommand(cmd()).withName("Trajectory_" + name + "_Spawner"); 236 } 237 238 /** 239 * Creates a command that resets the robot's odometry to the start of this trajectory. 240 * 241 * @return A command that resets the robot's odometry. 242 */ 243 public Command resetOdometry() { 244 return Commands.either( 245 Commands.runOnce(() -> resetOdometry.accept(getInitialPose().get()), driveSubsystem), 246 Commands.runOnce( 247 () -> { 248 noInitialPose.addCause(name); 249 routine.kill(); 250 }) 251 .andThen(driveSubsystem.run(() -> {})), 252 () -> getInitialPose().isPresent()) 253 .withName("Trajectory_ResetOdometry_" + name); 254 } 255 256 /** 257 * Will get the underlying {@link Trajectory} object. 258 * 259 * <p><b>WARNING:</b> This method is not type safe and should be used with caution. The sample 260 * type of the trajectory should be known before calling this method. 261 * 262 * @param <SampleType> The type of the trajectory samples. 263 * @return The underlying {@link Trajectory} object. 264 */ 265 @SuppressWarnings("unchecked") 266 public <SampleType extends TrajectorySample<SampleType>> 267 Trajectory<SampleType> getRawTrajectory() { 268 return (Trajectory<SampleType>) trajectory; 269 } 270 271 /** 272 * Will get the starting pose of the trajectory. 273 * 274 * <p>This position is flipped if alliance flipping is enabled and the alliance supplier returns 275 * Red. 276 * 277 * <p>This method returns an empty Optional if the trajectory is empty. This method returns an 278 * empty Optional if alliance flipping is enabled and the alliance supplier returns an empty 279 * Optional. 280 * 281 * @return The starting pose 282 */ 283 public Optional<Pose2d> getInitialPose() { 284 if (!allianceCtx.allianceKnownOrIgnored()) { 285 allianceNotReady.set(true); 286 return Optional.empty(); 287 } 288 return trajectory.getInitialPose(allianceCtx.doFlip()); 289 } 290 291 /** 292 * Will get the ending pose of the trajectory. 293 * 294 * <p>This position is flipped if alliance flipping is enabled and the alliance supplier returns 295 * Red. 296 * 297 * <p>This method returns an empty Optional if the trajectory is empty. This method returns an 298 * empty Optional if alliance flipping is enabled and the alliance supplier returns an empty 299 * Optional. 300 * 301 * @return The starting pose 302 */ 303 public Optional<Pose2d> getFinalPose() { 304 if (!allianceCtx.allianceKnownOrIgnored()) { 305 allianceNotReady.set(true); 306 return Optional.empty(); 307 } 308 return trajectory.getFinalPose(allianceCtx.doFlip()); 309 } 310 311 /** 312 * Returns a trigger that is true while the trajectory is scheduled. 313 * 314 * @return A trigger that is true while the trajectory is scheduled. 315 */ 316 public Trigger active() { 317 return new Trigger(routine.loop(), () -> this.isActive && routine.active().getAsBoolean()); 318 } 319 320 /** 321 * Returns a trigger that is true while the command is not scheduled. 322 * 323 * <p>The same as calling <code>active().negate()</code>. 324 * 325 * @return A trigger that is true while the command is not scheduled. 326 */ 327 public Trigger inactive() { 328 return active().negate(); 329 } 330 331 private Trigger timeTrigger(double targetTime, Timer timer) { 332 // Make the trigger only be high for 1 cycle when the time has elapsed 333 return new Trigger( 334 routine.loop(), 335 new BooleanSupplier() { 336 double lastTimestamp = -1.0; 337 OptionalInt pollTarget = OptionalInt.empty(); 338 339 public boolean getAsBoolean() { 340 if (!timer.isRunning()) { 341 lastTimestamp = -1.0; 342 pollTarget = OptionalInt.empty(); 343 return false; 344 } 345 double nowTimestamp = timer.get(); 346 try { 347 boolean timeAligns = lastTimestamp < targetTime && nowTimestamp >= targetTime; 348 if (pollTarget.isEmpty() && timeAligns) { 349 // if the time aligns for this cycle and it hasn't aligned previously this cycle 350 pollTarget = OptionalInt.of(routine.pollCount()); 351 return true; 352 } else if (pollTarget.isPresent() && routine.pollCount() == pollTarget.getAsInt()) { 353 // if the time aligned previously this cycle 354 return true; 355 } else if (pollTarget.isPresent()) { 356 // if the time aligned last cycle 357 pollTarget = OptionalInt.empty(); 358 return false; 359 } 360 return false; 361 } finally { 362 lastTimestamp = nowTimestamp; 363 } 364 } 365 }); 366 } 367 368 private Trigger enterExitTrigger(Trigger enter, Trigger exit) { 369 return new Trigger( 370 routine.loop(), 371 new BooleanSupplier() { 372 boolean output = false; 373 374 @Override 375 public boolean getAsBoolean() { 376 if (enter.getAsBoolean()) { 377 output = true; 378 } 379 if (exit.getAsBoolean()) { 380 output = false; 381 } 382 return output; 383 } 384 }); 385 } 386 387 /** 388 * Returns a trigger that rises to true a number of cycles after the trajectory ends and falls 389 * after one pulse. 390 * 391 * <p>This is different from inactive() in a few ways. 392 * 393 * <ul> 394 * <li>This will never be true if the trajectory is interrupted 395 * <li>This will never be true before the trajectory is run 396 * <li>This will fall the next cycle after the trajectory ends 397 * </ul> 398 * 399 * <p>Why does the trigger need to fall? 400 * 401 * <pre><code> 402 * //Lets say we had this code segment 403 * Trigger hasGamepiece = ...; 404 * Trigger noGamepiece = hasGamepiece.negate(); 405 * 406 * AutoTrajectory rushMidTraj = ...; 407 * AutoTrajectory goShootGamepiece = ...; 408 * AutoTrajectory pickupAnotherGamepiece = ...; 409 * 410 * routine.enabled().onTrue(rushMidTraj.cmd()); 411 * 412 * rushMidTraj.doneDelayed(10).and(noGamepiece).onTrue(pickupAnotherGamepiece.cmd()); 413 * rushMidTraj.doneDelayed(10).and(hasGamepiece).onTrue(goShootGamepiece.cmd()); 414 * 415 * // If done never falls when a new trajectory is scheduled 416 * // then these triggers leak into the next trajectory, causing the next note pickup 417 * // to trigger goShootGamepiece.cmd() even if we no longer care about these checks 418 * </code></pre> 419 * 420 * @param seconds The seconds to delay the trigger from rising to true. 421 * @return A trigger that is true when the trajectory is finished. 422 */ 423 public Trigger doneDelayed(double seconds) { 424 return timeTrigger(seconds, inactiveTimer).and(new Trigger(routine.loop(), () -> isCompleted)); 425 } 426 427 /** 428 * Returns a trigger that rises to true when the trajectory ends and falls after one pulse. 429 * 430 * <p>This is different from inactive() in a few ways. 431 * 432 * <ul> 433 * <li>This will never be true if the trajectory is interrupted 434 * <li>This will never be true before the trajectory is run 435 * <li>This will fall the next cycle after the trajectory ends 436 * </ul> 437 * 438 * <p>Why does the trigger need to fall? 439 * 440 * <pre><code> 441 * //Lets say we had this code segment 442 * Trigger hasGamepiece = ...; 443 * Trigger noGamepiece = hasGamepiece.negate(); 444 * 445 * AutoTrajectory rushMidTraj = ...; 446 * AutoTrajectory goShootGamepiece = ...; 447 * AutoTrajectory pickupAnotherGamepiece = ...; 448 * 449 * routine.enabled().onTrue(rushMidTraj.cmd()); 450 * 451 * rushMidTraj.done().and(noGamepiece).onTrue(pickupAnotherGamepiece.cmd()); 452 * rushMidTraj.done().and(hasGamepiece).onTrue(goShootGamepiece.cmd()); 453 * 454 * // If done never falls when a new trajectory is scheduled 455 * // then these triggers leak into the next trajectory, causing the next note pickup 456 * // to trigger goShootGamepiece.cmd() even if we no longer care about these checks 457 * </code></pre> 458 * 459 * @return A trigger that is true when the trajectory is finished. 460 */ 461 public Trigger done() { 462 return doneDelayed(0); 463 } 464 465 /** 466 * Returns a trigger that stays true for a number of cycles after the trajectory ends. 467 * 468 * @param seconds Seconds to stay true after the trajectory ends. 469 * @return A trigger that stays true for a number of cycles after the trajectory ends. 470 */ 471 public Trigger doneFor(double seconds) { 472 return enterExitTrigger(doneDelayed(0), doneDelayed(seconds)); 473 } 474 475 /** 476 * Returns a trigger that is true when the trajectory was the last one active and is done. 477 * 478 * @return A trigger that is true when the trajectory was the last one active and is done. 479 */ 480 public Trigger recentlyDone() { 481 return enterExitTrigger(doneDelayed(0), routine.idle().negate()); 482 } 483 484 /** 485 * A shorthand for `.done().onTrue(otherTrajectory.cmd())` 486 * 487 * @param otherTrajectory The other trajectory to run when this one is done. 488 */ 489 public void chain(AutoTrajectory otherTrajectory) { 490 done().onTrue(otherTrajectory.cmd()); 491 } 492 493 /** 494 * Returns a trigger that will go true for 1 cycle when the desired time has elapsed 495 * 496 * @param timeSinceStart The time since the command started in seconds. 497 * @return A trigger that is true when timeSinceStart has elapsed. 498 */ 499 public Trigger atTime(double timeSinceStart) { 500 // The timer should never be negative so report this as a warning 501 if (timeSinceStart < 0) { 502 triggerTimeNegative.addCause(name); 503 return offTrigger; 504 } 505 506 // The timer should never exceed the total trajectory time so report this as a warning 507 if (timeSinceStart > trajectory.getTotalTime()) { 508 triggerTimeAboveMax.addCause(name); 509 return offTrigger; 510 } 511 512 return timeTrigger(timeSinceStart, activeTimer); 513 } 514 515 /** 516 * Returns a trigger that will go true for 1 cycle when the desired before the end of the 517 * trajectory time. 518 * 519 * @param timeBeforeEnd The time before the end of the trajectory. 520 * @return A trigger that is true when timeBeforeEnd has elapsed. 521 */ 522 public Trigger atTimeBeforeEnd(double timeBeforeEnd) { 523 return atTime(trajectory.getTotalTime() - timeBeforeEnd); 524 } 525 526 /** 527 * Returns a trigger that is true when the event with the given name has been reached based on 528 * time. 529 * 530 * <p>A warning will be printed to the DriverStation if the event is not found and the trigger 531 * will always be false. 532 * 533 * @param eventName The name of the event. 534 * @return A trigger that is true when the event with the given name has been reached based on 535 * time. 536 * @see <a href="https://choreo.autos/usage/editing-paths/#event-markers">Event Markers in the 537 * GUI</a> 538 */ 539 public Trigger atTime(String eventName) { 540 boolean foundEvent = false; 541 Trigger trig = offTrigger; 542 543 for (var event : trajectory.getEvents(eventName)) { 544 // This could create a lot of objects, could be done a more efficient way 545 // with having it all be 1 trigger that just has a list of times and checks each one each 546 // cycle 547 // or something like that. If choreo starts proposing memory issues we can look into this. 548 trig = trig.or(atTime(event.timestamp)); 549 foundEvent = true; 550 } 551 552 // The user probably expects an event to exist if they're trying to do something at that event, 553 // report the missing event. 554 if (!foundEvent) { 555 eventNotFound.addCause(name); 556 } 557 558 return trig; 559 } 560 561 private boolean withinTolerance(Rotation2d lhs, Rotation2d rhs, double toleranceRadians) { 562 if (Math.abs(toleranceRadians) > Math.PI) { 563 return true; 564 } 565 double dot = lhs.getCos() * rhs.getCos() + lhs.getSin() * rhs.getSin(); 566 // cos(θ) >= cos(tolerance) means |θ| <= tolerance, for tolerance in [-pi, pi], as pre-checked 567 // above. 568 return dot > Math.cos(toleranceRadians); 569 } 570 571 /** 572 * Returns a trigger that is true when the robot is within toleranceMeters of the given pose. 573 * 574 * <p>The pose is flipped if alliance flipping is enabled and the alliance supplier returns Red. 575 * 576 * <p>While alliance flipping is enabled and the alliance supplier returns empty, the trigger will 577 * return false. 578 * 579 * @param pose The pose to check against, unflipped. 580 * @param toleranceMeters The tolerance in meters. 581 * @param toleranceRadians The heading tolerance in radians. 582 * @return A trigger that is true when the robot is within toleranceMeters of the given pose. 583 */ 584 public Trigger atPose(Pose2d pose, double toleranceMeters, double toleranceRadians) { 585 Pose2d flippedPose = ChoreoAllianceFlipUtil.flip(pose); 586 return new Trigger( 587 routine.loop(), 588 () -> { 589 if (allianceCtx.allianceKnownOrIgnored()) { 590 final Pose2d currentPose = poseSupplier.get(); 591 if (allianceCtx.doFlip()) { 592 boolean transValid = 593 currentPose.getTranslation().getDistance(flippedPose.getTranslation()) 594 < toleranceMeters; 595 boolean rotValid = 596 withinTolerance( 597 currentPose.getRotation(), flippedPose.getRotation(), toleranceRadians); 598 return transValid && rotValid; 599 } else { 600 boolean transValid = 601 currentPose.getTranslation().getDistance(pose.getTranslation()) 602 < toleranceMeters; 603 boolean rotValid = 604 withinTolerance( 605 currentPose.getRotation(), pose.getRotation(), toleranceRadians); 606 return transValid && rotValid; 607 } 608 } else { 609 allianceNotReady.set(true); 610 return false; 611 } 612 }) 613 .and(active()); 614 } 615 616 /** 617 * Returns a trigger that is true when the robot is within toleranceMeters and toleranceRadians of 618 * the given event's pose. 619 * 620 * <p>A warning will be printed to the DriverStation if the event is not found and the trigger 621 * will always be false. 622 * 623 * @param eventName The name of the event. 624 * @param toleranceMeters The tolerance in meters. 625 * @param toleranceRadians The heading tolerance in radians. 626 * @return A trigger that is true when the robot is within toleranceMeters of the given events 627 * pose. 628 * @see <a href="https://choreo.autos/usage/editing-paths/#event-markers">Event Markers in the 629 * GUI</a> 630 */ 631 public Trigger atPose(String eventName, double toleranceMeters, double toleranceRadians) { 632 boolean foundEvent = false; 633 Trigger trig = offTrigger; 634 635 for (var event : trajectory.getEvents(eventName)) { 636 // This could create a lot of objects, could be done a more efficient way 637 // with having it all be 1 trigger that just has a list of possess and checks each one each 638 // cycle or something like that. 639 // If choreo starts showing memory issues we can look into this. 640 Optional<Pose2d> poseOpt = 641 trajectory 642 // don't mirror here because the poses are mirrored themselves 643 // this also lets atPose be called before the alliance is ready 644 .sampleAt(event.timestamp, false) 645 .map(TrajectorySample::getPose); 646 if (poseOpt.isPresent()) { 647 trig = trig.or(atPose(poseOpt.get(), toleranceMeters, toleranceRadians)); 648 foundEvent = true; 649 } 650 } 651 652 // The user probably expects an event to exist if they're trying to do something at that event, 653 // report the missing event. 654 if (!foundEvent) { 655 eventNotFound.addCause(name); 656 } 657 658 return trig; 659 } 660 661 /** 662 * Returns a trigger that is true when the robot is within toleranceMeters of the given 663 * translation. 664 * 665 * <p>The translation is flipped if alliance flipping is enabled and the alliance supplier returns 666 * Red. 667 * 668 * <p>While alliance flipping is enabled and the alliance supplier returns empty, the trigger will 669 * return false. 670 * 671 * @param translation The translation to check against, unflipped. 672 * @param toleranceMeters The tolerance in meters. 673 * @return A trigger that is true when the robot is within toleranceMeters of the given 674 * translation. 675 */ 676 public Trigger atTranslation(Translation2d translation, double toleranceMeters) { 677 Translation2d flippedTranslation = ChoreoAllianceFlipUtil.flip(translation); 678 return new Trigger( 679 routine.loop(), 680 () -> { 681 if (allianceCtx.allianceKnownOrIgnored()) { 682 final Translation2d currentTrans = poseSupplier.get().getTranslation(); 683 if (allianceCtx.doFlip()) { 684 return currentTrans.getDistance(flippedTranslation) < toleranceMeters; 685 } else { 686 return currentTrans.getDistance(translation) < toleranceMeters; 687 } 688 } else { 689 allianceNotReady.set(true); 690 return false; 691 } 692 }) 693 .and(active()); 694 } 695 696 /** 697 * Returns a trigger that is true when the robot is within toleranceMeters and toleranceRadians of 698 * the given event's translation. 699 * 700 * <p>A warning will be printed to the DriverStation if the event is not found and the trigger 701 * will always be false. 702 * 703 * @param eventName The name of the event. 704 * @param toleranceMeters The tolerance in meters. 705 * @return A trigger that is true when the robot is within toleranceMeters of the given events 706 * translation. 707 * @see <a href="https://choreo.autos/usage/editing-paths/#event-markers">Event Markers in the 708 * GUI</a> 709 */ 710 public Trigger atTranslation(String eventName, double toleranceMeters) { 711 boolean foundEvent = false; 712 Trigger trig = offTrigger; 713 714 for (var event : trajectory.getEvents(eventName)) { 715 // This could create a lot of objects, could be done a more efficient way 716 // with having it all be 1 trigger that just has a list of poses and checks each one each 717 // cycle or something like that. 718 // If choreo starts showing memory issues we can look into this. 719 Optional<Translation2d> translationOpt = 720 trajectory 721 // don't mirror here because the translations are mirrored themselves 722 // this also lets atTranslation be called before the alliance is ready 723 .sampleAt(event.timestamp, false) 724 .map(TrajectorySample::getPose) 725 .map(Pose2d::getTranslation); 726 if (translationOpt.isPresent()) { 727 trig = trig.or(atTranslation(translationOpt.get(), toleranceMeters)); 728 foundEvent = true; 729 } 730 } 731 732 // The user probably expects an event to exist if they're trying to do something at that event, 733 // report the missing event. 734 if (!foundEvent) { 735 eventNotFound.addCause(name); 736 } 737 738 return trig; 739 } 740 741 /** 742 * Returns an array of all the timestamps of the events with the given name. 743 * 744 * @param eventName The name of the event. 745 * @return An array of all the timestamps of the events with the given name. 746 * @see <a href="https://choreo.autos/usage/editing-paths/#event-markers">Event Markers in the 747 * GUI</a> 748 */ 749 public double[] collectEventTimes(String eventName) { 750 double[] times = 751 trajectory.getEvents(eventName).stream() 752 .filter(e -> e.timestamp >= 0 && e.timestamp <= trajectory.getTotalTime()) 753 .mapToDouble(e -> e.timestamp) 754 .toArray(); 755 756 if (times.length == 0) { 757 eventNotFound.addCause("collectEvents(" + eventName + ")"); 758 } 759 760 return times; 761 } 762 763 /** 764 * Returns an array of all the poses of the events with the given name. 765 * 766 * <p>The returned poses are always unflipped. If you use them in a trigger like `atPose` or 767 * `atTranslation`, the library will automatically flip them if necessary. If you intend using 768 * them in a different context, you can use {@link ChoreoAllianceFlipUtil#flip} to flip them. 769 * 770 * @param eventName The name of the event. 771 * @return An array of all the poses of the events with the given name. 772 * @see <a href="https://choreo.autos/usage/editing-paths/#event-markers">Event Markers in the 773 * GUI</a> 774 */ 775 public Pose2d[] collectEventPoses(String eventName) { 776 double[] times = collectEventTimes(eventName); 777 Pose2d[] poses = new Pose2d[times.length]; 778 for (int i = 0; i < times.length; i++) { 779 Pose2d pose = 780 trajectory 781 .sampleAt(times[i], false) 782 .map(TrajectorySample::getPose) 783 .get(); // the event times are guaranteed to be valid 784 poses[i] = pose; 785 } 786 return poses; 787 } 788 789 @Override 790 public boolean equals(Object obj) { 791 return obj instanceof AutoTrajectory traj && name.equals(traj.name); 792 } 793}