Files
allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileCommand.h

83 lines
2.5 KiB
C
Raw Normal View History

// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
2019-10-26 12:58:13 -04:00
#pragma once
2019-10-26 12:58:13 -04:00
#include <functional>
#include <initializer_list>
2019-10-26 12:58:13 -04:00
#include <frc/Timer.h>
#include <frc/trajectory/TrapezoidProfile.h>
#include <wpi/ArrayRef.h>
2019-10-26 12:58:13 -04:00
#include "frc2/command/CommandBase.h"
#include "frc2/command/CommandHelper.h"
2019-10-26 12:58:13 -04:00
namespace frc2 {
/**
* A command that runs a TrapezoidProfile. Useful for smoothly controlling
* mechanism motion.
*
* @see TrapezoidProfile
*/
template <class Distance>
2019-10-26 12:58:13 -04:00
class TrapezoidProfileCommand
: public CommandHelper<CommandBase, TrapezoidProfileCommand<Distance>> {
using Distance_t = units::unit_t<Distance>;
using Velocity =
units::compound_unit<Distance, units::inverse<units::seconds>>;
using Velocity_t = units::unit_t<Velocity>;
using State = typename frc::TrapezoidProfile<Distance>::State;
2019-10-26 12:58:13 -04:00
public:
/**
* Creates a new TrapezoidProfileCommand that will execute the given
* TrapezoidalProfile. Output will be piped to the provided consumer function.
*
* @param profile The motion profile to execute.
* @param output The consumer for the profile output.
*/
TrapezoidProfileCommand(frc::TrapezoidProfile<Distance> profile,
std::function<void(State)> output,
std::initializer_list<Subsystem*> requirements)
: m_profile(profile), m_output(output) {
this->AddRequirements(requirements);
}
/**
* Creates a new TrapezoidProfileCommand that will execute the given
* TrapezoidalProfile. Output will be piped to the provided consumer function.
*
* @param profile The motion profile to execute.
* @param output The consumer for the profile output.
*/
TrapezoidProfileCommand(frc::TrapezoidProfile<Distance> profile,
std::function<void(State)> output,
wpi::ArrayRef<Subsystem*> requirements = {})
: m_profile(profile), m_output(output) {
this->AddRequirements(requirements);
}
2019-10-26 12:58:13 -04:00
void Initialize() override {
m_timer.Reset();
m_timer.Start();
}
2019-10-26 12:58:13 -04:00
void Execute() override { m_output(m_profile.Calculate(m_timer.Get())); }
2019-10-26 12:58:13 -04:00
void End(bool interrupted) override { m_timer.Stop(); }
2019-10-26 12:58:13 -04:00
bool IsFinished() override {
return m_timer.HasElapsed(m_profile.TotalTime());
}
2019-10-26 12:58:13 -04:00
private:
frc::TrapezoidProfile<Distance> m_profile;
std::function<void(State)> m_output;
2019-10-26 12:58:13 -04:00
frc::Timer m_timer;
2019-10-26 12:58:13 -04:00
};
} // namespace frc2