mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[wpimath] Refactor TrapezoidProfile API (#5457)
This commit is contained in:
@@ -39,13 +39,44 @@ class TrapezoidProfileCommand
|
||||
*
|
||||
* @param profile The motion profile to execute.
|
||||
* @param output The consumer for the profile output.
|
||||
* @param goal The supplier for the desired state
|
||||
* @param currentState The current state
|
||||
* @param requirements The list of requirements.
|
||||
*/
|
||||
TrapezoidProfileCommand(frc::TrapezoidProfile<Distance> profile,
|
||||
std::function<void(State)> output,
|
||||
std::function<State()> goal,
|
||||
std::function<State()> currentState,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: m_profile(profile), m_output(output) {
|
||||
: m_profile(profile),
|
||||
m_output(output),
|
||||
m_goal(goal),
|
||||
m_currentState(currentState) {
|
||||
this->AddRequirements(requirements);
|
||||
m_newAPI = true;
|
||||
}
|
||||
|
||||
/**
|
||||
* 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.
|
||||
* @param goal The supplier for the desired state
|
||||
* @param currentState The current state
|
||||
* @param requirements The list of requirements.
|
||||
*/
|
||||
TrapezoidProfileCommand(frc::TrapezoidProfile<Distance> profile,
|
||||
std::function<void(State)> output,
|
||||
std::function<State()> goal,
|
||||
std::function<State()> currentState,
|
||||
std::span<Subsystem* const> requirements = {})
|
||||
: m_profile(profile),
|
||||
m_output(output),
|
||||
m_goal(goal),
|
||||
m_currentState(currentState) {
|
||||
this->AddRequirements(requirements);
|
||||
m_newAPI = true;
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -55,17 +86,46 @@ class TrapezoidProfileCommand
|
||||
* @param profile The motion profile to execute.
|
||||
* @param output The consumer for the profile output.
|
||||
* @param requirements The list of requirements.
|
||||
* @deprecated The new constructor allows you to pass in a supplier for
|
||||
* desired and current state. This allows you to change goals at runtime.
|
||||
*/
|
||||
WPI_DEPRECATED(
|
||||
"The new constructor allows you to pass in a supplier for desired and "
|
||||
"current state. This allows you to change goals at runtime.")
|
||||
TrapezoidProfileCommand(frc::TrapezoidProfile<Distance> profile,
|
||||
std::function<void(State)> output,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: m_profile(profile), m_output(output) {
|
||||
this->AddRequirements(requirements);
|
||||
m_newAPI = false;
|
||||
}
|
||||
|
||||
/**
|
||||
* 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.
|
||||
* @param requirements The list of requirements.
|
||||
* @deprecated The new constructor allows you to pass in a supplier for
|
||||
* desired and current state. This allows you to change goals at runtime.
|
||||
*/
|
||||
WPI_DEPRECATED(
|
||||
"The new constructor allows you to pass in a supplier for desired and "
|
||||
"current state. This allows you to change goals at runtime.")
|
||||
TrapezoidProfileCommand(frc::TrapezoidProfile<Distance> profile,
|
||||
std::function<void(State)> output,
|
||||
std::span<Subsystem* const> requirements = {})
|
||||
: m_profile(profile), m_output(output) {
|
||||
this->AddRequirements(requirements);
|
||||
m_newAPI = false;
|
||||
}
|
||||
|
||||
void Initialize() override { m_timer.Restart(); }
|
||||
|
||||
void Execute() override { m_output(m_profile.Calculate(m_timer.Get())); }
|
||||
void Execute() override {
|
||||
m_output(m_profile.Calculate(m_timer.Get(), m_goal(), m_currentState()));
|
||||
}
|
||||
|
||||
void End(bool interrupted) override { m_timer.Stop(); }
|
||||
|
||||
@@ -76,7 +136,9 @@ class TrapezoidProfileCommand
|
||||
private:
|
||||
frc::TrapezoidProfile<Distance> m_profile;
|
||||
std::function<void(State)> m_output;
|
||||
|
||||
std::function<State()> m_goal;
|
||||
std::function<State()> m_currentState;
|
||||
bool m_newAPI; // TODO: Remove
|
||||
frc::Timer m_timer;
|
||||
};
|
||||
|
||||
|
||||
Reference in New Issue
Block a user