[commands] Add C++ Requirements struct (#5504)

This commit is contained in:
Joseph Eng
2023-09-17 20:48:39 -07:00
committed by GitHub
parent b265a68eea
commit 633c5a8a22
43 changed files with 273 additions and 1112 deletions

View File

@@ -79,44 +79,7 @@ class RamseteCommand : public CommandHelper<Command, RamseteCommand> {
frc::PIDController leftController,
frc::PIDController rightController,
std::function<void(units::volt_t, units::volt_t)> output,
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,
frc::PIDController leftController,
frc::PIDController rightController,
std::function<void(units::volt_t, units::volt_t)> output,
std::span<Subsystem* const> requirements = {});
Requirements requirements = {});
/**
* Constructs a new RamseteCommand that, when executed, will follow the
@@ -140,31 +103,7 @@ class RamseteCommand : public CommandHelper<Command, RamseteCommand> {
std::function<void(units::meters_per_second_t,
units::meters_per_second_t)>
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,
std::span<Subsystem* const> requirements = {});
Requirements requirements = {});
void Initialize() override;