Compare commits

...

7 Commits

Author SHA1 Message Date
Peter Johnson
32c62449be Add ArrayRef overloads to new command classes (#2216)
Also default requirements to {} in all cases for consistency.
2020-01-01 20:09:17 -08:00
Tyler Veness
6190fcb237 Run wpiformat (#2218) 2020-01-01 20:04:56 -08:00
Declan Freeman-Gleason
012d93b2bd Use an explicit stack instead of recursion when parameterizing splines (#2197)
This PR changes the spline parameterizer to use an explicit stack instead of recursion. This is motivated by the fact that splines with adjacent waypoints with approximately opposite headings will never parameterize. In this case the parameterizer subdivides these malformed splines fine for a while, and then gets stuck parameterizing infinitely on some interval. In the recursive approach, this would lead to a stack overflow. We could implement a recursion depth counter (this is what my team did on our similar trajectory code last season), but it's hard to choose a good number for max depth because the initial amount of stack used varies based on how the user calls Parameterize.

A good solution for this is converting the recursion to an "explicit stack," which basically simulates recursion, but allows us to have a much larger maximum stack size. Because we avoid the stack overflow, we can instead throws a more informative MalformedSplineException. If the user is using the TrajectoryGenerator instead of the SplineParameterizer directly then the TrajectoryGenerator will go ahead and catch the exception, return a harmless empty trajectory, and report and error to the driver station.
2020-01-01 18:23:08 -08:00
Matt
222669dc2c Fix trapezoidal profile PID controller setpoint bug (#2210)
Co-Authored-By: Austin Shalit <austinshalit@gmail.com>
2020-01-01 15:23:25 -08:00
Peter Johnson
abe25b795b TrajectoryUtil.toPathweaverJson: Create parent directories (#2214) 2020-01-01 13:35:04 -08:00
sciencewhiz
354185189c Update ProjectYear to 2020 (#2212) 2020-01-01 11:14:31 -08:00
sciencewhiz
f14fe434a1 Add (Old) qualifier to old subsystem (#2211) 2019-12-31 23:00:35 -06:00
51 changed files with 1164 additions and 170 deletions

View File

@@ -1,6 +1,6 @@
{
"enableCppIntellisense": true,
"currentLanguage": "cpp",
"projectYear": "Beta2020-2",
"projectYear": "2020",
"teamNumber": 0
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -113,7 +113,7 @@ public class ProfiledPIDCommand extends CommandBase {
@Override
public void initialize() {
m_controller.reset();
m_controller.reset(m_measurement.getAsDouble());
}
@Override

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -93,7 +93,7 @@ public abstract class ProfiledPIDSubsystem extends SubsystemBase {
*/
public void enable() {
m_enabled = true;
m_controller.reset();
m_controller.reset(getMeasurement());
}
/**

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -51,6 +51,13 @@ ParallelRaceGroup Command::WithInterrupt(std::function<bool()> condition) && {
SequentialCommandGroup Command::BeforeStarting(
std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements) && {
return std::move(*this).BeforeStarting(
std::move(toRun),
wpi::makeArrayRef(requirements.begin(), requirements.end()));
}
SequentialCommandGroup Command::BeforeStarting(
std::function<void()> toRun, wpi::ArrayRef<Subsystem*> requirements) && {
std::vector<std::unique_ptr<Command>> temp;
temp.emplace_back(
std::make_unique<InstantCommand>(std::move(toRun), requirements));
@@ -61,6 +68,13 @@ SequentialCommandGroup Command::BeforeStarting(
SequentialCommandGroup Command::AndThen(
std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements) && {
return std::move(*this).AndThen(
std::move(toRun),
wpi::makeArrayRef(requirements.begin(), requirements.end()));
}
SequentialCommandGroup Command::AndThen(
std::function<void()> toRun, wpi::ArrayRef<Subsystem*> requirements) && {
std::vector<std::unique_ptr<Command>> temp;
temp.emplace_back(std::move(*this).TransferOwnership());
temp.emplace_back(

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -21,6 +21,10 @@ void CommandBase::AddRequirements(
m_requirements.insert(requirements.begin(), requirements.end());
}
void CommandBase::AddRequirements(wpi::ArrayRef<Subsystem*> requirements) {
m_requirements.insert(requirements.begin(), requirements.end());
}
void CommandBase::AddRequirements(wpi::SmallSet<Subsystem*, 4> requirements) {
m_requirements.insert(requirements.begin(), requirements.end());
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -248,6 +248,12 @@ void CommandScheduler::RegisterSubsystem(
}
}
void CommandScheduler::RegisterSubsystem(wpi::ArrayRef<Subsystem*> subsystems) {
for (auto* subsystem : subsystems) {
RegisterSubsystem(subsystem);
}
}
void CommandScheduler::UnregisterSubsystem(
std::initializer_list<Subsystem*> subsystems) {
for (auto* subsystem : subsystems) {
@@ -255,6 +261,13 @@ void CommandScheduler::UnregisterSubsystem(
}
}
void CommandScheduler::UnregisterSubsystem(
wpi::ArrayRef<Subsystem*> subsystems) {
for (auto* subsystem : subsystems) {
UnregisterSubsystem(subsystem);
}
}
Command* CommandScheduler::GetDefaultCommand(const Subsystem* subsystem) const {
auto&& find = m_impl->subsystems.find(subsystem);
if (find != m_impl->subsystems.end()) {

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -20,6 +20,18 @@ FunctionalCommand::FunctionalCommand(
AddRequirements(requirements);
}
FunctionalCommand::FunctionalCommand(std::function<void()> onInit,
std::function<void()> onExecute,
std::function<void(bool)> onEnd,
std::function<bool()> isFinished,
wpi::ArrayRef<Subsystem*> requirements)
: m_onInit{std::move(onInit)},
m_onExecute{std::move(onExecute)},
m_onEnd{std::move(onEnd)},
m_isFinished{std::move(isFinished)} {
AddRequirements(requirements);
}
void FunctionalCommand::Initialize() { m_onInit(); }
void FunctionalCommand::Execute() { m_onExecute(); }

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -15,6 +15,12 @@ InstantCommand::InstantCommand(std::function<void()> toRun,
AddRequirements(requirements);
}
InstantCommand::InstantCommand(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements)
: m_toRun{std::move(toRun)} {
AddRequirements(requirements);
}
InstantCommand::InstantCommand() : m_toRun{[] {}} {}
void InstantCommand::Initialize() { m_toRun(); }

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -50,6 +50,46 @@ MecanumControllerCommand::MecanumControllerCommand(
AddRequirements(requirements);
}
MecanumControllerCommand::MecanumControllerCommand(
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
frc::SimpleMotorFeedforward<units::meters> feedforward,
frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
frc2::PIDController yController,
frc::ProfiledPIDController<units::radians> thetaController,
units::meters_per_second_t maxWheelVelocity,
std::function<frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds,
frc2::PIDController frontLeftController,
frc2::PIDController rearLeftController,
frc2::PIDController frontRightController,
frc2::PIDController rearRightController,
std::function<void(units::volt_t, units::volt_t, units::volt_t,
units::volt_t)>
output,
wpi::ArrayRef<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
m_feedforward(feedforward),
m_kinematics(kinematics),
m_xController(std::make_unique<frc2::PIDController>(xController)),
m_yController(std::make_unique<frc2::PIDController>(yController)),
m_thetaController(
std::make_unique<frc::ProfiledPIDController<units::radians>>(
thetaController)),
m_maxWheelVelocity(maxWheelVelocity),
m_frontLeftController(
std::make_unique<frc2::PIDController>(frontLeftController)),
m_rearLeftController(
std::make_unique<frc2::PIDController>(rearLeftController)),
m_frontRightController(
std::make_unique<frc2::PIDController>(frontRightController)),
m_rearRightController(
std::make_unique<frc2::PIDController>(rearRightController)),
m_currentWheelSpeeds(currentWheelSpeeds),
m_outputVolts(output),
m_usePID(true) {
AddRequirements(requirements);
}
MecanumControllerCommand::MecanumControllerCommand(
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
@@ -74,6 +114,30 @@ MecanumControllerCommand::MecanumControllerCommand(
AddRequirements(requirements);
}
MecanumControllerCommand::MecanumControllerCommand(
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
frc2::PIDController yController,
frc::ProfiledPIDController<units::radians> thetaController,
units::meters_per_second_t maxWheelVelocity,
std::function<void(units::meters_per_second_t, units::meters_per_second_t,
units::meters_per_second_t, units::meters_per_second_t)>
output,
wpi::ArrayRef<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
m_kinematics(kinematics),
m_xController(std::make_unique<frc2::PIDController>(xController)),
m_yController(std::make_unique<frc2::PIDController>(yController)),
m_thetaController(
std::make_unique<frc::ProfiledPIDController<units::radians>>(
thetaController)),
m_maxWheelVelocity(maxWheelVelocity),
m_outputVel(output),
m_usePID(false) {
AddRequirements(requirements);
}
void MecanumControllerCommand::Initialize() {
m_prevTime = 0_s;
auto initialState = m_trajectory.Sample(0_s);

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -16,6 +16,13 @@ NotifierCommand::NotifierCommand(std::function<void()> toRun,
AddRequirements(requirements);
}
NotifierCommand::NotifierCommand(std::function<void()> toRun,
units::second_t period,
wpi::ArrayRef<Subsystem*> requirements)
: m_toRun(toRun), m_notifier{std::move(toRun)}, m_period{period} {
AddRequirements(requirements);
}
NotifierCommand::NotifierCommand(NotifierCommand&& other)
: CommandHelper(std::move(other)),
m_toRun(other.m_toRun),

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -21,6 +21,18 @@ PIDCommand::PIDCommand(PIDController controller,
AddRequirements(requirements);
}
PIDCommand::PIDCommand(PIDController controller,
std::function<double()> measurementSource,
std::function<double()> setpointSource,
std::function<void(double)> useOutput,
wpi::ArrayRef<Subsystem*> requirements)
: m_controller{controller},
m_measurement{std::move(measurementSource)},
m_setpoint{std::move(setpointSource)},
m_useOutput{std::move(useOutput)} {
AddRequirements(requirements);
}
PIDCommand::PIDCommand(PIDController controller,
std::function<double()> measurementSource,
double setpoint, std::function<void(double)> useOutput,
@@ -28,6 +40,13 @@ PIDCommand::PIDCommand(PIDController controller,
: PIDCommand(controller, measurementSource, [setpoint] { return setpoint; },
useOutput, requirements) {}
PIDCommand::PIDCommand(PIDController controller,
std::function<double()> measurementSource,
double setpoint, std::function<void(double)> useOutput,
wpi::ArrayRef<Subsystem*> requirements)
: PIDCommand(controller, measurementSource, [setpoint] { return setpoint; },
useOutput, requirements) {}
void PIDCommand::Initialize() { m_controller.Reset(); }
void PIDCommand::Execute() {

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -32,6 +32,28 @@ RamseteCommand::RamseteCommand(
AddRequirements(requirements);
}
RamseteCommand::RamseteCommand(
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
frc::RamseteController controller,
frc::SimpleMotorFeedforward<units::meters> feedforward,
frc::DifferentialDriveKinematics kinematics,
std::function<frc::DifferentialDriveWheelSpeeds()> wheelSpeeds,
frc2::PIDController leftController, frc2::PIDController rightController,
std::function<void(volt_t, volt_t)> output,
wpi::ArrayRef<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
m_controller(controller),
m_feedforward(feedforward),
m_kinematics(kinematics),
m_speeds(wheelSpeeds),
m_leftController(std::make_unique<frc2::PIDController>(leftController)),
m_rightController(std::make_unique<frc2::PIDController>(rightController)),
m_outputVolts(output),
m_usePID(true) {
AddRequirements(requirements);
}
RamseteCommand::RamseteCommand(
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
frc::RamseteController controller,
@@ -48,6 +70,22 @@ RamseteCommand::RamseteCommand(
AddRequirements(requirements);
}
RamseteCommand::RamseteCommand(
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
frc::RamseteController controller,
frc::DifferentialDriveKinematics kinematics,
std::function<void(units::meters_per_second_t, units::meters_per_second_t)>
output,
wpi::ArrayRef<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
m_controller(controller),
m_kinematics(kinematics),
m_outputVel(output),
m_usePID(false) {
AddRequirements(requirements);
}
void RamseteCommand::Initialize() {
m_prevTime = 0_s;
auto initialState = m_trajectory.Sample(0_s);

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -15,4 +15,10 @@ RunCommand::RunCommand(std::function<void()> toRun,
AddRequirements(requirements);
}
RunCommand::RunCommand(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements)
: m_toRun{std::move(toRun)} {
AddRequirements(requirements);
}
void RunCommand::Execute() { m_toRun(); }

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -16,6 +16,13 @@ StartEndCommand::StartEndCommand(std::function<void()> onInit,
AddRequirements(requirements);
}
StartEndCommand::StartEndCommand(std::function<void()> onInit,
std::function<void()> onEnd,
wpi::ArrayRef<Subsystem*> requirements)
: m_onInit{std::move(onInit)}, m_onEnd{std::move(onEnd)} {
AddRequirements(requirements);
}
StartEndCommand::StartEndCommand(const StartEndCommand& other)
: CommandHelper(other) {
m_onInit = other.m_onInit;

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -22,6 +22,12 @@ Button Button::WhenPressed(std::function<void()> toRun,
return *this;
}
Button Button::WhenPressed(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements) {
WhenActive(std::move(toRun), requirements);
return *this;
}
Button Button::WhileHeld(Command* command, bool interruptible) {
WhileActiveContinous(command, interruptible);
return *this;
@@ -33,6 +39,12 @@ Button Button::WhileHeld(std::function<void()> toRun,
return *this;
}
Button Button::WhileHeld(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements) {
WhileActiveContinous(std::move(toRun), requirements);
return *this;
}
Button Button::WhenHeld(Command* command, bool interruptible) {
WhileActiveOnce(command, interruptible);
return *this;
@@ -49,6 +61,12 @@ Button Button::WhenReleased(std::function<void()> toRun,
return *this;
}
Button Button::WhenReleased(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements) {
WhenInactive(std::move(toRun), requirements);
return *this;
}
Button Button::ToggleWhenPressed(Command* command, bool interruptible) {
ToggleWhenActive(command, interruptible);
return *this;

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -30,6 +30,12 @@ Trigger Trigger::WhenActive(Command* command, bool interruptible) {
Trigger Trigger::WhenActive(std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements) {
return WhenActive(std::move(toRun), wpi::makeArrayRef(requirements.begin(),
requirements.end()));
}
Trigger Trigger::WhenActive(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements) {
return WhenActive(InstantCommand(std::move(toRun), requirements));
}
@@ -52,6 +58,13 @@ Trigger Trigger::WhileActiveContinous(Command* command, bool interruptible) {
Trigger Trigger::WhileActiveContinous(
std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements) {
return WhileActiveContinous(
std::move(toRun),
wpi::makeArrayRef(requirements.begin(), requirements.end()));
}
Trigger Trigger::WhileActiveContinous(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements) {
return WhileActiveContinous(InstantCommand(std::move(toRun), requirements));
}
@@ -87,6 +100,12 @@ Trigger Trigger::WhenInactive(Command* command, bool interruptible) {
Trigger Trigger::WhenInactive(std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements) {
return WhenInactive(std::move(toRun), wpi::makeArrayRef(requirements.begin(),
requirements.end()));
}
Trigger Trigger::WhenInactive(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements) {
return WhenInactive(InstantCommand(std::move(toRun), requirements));
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -8,6 +8,7 @@
#pragma once
#include <functional>
#include <initializer_list>
#include <memory>
#include <string>
@@ -132,7 +133,18 @@ class Command : public frc::ErrorBase {
*/
SequentialCommandGroup BeforeStarting(
std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements = {}) &&;
std::initializer_list<Subsystem*> requirements) &&;
/**
* Decorates this command with a runnable to run before this command starts.
*
* @param toRun the Runnable to run
* @param requirements the required subsystems
* @return the decorated command
*/
SequentialCommandGroup BeforeStarting(
std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements = {}) &&;
/**
* Decorates this command with a runnable to run after the command finishes.
@@ -143,7 +155,18 @@ class Command : public frc::ErrorBase {
*/
SequentialCommandGroup AndThen(
std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements = {}) &&;
std::initializer_list<Subsystem*> requirements) &&;
/**
* Decorates this command with a runnable to run after the command finishes.
*
* @param toRun the Runnable to run
* @param requirements the required subsystems
* @return the decorated command
*/
SequentialCommandGroup AndThen(
std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements = {}) &&;
/**
* Decorates this command to run perpetually, ignoring its ordinary end

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -12,6 +12,7 @@
#include <frc/smartdashboard/Sendable.h>
#include <frc/smartdashboard/SendableHelper.h>
#include <wpi/ArrayRef.h>
#include <wpi/SmallSet.h>
#include <wpi/Twine.h>
@@ -32,6 +33,13 @@ class CommandBase : public Command,
*/
void AddRequirements(std::initializer_list<Subsystem*> requirements);
/**
* Adds the specified requirements to the command.
*
* @param requirements the requirements to add
*/
void AddRequirements(wpi::ArrayRef<Subsystem*> requirements);
void AddRequirements(wpi::SmallSet<Subsystem*, 4> requirements);
wpi::SmallSet<Subsystem*, 4> GetRequirements() const override;

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -157,8 +157,10 @@ class CommandScheduler final : public frc::Sendable,
void UnregisterSubsystem(Subsystem* subsystem);
void RegisterSubsystem(std::initializer_list<Subsystem*> subsystems);
void RegisterSubsystem(wpi::ArrayRef<Subsystem*> subsystems);
void UnregisterSubsystem(std::initializer_list<Subsystem*> subsystems);
void UnregisterSubsystem(wpi::ArrayRef<Subsystem*> subsystems);
/**
* Sets the default command for a subsystem. Registers that subsystem if it

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -8,6 +8,9 @@
#pragma once
#include <functional>
#include <initializer_list>
#include <wpi/ArrayRef.h>
#include "frc2/command/CommandBase.h"
#include "frc2/command/CommandHelper.h"
@@ -36,7 +39,23 @@ class FunctionalCommand : public CommandHelper<CommandBase, FunctionalCommand> {
std::function<void()> onExecute,
std::function<void(bool)> onEnd,
std::function<bool()> isFinished,
std::initializer_list<Subsystem*> requirements = {});
std::initializer_list<Subsystem*> requirements);
/**
* Creates a new FunctionalCommand.
*
* @param onInit the function to run on command initialization
* @param onExecute the function to run on command execution
* @param onEnd the function to run on command end
* @param isFinished the function that determines whether the command has
* finished
* @param requirements the subsystems required by this command
*/
FunctionalCommand(std::function<void()> onInit,
std::function<void()> onExecute,
std::function<void(bool)> onEnd,
std::function<bool()> isFinished,
wpi::ArrayRef<Subsystem*> requirements = {});
FunctionalCommand(FunctionalCommand&& other) = default;

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -10,6 +10,8 @@
#include <functional>
#include <initializer_list>
#include <wpi/ArrayRef.h>
#include "frc2/command/CommandBase.h"
#include "frc2/command/CommandHelper.h"
@@ -29,7 +31,17 @@ class InstantCommand : public CommandHelper<CommandBase, InstantCommand> {
* @param requirements the subsystems required by this command
*/
InstantCommand(std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements = {});
std::initializer_list<Subsystem*> requirements);
/**
* Creates a new InstantCommand that runs the given Runnable with the given
* requirements.
*
* @param toRun the Runnable to run
* @param requirements the subsystems required by this command
*/
InstantCommand(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements = {});
InstantCommand(InstantCommand&& other) = default;

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -7,6 +7,7 @@
#include <cmath>
#include <functional>
#include <initializer_list>
#include <memory>
#include <frc/controller/PIDController.h>
@@ -18,6 +19,7 @@
#include <frc/kinematics/MecanumDriveWheelSpeeds.h>
#include <frc/trajectory/Trajectory.h>
#include <units/units.h>
#include <wpi/ArrayRef.h>
#include "CommandBase.h"
#include "CommandHelper.h"
@@ -99,6 +101,57 @@ class MecanumControllerCommand
output,
std::initializer_list<Subsystem*> requirements);
/**
* Constructs a new MecanumControllerCommand that when executed will follow
* the provided trajectory. PID control and feedforward are handled
* internally. Outputs are scaled from -12 to 12 as a voltage output to the
* motor.
*
* <p>Note: The controllers will *not* set the outputVolts to zero upon
* completion of the path this is left to the user, since it is not
* appropriate for paths with nonstationary endstates.
*
* <p>Note 2: The rotation controller will calculate the rotation based on the
* final pose in the trajectory, not the poses at each time step.
*
* @param trajectory The trajectory to follow.
* @param pose A function that supplies the robot pose,
* provided by the odometry class.
* @param feedforward The feedforward to use for the drivetrain.
* @param kinematics The kinematics for the robot drivetrain.
* @param xController The Trajectory Tracker PID controller
* for the robot's x position.
* @param yController The Trajectory Tracker PID controller
* for the robot's y position.
* @param thetaController The Trajectory Tracker PID controller
* for angle for the robot.
* @param maxWheelVelocity The maximum velocity of a drivetrain wheel.
* @param frontLeftController The front left wheel velocity PID.
* @param rearLeftController The rear left wheel velocity PID.
* @param frontRightController The front right wheel velocity PID.
* @param rearRightController The rear right wheel velocity PID.
* @param currentWheelSpeeds A MecanumDriveWheelSpeeds object containing
* the current wheel speeds.
* @param output The output of the velocity PIDs.
* @param requirements The subsystems to require.
*/
MecanumControllerCommand(
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
frc::SimpleMotorFeedforward<units::meters> feedforward,
frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
frc2::PIDController yController,
frc::ProfiledPIDController<units::radians> thetaController,
units::meters_per_second_t maxWheelVelocity,
std::function<frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds,
frc2::PIDController frontLeftController,
frc2::PIDController rearLeftController,
frc2::PIDController frontRightController,
frc2::PIDController rearRightController,
std::function<void(units::volt_t, units::volt_t, units::volt_t,
units::volt_t)>
output,
wpi::ArrayRef<Subsystem*> requirements = {});
/**
* Constructs a new MecanumControllerCommand that when executed will follow
* the provided trajectory. The user should implement a velocity PID on the
@@ -137,6 +190,44 @@ class MecanumControllerCommand
output,
std::initializer_list<Subsystem*> requirements);
/**
* Constructs a new MecanumControllerCommand that when executed will follow
* the provided trajectory. The user should implement a velocity PID on the
* desired output wheel velocities.
*
* <p>Note: The controllers will *not* set the outputVolts to zero upon
* completion of the path - this is left to the user, since it is not
* appropriate for paths with non-stationary end-states.
*
* <p>Note2: The rotation controller will calculate the rotation based on the
* final pose in the trajectory, not the poses at each time step.
*
* @param trajectory The trajectory to follow.
* @param pose A function that supplies the robot pose - use one
* of the odometry classes to provide this.
* @param kinematics The kinematics for the robot drivetrain.
* @param xController The Trajectory Tracker PID controller
* for the robot's x position.
* @param yController The Trajectory Tracker PID controller
* for the robot's y position.
* @param thetaController The Trajectory Tracker PID controller
* for angle for the robot.
* @param maxWheelVelocity The maximum velocity of a drivetrain wheel.
* @param output The output of the position PIDs.
* @param requirements The subsystems to require.
*/
MecanumControllerCommand(
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
frc2::PIDController yController,
frc::ProfiledPIDController<units::radians> thetaController,
units::meters_per_second_t maxWheelVelocity,
std::function<void(units::meters_per_second_t, units::meters_per_second_t,
units::meters_per_second_t,
units::meters_per_second_t)>
output,
wpi::ArrayRef<Subsystem*> requirements = {});
void Initialize() override;
void Execute() override;

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -12,6 +12,7 @@
#include <frc/Notifier.h>
#include <units/units.h>
#include <wpi/ArrayRef.h>
#include "frc2/command/CommandBase.h"
#include "frc2/command/CommandHelper.h"
@@ -37,7 +38,17 @@ class NotifierCommand : public CommandHelper<CommandBase, NotifierCommand> {
* @param requirements the subsystems required by this command
*/
NotifierCommand(std::function<void()> toRun, units::second_t period,
std::initializer_list<Subsystem*> requirements = {});
std::initializer_list<Subsystem*> requirements);
/**
* Creates a new NotifierCommand.
*
* @param toRun the runnable for the notifier to run
* @param period the period at which the notifier should run
* @param requirements the subsystems required by this command
*/
NotifierCommand(std::function<void()> toRun, units::second_t period,
wpi::ArrayRef<Subsystem*> requirements = {});
NotifierCommand(NotifierCommand&& other);

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -40,7 +40,23 @@ class PIDCommand : public CommandHelper<CommandBase, PIDCommand> {
std::function<double()> measurementSource,
std::function<double()> setpointSource,
std::function<void(double)> useOutput,
std::initializer_list<Subsystem*> requirements = {});
std::initializer_list<Subsystem*> requirements);
/**
* Creates a new PIDCommand, which controls the given output with a
* PIDController.
*
* @param controller the controller that controls the output.
* @param measurementSource the measurement of the process variable
* @param setpointSource the controller's reference (aka setpoint)
* @param useOutput the controller's output
* @param requirements the subsystems required by this command
*/
PIDCommand(PIDController controller,
std::function<double()> measurementSource,
std::function<double()> setpointSource,
std::function<void(double)> useOutput,
wpi::ArrayRef<Subsystem*> requirements = {});
/**
* Creates a new PIDCommand, which controls the given output with a
@@ -57,6 +73,21 @@ class PIDCommand : public CommandHelper<CommandBase, PIDCommand> {
std::function<void(double)> useOutput,
std::initializer_list<Subsystem*> requirements);
/**
* Creates a new PIDCommand, which controls the given output with a
* PIDController with a constant setpoint.
*
* @param controller the controller that controls the output.
* @param measurementSource the measurement of the process variable
* @param setpoint the controller's setpoint (aka setpoint)
* @param useOutput the controller's output
* @param requirements the subsystems required by this command
*/
PIDCommand(PIDController controller,
std::function<double()> measurementSource, double setpoint,
std::function<void(double)> useOutput,
wpi::ArrayRef<Subsystem*> requirements = {});
PIDCommand(PIDCommand&& other) = default;
PIDCommand(const PIDCommand& other) = default;

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -13,6 +13,7 @@
#include <frc/controller/ProfiledPIDController.h>
#include <units/units.h>
#include <wpi/ArrayRef.h>
#include "frc2/command/CommandBase.h"
#include "frc2/command/CommandHelper.h"
@@ -50,7 +51,29 @@ class ProfiledPIDCommand
std::function<Distance_t()> measurementSource,
std::function<State()> goalSource,
std::function<void(double, State)> useOutput,
std::initializer_list<Subsystem*> requirements = {})
std::initializer_list<Subsystem*> requirements)
: m_controller{controller},
m_measurement{std::move(measurementSource)},
m_goal{std::move(goalSource)},
m_useOutput{std::move(useOutput)} {
this->AddRequirements(requirements);
}
/**
* Creates a new PIDCommand, which controls the given output with a
* ProfiledPIDController.
*
* @param controller the controller that controls the output.
* @param measurementSource the measurement of the process variable
* @param goalSource the controller's goal
* @param useOutput the controller's output
* @param requirements the subsystems required by this command
*/
ProfiledPIDCommand(frc::ProfiledPIDController<Distance> controller,
std::function<Distance_t()> measurementSource,
std::function<State()> goalSource,
std::function<void(double, State)> useOutput,
wpi::ArrayRef<Subsystem*> requirements = {})
: m_controller{controller},
m_measurement{std::move(measurementSource)},
m_goal{std::move(goalSource)},
@@ -79,6 +102,27 @@ class ProfiledPIDCommand
},
useOutput, requirements) {}
/**
* Creates a new PIDCommand, which controls the given output with a
* ProfiledPIDController.
*
* @param controller the controller that controls the output.
* @param measurementSource the measurement of the process variable
* @param goalSource the controller's goal
* @param useOutput the controller's output
* @param requirements the subsystems required by this command
*/
ProfiledPIDCommand(frc::ProfiledPIDController<Distance> controller,
std::function<Distance_t()> measurementSource,
std::function<Distance_t()> goalSource,
std::function<void(double, State)> useOutput,
wpi::ArrayRef<Subsystem*> requirements = {})
: ProfiledPIDCommand(controller, measurementSource,
[&goalSource]() {
return State{goalSource(), Velocity_t{0}};
},
useOutput, requirements) {}
/**
* Creates a new PIDCommand, which controls the given output with a
* ProfiledPIDController with a constant goal.
@@ -96,6 +140,23 @@ class ProfiledPIDCommand
: ProfiledPIDCommand(controller, measurementSource,
[goal] { return goal; }, useOutput, requirements) {}
/**
* Creates a new PIDCommand, which controls the given output with a
* ProfiledPIDController with a constant goal.
*
* @param controller the controller that controls the output.
* @param measurementSource the measurement of the process variable
* @param goal the controller's goal
* @param useOutput the controller's output
* @param requirements the subsystems required by this command
*/
ProfiledPIDCommand(frc::ProfiledPIDController<Distance> controller,
std::function<Distance_t()> measurementSource, State goal,
std::function<void(double, State)> useOutput,
wpi::ArrayRef<Subsystem*> requirements = {})
: ProfiledPIDCommand(controller, measurementSource,
[goal] { return goal; }, useOutput, requirements) {}
/**
* Creates a new PIDCommand, which controls the given output with a
* ProfiledPIDController with a constant goal.
@@ -114,11 +175,29 @@ class ProfiledPIDCommand
: ProfiledPIDCommand(controller, measurementSource,
[goal] { return goal; }, useOutput, requirements) {}
/**
* Creates a new PIDCommand, which controls the given output with a
* ProfiledPIDController with a constant goal.
*
* @param controller the controller that controls the output.
* @param measurementSource the measurement of the process variable
* @param goal the controller's goal
* @param useOutput the controller's output
* @param requirements the subsystems required by this command
*/
ProfiledPIDCommand(frc::ProfiledPIDController<Distance> controller,
std::function<Distance_t()> measurementSource,
Distance_t goal,
std::function<void(double, State)> useOutput,
wpi::ArrayRef<Subsystem*> requirements = {})
: ProfiledPIDCommand(controller, measurementSource,
[goal] { return goal; }, useOutput, requirements) {}
ProfiledPIDCommand(ProfiledPIDCommand&& other) = default;
ProfiledPIDCommand(const ProfiledPIDCommand& other) = default;
void Initialize() override { m_controller.Reset(); }
void Initialize() override { m_controller.Reset(m_measurement()); }
void Execute() override {
m_useOutput(m_controller.Calculate(m_measurement(), m_goal()),

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -62,10 +62,10 @@ class ProfiledPIDSubsystem : public SubsystemBase {
void SetGoal(Distance_t goal) { m_goal = State{goal, Velocity_t(0)}; }
/**
* Enables the PID control. Resets the controller.
* Enables the PID control. Resets the controller.
*/
virtual void Enable() {
m_controller.Reset();
m_controller.Reset(GetMeasurement());
m_enabled = true;
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -18,6 +18,7 @@
#include <frc/kinematics/DifferentialDriveKinematics.h>
#include <frc/trajectory/Trajectory.h>
#include <units/units.h>
#include <wpi/ArrayRef.h>
#include "frc2/Timer.h"
#include "frc2/command/CommandBase.h"
@@ -78,7 +79,44 @@ class RamseteCommand : public CommandHelper<CommandBase, RamseteCommand> {
frc2::PIDController leftController,
frc2::PIDController rightController,
std::function<void(units::volt_t, units::volt_t)> output,
std::initializer_list<Subsystem*> requirements = {});
std::initializer_list<Subsystem*> requirements);
/**
* Constructs a new RamseteCommand that, when executed, will follow the
* provided trajectory. PID control and feedforward are handled internally,
* and outputs are scaled -12 to 12 representing units of volts.
*
* <p>Note: The controller will *not* set the outputVolts to zero upon
* completion of the path - this is left to the user, since it is not
* appropriate for paths with nonstationary endstates.
*
* @param trajectory The trajectory to follow.
* @param pose A function that supplies the robot pose - use one of
* the odometry classes to provide this.
* @param controller The RAMSETE controller used to follow the
* trajectory.
* @param feedforward A component for calculating the feedforward for the
* drive.
* @param kinematics The kinematics for the robot drivetrain.
* @param wheelSpeeds A function that supplies the speeds of the left
* and right sides of the robot drive.
* @param leftController The PIDController for the left side of the robot
* drive.
* @param rightController The PIDController for the right side of the robot
* drive.
* @param output A function that consumes the computed left and right
* outputs (in volts) for the robot drive.
* @param requirements The subsystems to require.
*/
RamseteCommand(frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
frc::RamseteController controller,
frc::SimpleMotorFeedforward<units::meters> feedforward,
frc::DifferentialDriveKinematics kinematics,
std::function<frc::DifferentialDriveWheelSpeeds()> wheelSpeeds,
frc2::PIDController leftController,
frc2::PIDController rightController,
std::function<void(units::volt_t, units::volt_t)> output,
wpi::ArrayRef<Subsystem*> requirements = {});
/**
* Constructs a new RamseteCommand that, when executed, will follow the
@@ -104,6 +142,30 @@ class RamseteCommand : public CommandHelper<CommandBase, RamseteCommand> {
output,
std::initializer_list<Subsystem*> requirements);
/**
* Constructs a new RamseteCommand that, when executed, will follow the
* provided trajectory. Performs no PID control and calculates no
* feedforwards; outputs are the raw wheel speeds from the RAMSETE controller,
* and will need to be converted into a usable form by the user.
*
* @param trajectory The trajectory to follow.
* @param pose A function that supplies the robot pose - use one of
* the odometry classes to provide this.
* @param controller The RAMSETE controller used to follow the
* trajectory.
* @param kinematics The kinematics for the robot drivetrain.
* @param output A function that consumes the computed left and right
* wheel speeds.
* @param requirements The subsystems to require.
*/
RamseteCommand(frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
frc::RamseteController controller,
frc::DifferentialDriveKinematics kinematics,
std::function<void(units::meters_per_second_t,
units::meters_per_second_t)>
output,
wpi::ArrayRef<Subsystem*> requirements = {});
void Initialize() override;
void Execute() override;

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -10,6 +10,8 @@
#include <functional>
#include <initializer_list>
#include <wpi/ArrayRef.h>
#include "frc2/command/CommandBase.h"
#include "frc2/command/CommandHelper.h"
@@ -30,7 +32,17 @@ class RunCommand : public CommandHelper<CommandBase, RunCommand> {
* @param requirements the subsystems to require
*/
RunCommand(std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements = {});
std::initializer_list<Subsystem*> requirements);
/**
* Creates a new RunCommand. The Runnable will be run continuously until the
* command ends. Does not run when disabled.
*
* @param toRun the Runnable to run
* @param requirements the subsystems to require
*/
RunCommand(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements = {});
RunCommand(RunCommand&& other) = default;

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -10,6 +10,8 @@
#include <functional>
#include <initializer_list>
#include <wpi/ArrayRef.h>
#include "frc2/command/CommandBase.h"
#include "frc2/command/CommandHelper.h"
@@ -32,7 +34,18 @@ class StartEndCommand : public CommandHelper<CommandBase, StartEndCommand> {
* @param requirements the subsystems required by this command
*/
StartEndCommand(std::function<void()> onInit, std::function<void()> onEnd,
std::initializer_list<Subsystem*> requirements = {});
std::initializer_list<Subsystem*> requirements);
/**
* Creates a new StartEndCommand. Will run the given runnables when the
* command starts and when it ends.
*
* @param onInit the Runnable to run on command init
* @param onEnd the Runnable to run on command end
* @param requirements the subsystems required by this command
*/
StartEndCommand(std::function<void()> onInit, std::function<void()> onEnd,
wpi::ArrayRef<Subsystem*> requirements = {});
StartEndCommand(StartEndCommand&& other) = default;

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -7,6 +7,7 @@
#include <cmath>
#include <functional>
#include <initializer_list>
#include <memory>
#include <frc/controller/PIDController.h>
@@ -17,6 +18,7 @@
#include <frc/kinematics/SwerveModuleState.h>
#include <frc/trajectory/Trajectory.h>
#include <units/units.h>
#include <wpi/ArrayRef.h>
#include "CommandBase.h"
#include "CommandHelper.h"
@@ -92,6 +94,42 @@ class SwerveControllerCommand
output,
std::initializer_list<Subsystem*> requirements);
/**
* Constructs a new SwerveControllerCommand that when executed will follow the
* provided trajectory. This command will not return output voltages but
* rather raw module states from the position controllers which need to be put
* into a velocity PID.
*
* <p>Note: The controllers will *not* set the outputVolts to zero upon
* completion of the path- this is left to the user, since it is not
* appropriate for paths with nonstationary endstates.
*
* <p>Note 2: The rotation controller will calculate the rotation based on the
* final pose in the trajectory, not the poses at each time step.
*
* @param trajectory The trajectory to follow.
* @param pose A function that supplies the robot pose,
* provided by the odometry class.
* @param kinematics The kinematics for the robot drivetrain.
* @param xController The Trajectory Tracker PID controller
* for the robot's x position.
* @param yController The Trajectory Tracker PID controller
* for the robot's y position.
* @param thetaController The Trajectory Tracker PID controller
* for angle for the robot.
* @param output The raw output module states from the
* position controllers.
* @param requirements The subsystems to require.
*/
SwerveControllerCommand(
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
frc::SwerveDriveKinematics<NumModules> kinematics,
frc2::PIDController xController, frc2::PIDController yController,
frc::ProfiledPIDController<units::radians> thetaController,
std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
output,
wpi::ArrayRef<Subsystem*> requirements = {});
void Initialize() override;
void Execute() override;

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -31,6 +31,26 @@ SwerveControllerCommand<NumModules>::SwerveControllerCommand(
this->AddRequirements(requirements);
}
template <size_t NumModules>
SwerveControllerCommand<NumModules>::SwerveControllerCommand(
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
frc::SwerveDriveKinematics<NumModules> kinematics,
frc2::PIDController xController, frc2::PIDController yController,
frc::ProfiledPIDController<units::radians> thetaController,
std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
wpi::ArrayRef<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
m_kinematics(kinematics),
m_xController(std::make_unique<frc2::PIDController>(xController)),
m_yController(std::make_unique<frc2::PIDController>(yController)),
m_thetaController(
std::make_unique<frc::ProfiledPIDController<units::radians>>(
thetaController)),
m_outputStates(output) {
this->AddRequirements(requirements);
}
template <size_t NumModules>
void SwerveControllerCommand<NumModules>::Initialize() {
m_finalPose = m_trajectory.Sample(m_trajectory.TotalTime()).pose;

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -11,6 +11,7 @@
#include <initializer_list>
#include <frc/trajectory/TrapezoidProfile.h>
#include <wpi/ArrayRef.h>
#include "frc2/Timer.h"
#include "frc2/command/CommandBase.h"
@@ -42,7 +43,21 @@ class TrapezoidProfileCommand
*/
TrapezoidProfileCommand(frc::TrapezoidProfile<Distance> profile,
std::function<void(State)> output,
std::initializer_list<Subsystem*> requirements = {})
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);
}

View File

@@ -1,13 +1,18 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <functional>
#include <initializer_list>
#include <utility>
#include <wpi/ArrayRef.h>
#include "Trigger.h"
namespace frc2 {
@@ -68,7 +73,16 @@ class Button : public Trigger {
* @param requirements the required subsystems.
*/
Button WhenPressed(std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements = {});
std::initializer_list<Subsystem*> requirements);
/**
* Binds a runnable to execute when the button is pressed.
*
* @param toRun the runnable to execute.
* @param requirements the required subsystems.
*/
Button WhenPressed(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements = {});
/**
* Binds a command to be started repeatedly while the button is pressed, and
@@ -105,7 +119,16 @@ class Button : public Trigger {
* @param requirements the required subsystems.
*/
Button WhileHeld(std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements = {});
std::initializer_list<Subsystem*> requirements);
/**
* Binds a runnable to execute repeatedly while the button is pressed.
*
* @param toRun the runnable to execute.
* @param requirements the required subsystems.
*/
Button WhileHeld(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements = {});
/**
* Binds a command to be started when the button is pressed, and cancelled
@@ -170,7 +193,16 @@ class Button : public Trigger {
* @param requirements the required subsystems.
*/
Button WhenReleased(std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements = {});
std::initializer_list<Subsystem*> requirements);
/**
* Binds a runnable to execute when the button is released.
*
* @param toRun the runnable to execute.
* @param requirements the required subsystems.
*/
Button WhenReleased(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements = {});
/**
* Binds a command to start when the button is pressed, and be cancelled when

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -7,10 +7,13 @@
#pragma once
#include <atomic>
#include <functional>
#include <initializer_list>
#include <memory>
#include <utility>
#include <wpi/ArrayRef.h>
#include "frc2/command/Command.h"
#include "frc2/command/CommandScheduler.h"
@@ -99,7 +102,16 @@ class Trigger {
* @paaram requirements the required subsystems.
*/
Trigger WhenActive(std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements = {});
std::initializer_list<Subsystem*> requirements);
/**
* Binds a runnable to execute when the trigger becomes active.
*
* @param toRun the runnable to execute.
* @paaram requirements the required subsystems.
*/
Trigger WhenActive(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements = {});
/**
* Binds a command to be started repeatedly while the trigger is active, and
@@ -149,9 +161,17 @@ class Trigger {
* @param toRun the runnable to execute.
* @param requirements the required subsystems.
*/
Trigger WhileActiveContinous(
std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements = {});
Trigger WhileActiveContinous(std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements);
/**
* Binds a runnable to execute repeatedly while the trigger is active.
*
* @param toRun the runnable to execute.
* @param requirements the required subsystems.
*/
Trigger WhileActiveContinous(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements = {});
/**
* Binds a command to be started when the trigger becomes active, and
@@ -242,7 +262,16 @@ class Trigger {
* @param requirements the required subsystems.
*/
Trigger WhenInactive(std::function<void()> toRun,
std::initializer_list<Subsystem*> requirements = {});
std::initializer_list<Subsystem*> requirements);
/**
* Binds a runnable to execute when the trigger becomes inactive.
*
* @param toRun the runnable to execute.
* @param requirements the required subsystems.
*/
Trigger WhenInactive(std::function<void()> toRun,
wpi::ArrayRef<Subsystem*> requirements = {});
/**
* Binds a command to start when the trigger becomes active, and be cancelled

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -9,11 +9,16 @@
#include <utility>
#include "frc/DriverStation.h"
#include "frc/spline/SplineHelper.h"
#include "frc/spline/SplineParameterizer.h"
#include "frc/trajectory/TrajectoryParameterizer.h"
using namespace frc;
const Trajectory TrajectoryGenerator::kDoNothingTrajectory(
std::vector<Trajectory::State>{Trajectory::State()});
Trajectory TrajectoryGenerator::GenerateTrajectory(
Spline<3>::ControlVector initial,
const std::vector<Translation2d>& interiorWaypoints,
@@ -29,9 +34,15 @@ Trajectory TrajectoryGenerator::GenerateTrajectory(
end.y[1] *= -1;
}
auto points =
SplinePointsFromSplines(SplineHelper::CubicSplinesFromControlVectors(
initial, interiorWaypoints, end));
std::vector<frc::SplineParameterizer::PoseWithCurvature> points;
try {
points =
SplinePointsFromSplines(SplineHelper::CubicSplinesFromControlVectors(
initial, interiorWaypoints, end));
} catch (SplineParameterizer::MalformedSplineException& e) {
DriverStation::ReportError(e.what());
return kDoNothingTrajectory;
}
// After trajectory generation, flip theta back so it's relative to the
// field. Also fix curvature.
@@ -68,8 +79,14 @@ Trajectory TrajectoryGenerator::GenerateTrajectory(
}
}
auto points = SplinePointsFromSplines(
SplineHelper::QuinticSplinesFromControlVectors(controlVectors));
std::vector<frc::SplineParameterizer::PoseWithCurvature> points;
try {
points = SplinePointsFromSplines(
SplineHelper::QuinticSplinesFromControlVectors(controlVectors));
} catch (SplineParameterizer::MalformedSplineException& e) {
DriverStation::ReportError(e.what());
return kDoNothingTrajectory;
}
// After trajectory generation, flip theta back so it's relative to the
// field. Also fix curvature.

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -46,7 +46,8 @@ class ProfiledPIDController
public:
/**
* Allocates a ProfiledPIDController with the given constants for Kp, Ki, and
* Kd.
* Kd. Users should call reset() when they first start running the controller
* to avoid unwanted behavior.
*
* @param Kp The proportional coefficient.
* @param Ki The integral coefficient.
@@ -292,9 +293,34 @@ class ProfiledPIDController
}
/**
* Reset the previous error, the integral term, and disable the controller.
* Reset the previous error and the integral term.
*
* @param measurement The current measured State of the system.
*/
void Reset() { m_controller.Reset(); }
void Reset(const State& measurement) {
m_controller.Reset();
m_setpoint = measurement;
}
/**
* Reset the previous error and the integral term.
*
* @param measuredPosition The current measured position of the system.
* @param measuredVelocity The current measured velocity of the system.
*/
void Reset(Distance_t measuredPosition, Velocity_t measuredVelocity) {
Reset(State{measuredPosition, measuredVelocity});
}
/**
* Reset the previous error and the integral term.
*
* @param measuredPosition The current measured position of the system. The
* velocity is assumed to be zero.
*/
void Reset(Distance_t measuredPosition) {
Reset(measuredPosition, Velocity_t(0));
}
void InitSendable(frc::SendableBuilder& builder) override {
builder.SetSmartDashboardType("ProfiledPIDController");

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -33,10 +33,13 @@
#include <frc/spline/Spline.h>
#include <stack>
#include <string>
#include <utility>
#include <vector>
#include <units/units.h>
#include <wpi/Twine.h>
namespace frc {
@@ -47,6 +50,11 @@ class SplineParameterizer {
public:
using PoseWithCurvature = std::pair<Pose2d, curvature_t>;
struct MalformedSplineException : public std::runtime_error {
explicit MalformedSplineException(const char* what_arg)
: runtime_error(what_arg) {}
};
/**
* Parameterizes the spline. This method breaks up the spline into various
* arcs until their dx, dy, and dtheta are within specific tolerances.
@@ -64,14 +72,48 @@ class SplineParameterizer {
static std::vector<PoseWithCurvature> Parameterize(const Spline<Dim>& spline,
double t0 = 0.0,
double t1 = 1.0) {
std::vector<PoseWithCurvature> arr;
std::vector<PoseWithCurvature> splinePoints;
// The parameterization does not add the first initial point. Let's add
// that.
arr.push_back(spline.GetPoint(t0));
// The parameterization does not add the initial point. Let's add that.
splinePoints.push_back(spline.GetPoint(t0));
GetSegmentArc(spline, &arr, t0, t1);
return arr;
// We use an "explicit stack" to simulate recursion, instead of a recursive
// function call This give us greater control, instead of a stack overflow
std::stack<StackContents> stack;
stack.emplace(StackContents{t0, t1});
StackContents current;
PoseWithCurvature start;
PoseWithCurvature end;
int iterations = 0;
while (!stack.empty()) {
current = stack.top();
stack.pop();
start = spline.GetPoint(current.t0);
end = spline.GetPoint(current.t1);
const auto twist = start.first.Log(end.first);
if (units::math::abs(twist.dy) > kMaxDy ||
units::math::abs(twist.dx) > kMaxDx ||
units::math::abs(twist.dtheta) > kMaxDtheta) {
stack.emplace(StackContents{(current.t0 + current.t1) / 2, current.t1});
stack.emplace(StackContents{current.t0, (current.t0 + current.t1) / 2});
} else {
splinePoints.push_back(spline.GetPoint(current.t1));
}
if (iterations++ >= kMaxIterations) {
throw MalformedSplineException(
"Could not parameterize a malformed spline. "
"This means that you probably had two or more adjacent "
"waypoints that were very close together with headings "
"in opposing directions.");
}
}
return splinePoints;
}
private:
@@ -80,33 +122,19 @@ class SplineParameterizer {
static constexpr units::meter_t kMaxDy = 0.05_in;
static constexpr units::radian_t kMaxDtheta = 0.0872_rad;
struct StackContents {
double t0;
double t1;
};
/**
* Breaks up the spline into arcs until the dx, dy, and theta of each arc is
* within tolerance.
*
* @param spline The spline to parameterize.
* @param vector Pointer to vector of poses.
* @param t0 Starting point for arc.
* @param t1 Ending point for arc.
* A malformed spline does not actually explode the LIFO stack size. Instead,
* the stack size stays at a relatively small number (e.g. 30) and never
* decreases. Because of this, we must count iterations. Even long, complex
* paths don't usually go over 300 iterations, so hitting this maximum should
* definitely indicate something has gone wrong.
*/
template <int Dim>
static void GetSegmentArc(const Spline<Dim>& spline,
std::vector<PoseWithCurvature>* vector, double t0,
double t1) {
const auto start = spline.GetPoint(t0);
const auto end = spline.GetPoint(t1);
const auto twist = start.first.Log(end.first);
if (units::math::abs(twist.dy) > kMaxDy ||
units::math::abs(twist.dx) > kMaxDx ||
units::math::abs(twist.dtheta) > kMaxDtheta) {
GetSegmentArc(spline, vector, t0, (t0 + t1) / 2);
GetSegmentArc(spline, vector, (t0 + t1) / 2, t1);
} else {
vector->push_back(spline.GetPoint(t1));
}
}
static constexpr int kMaxIterations = 5000;
friend class CubicHermiteSplineTest;
friend class QuinticHermiteSplineTest;

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -113,5 +113,8 @@ class TrajectoryGenerator {
}
return splinePoints;
}
private:
static const Trajectory kDoNothingTrajectory;
};
} // namespace frc

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -120,3 +120,14 @@ TEST_F(CubicHermiteSplineTest, OneInterior) {
Pose2d end{4_m, 0_m, 0_rad};
Run(start, waypoints, end);
}
TEST_F(CubicHermiteSplineTest, ThrowsOnMalformed) {
EXPECT_THROW(
Run(Pose2d{0_m, 0_m, Rotation2d(0_deg)}, std::vector<Translation2d>{},
Pose2d{1_m, 0_m, Rotation2d(180_deg)}),
SplineParameterizer::MalformedSplineException);
EXPECT_THROW(
Run(Pose2d{10_m, 10_m, Rotation2d(90_deg)}, std::vector<Translation2d>{},
Pose2d{10_m, 11_m, Rotation2d(-90_deg)}),
SplineParameterizer::MalformedSplineException);
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -85,3 +85,12 @@ TEST_F(QuinticHermiteSplineTest, SquigglyCurve) {
Run(Pose2d(0_m, 0_m, Rotation2d(90_deg)),
Pose2d(-1_m, 0_m, Rotation2d(90_deg)));
}
TEST_F(QuinticHermiteSplineTest, ThrowsOnMalformed) {
EXPECT_THROW(Run(Pose2d(0_m, 0_m, Rotation2d(0_deg)),
Pose2d(1_m, 0_m, Rotation2d(180_deg))),
SplineParameterizer::MalformedSplineException);
EXPECT_THROW(Run(Pose2d(10_m, 10_m, Rotation2d(90_deg)),
Pose2d(10_m, 11_m, Rotation2d(-90_deg))),
SplineParameterizer::MalformedSplineException);
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -33,3 +33,13 @@ TEST(TrajectoryGenerationTest, ObeysConstraints) {
12_fps_sq + 0.01_fps_sq);
}
}
TEST(TrajectoryGenertionTest, ReturnsEmptyOnMalformed) {
const auto t = TrajectoryGenerator::GenerateTrajectory(
std::vector<Pose2d>{Pose2d(0_m, 0_m, Rotation2d(0_deg)),
Pose2d(1_m, 0_m, Rotation2d(180_deg))},
TrajectoryConfig(12_fps, 12_fps_sq));
ASSERT_EQ(t.States().size(), 1u);
ASSERT_EQ(t.TotalTime(), 0_s);
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2018-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -328,7 +328,7 @@ public class PIDController implements Sendable, AutoCloseable {
}
/**
* Resets the previous error and the integral term. Also disables the controller.
* Resets the previous error and the integral term.
*/
public void reset() {
m_prevError = 0;

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -15,7 +15,8 @@ import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
/**
* Implements a PID control loop whose setpoint is constrained by a trapezoid
* profile.
* profile. Users should call reset() when they first start running the controller
* to avoid unwanted behavior.
*/
@SuppressWarnings("PMD.TooManyMethods")
public class ProfiledPIDController implements Sendable {
@@ -319,10 +320,33 @@ public class ProfiledPIDController implements Sendable {
}
/**
* Reset the previous error, the integral term, and disable the controller.
* Reset the previous error and the integral term.
*
* @param measurement The current measured State of the system.
*/
public void reset() {
public void reset(TrapezoidProfile.State measurement) {
m_controller.reset();
m_setpoint = measurement;
}
/**
* Reset the previous error and the integral term.
*
* @param measuredPosition The current measured position of the system.
* @param measuredVelocity The current measured velocity of the system.
*/
public void reset(double measuredPosition, double measuredVelocity) {
reset(new TrapezoidProfile.State(measuredPosition, measuredVelocity));
}
/**
* Reset the previous error and the integral term.
*
* @param measuredPosition The current measured position of the system. The velocity is
* assumed to be zero.
*/
public void reset(double measuredPosition) {
reset(measuredPosition, 0.0);
}
@Override

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -31,6 +31,7 @@
package edu.wpi.first.wpilibj.spline;
import java.util.ArrayDeque;
import java.util.ArrayList;
import java.util.List;
@@ -42,6 +43,36 @@ public final class SplineParameterizer {
private static final double kMaxDy = 0.00127;
private static final double kMaxDtheta = 0.0872;
/**
* A malformed spline does not actually explode the LIFO stack size. Instead, the stack size
* stays at a relatively small number (e.g. 30) and never decreases. Because of this, we must
* count iterations. Even long, complex paths don't usually go over 300 iterations, so hitting
* this maximum should definitely indicate something has gone wrong.
*/
private static final int kMaxIterations = 5000;
@SuppressWarnings("MemberName")
private static class StackContents {
final double t1;
final double t0;
StackContents(double t0, double t1) {
this.t0 = t0;
this.t1 = t1;
}
}
public static class MalformedSplineException extends RuntimeException {
/**
* Create a new exception with the given message.
*
* @param message the message to pass with the exception
*/
private MalformedSplineException(String message) {
super(message);
}
}
/**
* Private constructor because this is a utility class.
*/
@@ -53,7 +84,9 @@ public final class SplineParameterizer {
* arcs until their dx, dy, and dtheta are within specific tolerances.
*
* @param spline The spline to parameterize.
* @return A vector of poses and curvatures that represents various points on the spline.
* @return A list of poses and curvatures that represents various points on the spline.
* @throws MalformedSplineException When the spline is malformed (e.g. has close adjacent points
* with approximately opposing headings)
*/
public static List<PoseWithCurvature> parameterize(Spline spline) {
return parameterize(spline, 0.0, 1.0);
@@ -66,41 +99,54 @@ public final class SplineParameterizer {
* @param spline The spline to parameterize.
* @param t0 Starting internal spline parameter. It is recommended to use 0.0.
* @param t1 Ending internal spline parameter. It is recommended to use 1.0.
* @return A vector of poses and curvatures that represents various points on the spline.
* @return A list of poses and curvatures that represents various points on the spline.
* @throws MalformedSplineException When the spline is malformed (e.g. has close adjacent points
* with approximately opposing headings)
*/
@SuppressWarnings("PMD.AvoidInstantiatingObjectsInLoops")
public static List<PoseWithCurvature> parameterize(Spline spline, double t0, double t1) {
var arr = new ArrayList<PoseWithCurvature>();
var splinePoints = new ArrayList<PoseWithCurvature>();
// The parameterization does not add the first initial point. Let's add
// that.
arr.add(spline.getPoint(t0));
// The parameterization does not add the initial point. Let's add that.
splinePoints.add(spline.getPoint(t0));
getSegmentArc(spline, arr, t0, t1);
return arr;
}
// We use an "explicit stack" to simulate recursion, instead of a recursive function call
// This give us greater control, instead of a stack overflow
var stack = new ArrayDeque<StackContents>();
stack.push(new StackContents(t0, t1));
/**
* Breaks up the spline into arcs until the dx, dy, and theta of each arc is
* within tolerance.
*
* @param spline The spline to parameterize.
* @param vector Pointer to vector of poses.
* @param t0 Starting point for arc.
* @param t1 Ending point for arc.
*/
private static void getSegmentArc(Spline spline, List<PoseWithCurvature> vector,
double t0, double t1) {
final var start = spline.getPoint(t0);
final var end = spline.getPoint(t1);
StackContents current;
PoseWithCurvature start;
PoseWithCurvature end;
int iterations = 0;
final var twist = start.poseMeters.log(end.poseMeters);
while (!stack.isEmpty()) {
current = stack.removeFirst();
start = spline.getPoint(current.t0);
end = spline.getPoint(current.t1);
if (Math.abs(twist.dy) > kMaxDy || Math.abs(twist.dx) > kMaxDx
|| Math.abs(twist.dtheta) > kMaxDtheta) {
getSegmentArc(spline, vector, t0, (t0 + t1) / 2);
getSegmentArc(spline, vector, (t0 + t1) / 2, t1);
} else {
vector.add(spline.getPoint(t1));
final var twist = start.poseMeters.log(end.poseMeters);
if (
Math.abs(twist.dy) > kMaxDy
|| Math.abs(twist.dx) > kMaxDx
|| Math.abs(twist.dtheta) > kMaxDtheta
) {
stack.addFirst(new StackContents((current.t0 + current.t1) / 2, current.t1));
stack.addFirst(new StackContents(current.t0, (current.t0 + current.t1) / 2));
} else {
splinePoints.add(spline.getPoint(current.t1));
}
iterations++;
if (iterations >= kMaxIterations) {
throw new MalformedSplineException(
"Could not parameterize a malformed spline. "
+ "This means that you probably had two or more adjacent waypoints that were very close "
+ "together with headings in opposing directions."
);
}
}
return splinePoints;
}
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -8,9 +8,11 @@
package edu.wpi.first.wpilibj.trajectory;
import java.util.ArrayList;
import java.util.Arrays;
import java.util.Collection;
import java.util.List;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.geometry.Pose2d;
import edu.wpi.first.wpilibj.geometry.Rotation2d;
import edu.wpi.first.wpilibj.geometry.Transform2d;
@@ -19,8 +21,12 @@ import edu.wpi.first.wpilibj.spline.PoseWithCurvature;
import edu.wpi.first.wpilibj.spline.Spline;
import edu.wpi.first.wpilibj.spline.SplineHelper;
import edu.wpi.first.wpilibj.spline.SplineParameterizer;
import edu.wpi.first.wpilibj.spline.SplineParameterizer.MalformedSplineException;
public final class TrajectoryGenerator {
private static final Trajectory kDoNothingTrajectory =
new Trajectory(Arrays.asList(new Trajectory.State()));
/**
* Private constructor because this is a utility class.
*/
@@ -60,9 +66,14 @@ public final class TrajectoryGenerator {
}
// Get the spline points
var points = splinePointsFromSplines(SplineHelper.getCubicSplinesFromControlVectors(
newInitial, interiorWaypoints.toArray(new Translation2d[0]), newEnd
));
List<PoseWithCurvature> points;
try {
points = splinePointsFromSplines(SplineHelper.getCubicSplinesFromControlVectors(newInitial,
interiorWaypoints.toArray(new Translation2d[0]), newEnd));
} catch (MalformedSplineException ex) {
DriverStation.reportError(ex.getMessage(), ex.getStackTrace());
return kDoNothingTrajectory;
}
// Change the points back to their original orientation.
if (config.isReversed()) {
@@ -130,9 +141,15 @@ public final class TrajectoryGenerator {
}
// Get the spline points
var points = splinePointsFromSplines(SplineHelper.getQuinticSplinesFromControlVectors(
newControlVectors.toArray(new Spline.ControlVector[]{})
));
List<PoseWithCurvature> points;
try {
points = splinePointsFromSplines(SplineHelper.getQuinticSplinesFromControlVectors(
newControlVectors.toArray(new Spline.ControlVector[]{})
));
} catch (MalformedSplineException ex) {
DriverStation.reportError(ex.getMessage(), ex.getStackTrace());
return kDoNothingTrajectory;
}
// Change the points back to their original orientation.
if (config.isReversed()) {
@@ -171,6 +188,8 @@ public final class TrajectoryGenerator {
*
* @param splines The splines to parameterize.
* @return The spline points for use in time parameterization of a trajectory.
* @throws MalformedSplineException When the spline is malformed (e.g. has close adjacent points
* with approximately opposing headings)
*/
public static List<PoseWithCurvature> splinePointsFromSplines(
Spline[] splines) {

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -47,6 +47,7 @@ public final class TrajectoryUtil {
* @throws IOException if writing to the file fails
*/
public static void toPathweaverJson(Trajectory trajectory, Path path) throws IOException {
Files.createDirectories(path.getParent());
try (BufferedWriter writer = Files.newBufferedWriter(path)) {
WRITER.writeValue(writer, trajectory.getStates().toArray(new Trajectory.State[0]));
}

View File

@@ -0,0 +1,26 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
package edu.wpi.first.wpilibj.controller;
import org.junit.jupiter.api.Test;
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
import static org.junit.jupiter.api.Assertions.assertEquals;
class ProfiledPIDControllerTest {
@Test
void testStartFromNonZeroPosition() {
ProfiledPIDController controller = new ProfiledPIDController(1.0, 0.0, 0.0,
new TrapezoidProfile.Constraints(1.0, 1.0));
controller.reset(20);
assertEquals(0.0, controller.calculate(20), 0.05);
}
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -8,6 +8,7 @@
package edu.wpi.first.wpilibj.spline;
import java.util.ArrayList;
import java.util.Arrays;
import java.util.List;
import org.junit.jupiter.api.Test;
@@ -15,9 +16,11 @@ import org.junit.jupiter.api.Test;
import edu.wpi.first.wpilibj.geometry.Pose2d;
import edu.wpi.first.wpilibj.geometry.Rotation2d;
import edu.wpi.first.wpilibj.geometry.Translation2d;
import edu.wpi.first.wpilibj.spline.SplineParameterizer.MalformedSplineException;
import static org.junit.jupiter.api.Assertions.assertAll;
import static org.junit.jupiter.api.Assertions.assertEquals;
import static org.junit.jupiter.api.Assertions.assertThrows;
import static org.junit.jupiter.api.Assertions.assertTrue;
@@ -145,4 +148,15 @@ class CubicHermiteSplineTest {
run(start, waypoints, end);
}
@Test
void testMalformed() {
assertThrows(MalformedSplineException.class, () -> run(
new Pose2d(0, 0, Rotation2d.fromDegrees(0)),
new ArrayList<>(), new Pose2d(1, 0, Rotation2d.fromDegrees(180))));
assertThrows(MalformedSplineException.class, () -> run(
new Pose2d(10, 10, Rotation2d.fromDegrees(90)),
Arrays.asList(new Translation2d(10, 10.5)),
new Pose2d(10, 11, Rotation2d.fromDegrees(-90))));
}
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -13,9 +13,11 @@ import org.junit.jupiter.api.Test;
import edu.wpi.first.wpilibj.geometry.Pose2d;
import edu.wpi.first.wpilibj.geometry.Rotation2d;
import edu.wpi.first.wpilibj.spline.SplineParameterizer.MalformedSplineException;
import static org.junit.jupiter.api.Assertions.assertAll;
import static org.junit.jupiter.api.Assertions.assertEquals;
import static org.junit.jupiter.api.Assertions.assertThrows;
import static org.junit.jupiter.api.Assertions.assertTrue;
class QuinticHermiteSplineTest {
@@ -23,7 +25,7 @@ class QuinticHermiteSplineTest {
private static final double kMaxDy = 0.00127;
private static final double kMaxDtheta = 0.0872;
@SuppressWarnings({"ParameterName", "PMD.UnusedLocalVariable"})
@SuppressWarnings({ "ParameterName", "PMD.UnusedLocalVariable" })
private void run(Pose2d a, Pose2d b) {
// Start the timer.
var start = System.nanoTime();
@@ -49,29 +51,27 @@ class QuinticHermiteSplineTest {
assertAll(
() -> assertTrue(Math.abs(twist.dx) < kMaxDx),
() -> assertTrue(Math.abs(twist.dy) < kMaxDy),
() -> assertTrue(Math.abs(twist.dtheta) < kMaxDtheta)
);
() -> assertTrue(Math.abs(twist.dtheta) < kMaxDtheta));
}
// Check first point
assertAll(
() -> assertEquals(a.getTranslation().getX(),
poses.get(0).poseMeters.getTranslation().getX(), 1E-9),
() -> assertEquals(a.getTranslation().getY(),
poses.get(0).poseMeters.getTranslation().getY(), 1E-9),
() -> assertEquals(a.getRotation().getRadians(),
poses.get(0).poseMeters.getRotation().getRadians(), 1E-9)
);
() -> assertEquals(
a.getTranslation().getX(), poses.get(0).poseMeters.getTranslation().getX(), 1E-9),
() -> assertEquals(
a.getTranslation().getY(), poses.get(0).poseMeters.getTranslation().getY(), 1E-9),
() -> assertEquals(
a.getRotation().getRadians(), poses.get(0).poseMeters.getRotation().getRadians(),
1E-9));
// Check last point
assertAll(
() -> assertEquals(b.getTranslation().getX(),
poses.get(poses.size() - 1).poseMeters.getTranslation().getX(), 1E-9),
() -> assertEquals(b.getTranslation().getY(),
poses.get(poses.size() - 1).poseMeters.getTranslation().getY(), 1E-9),
() -> assertEquals(b.getTranslation().getX(), poses.get(poses.size() - 1)
.poseMeters.getTranslation().getX(), 1E-9),
() -> assertEquals(b.getTranslation().getY(), poses.get(poses.size() - 1)
.poseMeters.getTranslation().getY(), 1E-9),
() -> assertEquals(b.getRotation().getRadians(),
poses.get(poses.size() - 1).poseMeters.getRotation().getRadians(), 1E-9)
);
poses.get(poses.size() - 1).poseMeters.getRotation().getRadians(), 1E-9));
}
@SuppressWarnings("PMD.JUnitTestsShouldIncludeAssert")
@@ -89,7 +89,20 @@ class QuinticHermiteSplineTest {
@SuppressWarnings("PMD.JUnitTestsShouldIncludeAssert")
@Test
void testSquiggly() {
run(new Pose2d(0, 0, Rotation2d.fromDegrees(90)),
run(
new Pose2d(0, 0, Rotation2d.fromDegrees(90)),
new Pose2d(-1, 0, Rotation2d.fromDegrees(90)));
}
@Test
void testMalformed() {
assertThrows(MalformedSplineException.class,
() -> run(
new Pose2d(0, 0, Rotation2d.fromDegrees(0)),
new Pose2d(1, 0, Rotation2d.fromDegrees(180))));
assertThrows(MalformedSplineException.class,
() -> run(
new Pose2d(10, 10, Rotation2d.fromDegrees(90)),
new Pose2d(10, 11, Rotation2d.fromDegrees(-90))));
}
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -8,10 +8,12 @@
package edu.wpi.first.wpilibj.trajectory;
import java.util.ArrayList;
import java.util.Arrays;
import java.util.List;
import org.junit.jupiter.api.Test;
import edu.wpi.first.hal.sim.DriverStationSim;
import edu.wpi.first.wpilibj.geometry.Pose2d;
import edu.wpi.first.wpilibj.geometry.Rotation2d;
import edu.wpi.first.wpilibj.geometry.Transform2d;
@@ -20,6 +22,7 @@ import edu.wpi.first.wpilibj.trajectory.constraint.TrajectoryConstraint;
import static edu.wpi.first.wpilibj.util.Units.feetToMeters;
import static org.junit.jupiter.api.Assertions.assertAll;
import static org.junit.jupiter.api.Assertions.assertEquals;
import static org.junit.jupiter.api.Assertions.assertTrue;
class TrajectoryGeneratorTest {
@@ -69,4 +72,24 @@ class TrajectoryGeneratorTest {
);
}
}
@Test
void testMalformedTrajectory() {
var dsSim = new DriverStationSim();
dsSim.setSendError(false);
var traj =
TrajectoryGenerator.generateTrajectory(
Arrays.asList(
new Pose2d(0, 0, Rotation2d.fromDegrees(0)),
new Pose2d(1, 0, Rotation2d.fromDegrees(180))
),
new TrajectoryConfig(feetToMeters(12), feetToMeters(12))
);
assertEquals(traj.getStates().size(), 1);
assertEquals(traj.getTotalTimeSeconds(), 0);
dsSim.setSendError(true);
}
}

View File

@@ -40,7 +40,7 @@
"commandversion": 1
},
{
"name": "Subsystem",
"name": "Subsystem (Old)",
"description": "A subsystem",
"tags": [
"subsystem"