Add ArrayRef overloads to new command classes (#2216)

Also default requirements to {} in all cases for consistency.
This commit is contained in:
Peter Johnson
2020-01-01 20:09:17 -08:00
committed by GitHub
parent 6190fcb237
commit 32c62449be
30 changed files with 773 additions and 49 deletions

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

@@ -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,6 +175,24 @@ 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;

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