001// Copyright (c) FIRST and other WPILib contributors. 002// Open Source Software; you can modify and/or share it under the terms of 003// the WPILib BSD license file in the root directory of this project. 004 005package edu.wpi.first.wpilibj2.command; 006 007import static edu.wpi.first.math.trajectory.TrapezoidProfile.State; 008import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; 009 010import edu.wpi.first.math.trajectory.TrapezoidProfile; 011import edu.wpi.first.wpilibj.Timer; 012import java.util.function.Consumer; 013 014/** 015 * A command that runs a {@link TrapezoidProfile}. Useful for smoothly controlling mechanism motion. 016 */ 017public class TrapezoidProfileCommand extends CommandBase { 018 private final TrapezoidProfile m_profile; 019 private final Consumer<State> m_output; 020 021 private final Timer m_timer = new Timer(); 022 023 /** 024 * Creates a new TrapezoidProfileCommand that will execute the given {@link TrapezoidProfile}. 025 * Output will be piped to the provided consumer function. 026 * 027 * @param profile The motion profile to execute. 028 * @param output The consumer for the profile output. 029 * @param requirements The subsystems required by this command. 030 */ 031 public TrapezoidProfileCommand( 032 TrapezoidProfile profile, Consumer<State> output, Subsystem... requirements) { 033 m_profile = requireNonNullParam(profile, "profile", "TrapezoidProfileCommand"); 034 m_output = requireNonNullParam(output, "output", "TrapezoidProfileCommand"); 035 addRequirements(requirements); 036 } 037 038 @Override 039 public void initialize() { 040 m_timer.reset(); 041 m_timer.start(); 042 } 043 044 @Override 045 public void execute() { 046 m_output.accept(m_profile.calculate(m_timer.get())); 047 } 048 049 @Override 050 public void end(boolean interrupted) { 051 m_timer.stop(); 052 } 053 054 @Override 055 public boolean isFinished() { 056 return m_timer.hasElapsed(m_profile.totalTime()); 057 } 058}