From d55c55b2b8ca0a57c05c8dcc073d08ae62a2b21d Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Fri, 1 Dec 2023 21:05:52 -0800 Subject: [PATCH] Run wpiformat --- .../Frisbeebot/cpp/RobotContainer.cpp | 33 ++++---- .../Frisbeebot/include/RobotContainer.h | 1 - .../GearsBot/include/RobotContainer.h | 2 +- .../include/RobotContainer.h | 2 +- .../HatchbotInlined/cpp/RobotContainer.cpp | 6 +- .../HatchbotInlined/include/RobotContainer.h | 2 +- .../HatchbotInlined/include/commands/Autos.h | 5 +- .../cpp/RobotContainer.cpp | 11 +-- .../include/RobotContainer.h | 11 +-- .../cpp/RobotContainer.cpp | 82 ++++++++++--------- .../include/RobotContainer.h | 3 +- .../SelectCommand/include/RobotContainer.h | 2 +- .../cpp/RobotContainer.cpp | 24 +++--- .../include/RobotContainer.h | 2 +- 14 files changed, 92 insertions(+), 94 deletions(-) diff --git a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/RobotContainer.cpp index 26813c4117d..95ebfa76d3d 100644 --- a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/RobotContainer.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/RobotContainer.cpp @@ -63,20 +63,21 @@ void RobotContainer::ConfigureButtonBindings() { frc2::CommandPtr RobotContainer::GetAutonomousCommand() { // Runs the chosen command in autonomous return frc2::cmd::Sequence( - // Start the command by spinning up the shooter... - frc2::cmd::RunOnce([this] { m_shooter.Enable(); }, {&m_shooter}), - // Wait until the shooter is at speed before feeding the frisbees - frc2::cmd::WaitUntil([this] { return m_shooter.AtSetpoint(); }), - // Start running the feeder - frc2::cmd::RunOnce([this] { m_shooter.RunFeeder(); }, {&m_shooter}), - // Shoot for the specified time - frc2::cmd::Wait(ac::kAutoShootTimeSeconds)) - // Add a timeout (will end the command if, for instance, the shooter - // never gets up to speed) - .WithTimeout(ac::kAutoTimeoutSeconds) - // When the command ends, turn off the shooter and the feeder - .AndThen(frc2::cmd::RunOnce([this] { - m_shooter.Disable(); - m_shooter.StopFeeder(); - })); + // Start the command by spinning up the shooter... + frc2::cmd::RunOnce([this] { m_shooter.Enable(); }, {&m_shooter}), + // Wait until the shooter is at speed before feeding the frisbees + frc2::cmd::WaitUntil([this] { return m_shooter.AtSetpoint(); }), + // Start running the feeder + frc2::cmd::RunOnce([this] { m_shooter.RunFeeder(); }, + {&m_shooter}), + // Shoot for the specified time + frc2::cmd::Wait(ac::kAutoShootTimeSeconds)) + // Add a timeout (will end the command if, for instance, the shooter + // never gets up to speed) + .WithTimeout(ac::kAutoTimeoutSeconds) + // When the command ends, turn off the shooter and the feeder + .AndThen(frc2::cmd::RunOnce([this] { + m_shooter.Disable(); + m_shooter.StopFeeder(); + })); } diff --git a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/RobotContainer.h b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/RobotContainer.h index 3d94058f683..0e36c73d9d2 100644 --- a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/RobotContainer.h +++ b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/RobotContainer.h @@ -48,6 +48,5 @@ class RobotContainer { frc2::CommandPtr m_stopShooter = frc2::cmd::RunOnce([this] { m_shooter.Disable(); }, {&m_shooter}); - void ConfigureButtonBindings(); }; diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/RobotContainer.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/RobotContainer.h index ab523e40284..ef9f3830e66 100644 --- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/RobotContainer.h +++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/RobotContainer.h @@ -5,8 +5,8 @@ #pragma once #include -#include #include +#include #include "commands/Autonomous.h" #include "subsystems/Claw.h" diff --git a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/RobotContainer.h b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/RobotContainer.h index 43eb08b765c..0ecb7286d9f 100644 --- a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/RobotContainer.h +++ b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/RobotContainer.h @@ -7,8 +7,8 @@ #include #include #include -#include #include +#include #include #include "Constants.h" diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp index 329bfa5fc66..15b323b36f4 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp @@ -76,12 +76,12 @@ frc2::CommandPtr RobotContainer::GetAutonomousCommand() { switch (m_chooser.GetSelected()) { case autos::AutoEnum::kSimpleAuto: return autos::SimpleAuto(&m_drive); - break; + break; case autos::AutoEnum::kComplexAuto: return autos::ComplexAuto(&m_drive, &m_hatch); - break; + break; default: return frc2::CommandPtr(nullptr); - break; + break; } } diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/RobotContainer.h b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/RobotContainer.h index df086967f0c..490742047fa 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/RobotContainer.h +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/RobotContainer.h @@ -6,8 +6,8 @@ #include #include -#include #include +#include #include #include "Constants.h" diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/commands/Autos.h b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/commands/Autos.h index dae3a543c21..dfc73343f34 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/commands/Autos.h +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/commands/Autos.h @@ -23,9 +23,6 @@ frc2::CommandPtr SimpleAuto(DriveSubsystem* drive); */ frc2::CommandPtr ComplexAuto(DriveSubsystem* drive, HatchSubsystem* hatch); -enum class AutoEnum { - kSimpleAuto, - kComplexAuto -}; +enum class AutoEnum { kSimpleAuto, kComplexAuto }; } // namespace autos diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp index 7cd3fe710b6..91434fcccfc 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp @@ -83,13 +83,14 @@ frc2::CommandPtr RobotContainer::GetAutonomousCommand() { switch (m_chooser.GetSelected()) { case Autos::kSimpleAuto: return DriveDistance(AutoConstants::kAutoDriveDistanceInches, - AutoConstants::kAutoDriveSpeed, &m_drive).ToPtr(); - break; + AutoConstants::kAutoDriveSpeed, &m_drive) + .ToPtr(); + break; case Autos::kComplexAuto: return ComplexAuto(&m_drive, &m_hatch).ToPtr(); - break; - default: + break; + default: return frc2::CommandPtr(nullptr); - break; + break; } } diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/RobotContainer.h b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/RobotContainer.h index 95396e1efca..0b0caa6a409 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/RobotContainer.h +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/RobotContainer.h @@ -6,8 +6,8 @@ #include #include -#include #include +#include #include "Constants.h" #include "commands/ComplexAuto.h" @@ -17,13 +17,10 @@ #include "subsystems/HatchSubsystem.h" /** - * This is where the autos can be listed for the autonomous chooser so it can use CommandPtr - * the sendable chooser does not support the use of CommandPtr + * This is where the autos can be listed for the autonomous chooser so it can + * use CommandPtr the sendable chooser does not support the use of CommandPtr */ -enum class Autos { - kSimpleAuto, - kComplexAuto -}; +enum class Autos { kSimpleAuto, kComplexAuto }; /** * This class is where the bulk of the robot should be declared. Since diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/RobotContainer.cpp index 7c80d8b978c..25bfc3f04e9 100644 --- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/RobotContainer.cpp +++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/RobotContainer.cpp @@ -12,11 +12,11 @@ #include #include #include +#include #include #include #include #include -#include #include "Constants.h" @@ -71,43 +71,45 @@ frc2::CommandPtr RobotContainer::GetAutonomousCommand() { // no auto return frc2::cmd::Sequence( - frc2::MecanumControllerCommand( - exampleTrajectory, [this]() { return m_drive.GetPose(); }, - - frc::SimpleMotorFeedforward(ks, kv, ka), - DriveConstants::kDriveKinematics, - - frc::PIDController{AutoConstants::kPXController, 0, 0}, - frc::PIDController{AutoConstants::kPYController, 0, 0}, - frc::ProfiledPIDController( - AutoConstants::kPThetaController, 0, 0, - AutoConstants::kThetaControllerConstraints), - - AutoConstants::kMaxSpeed, - - [this]() { - return frc::MecanumDriveWheelSpeeds{ - units::meters_per_second_t{m_drive.GetFrontLeftEncoder().GetRate()}, - units::meters_per_second_t{ - m_drive.GetFrontRightEncoder().GetRate()}, - units::meters_per_second_t{m_drive.GetRearLeftEncoder().GetRate()}, - units::meters_per_second_t{ - m_drive.GetRearRightEncoder().GetRate()}}; - }, - - frc::PIDController{DriveConstants::kPFrontLeftVel, 0, 0}, - frc::PIDController{DriveConstants::kPRearLeftVel, 0, 0}, - frc::PIDController{DriveConstants::kPFrontRightVel, 0, 0}, - frc::PIDController{DriveConstants::kPRearRightVel, 0, 0}, - - [this](units::volt_t frontLeft, units::volt_t rearLeft, - units::volt_t frontRight, units::volt_t rearRight) { - m_drive.SetMotorControllersVolts(frontLeft, rearLeft, frontRight, - rearRight); - }, - - {&m_drive}).ToPtr(), - frc2::InstantCommand([this] { m_drive.Drive(0, 0, 0, false); }, {}).ToPtr() - ); - + frc2::MecanumControllerCommand( + exampleTrajectory, [this]() { return m_drive.GetPose(); }, + + frc::SimpleMotorFeedforward(ks, kv, ka), + DriveConstants::kDriveKinematics, + + frc::PIDController{AutoConstants::kPXController, 0, 0}, + frc::PIDController{AutoConstants::kPYController, 0, 0}, + frc::ProfiledPIDController( + AutoConstants::kPThetaController, 0, 0, + AutoConstants::kThetaControllerConstraints), + + AutoConstants::kMaxSpeed, + + [this]() { + return frc::MecanumDriveWheelSpeeds{ + units::meters_per_second_t{ + m_drive.GetFrontLeftEncoder().GetRate()}, + units::meters_per_second_t{ + m_drive.GetFrontRightEncoder().GetRate()}, + units::meters_per_second_t{ + m_drive.GetRearLeftEncoder().GetRate()}, + units::meters_per_second_t{ + m_drive.GetRearRightEncoder().GetRate()}}; + }, + + frc::PIDController{DriveConstants::kPFrontLeftVel, 0, 0}, + frc::PIDController{DriveConstants::kPRearLeftVel, 0, 0}, + frc::PIDController{DriveConstants::kPFrontRightVel, 0, 0}, + frc::PIDController{DriveConstants::kPRearRightVel, 0, 0}, + + [this](units::volt_t frontLeft, units::volt_t rearLeft, + units::volt_t frontRight, units::volt_t rearRight) { + m_drive.SetMotorControllersVolts(frontLeft, rearLeft, frontRight, + rearRight); + }, + + {&m_drive}) + .ToPtr(), + frc2::InstantCommand([this] { m_drive.Drive(0, 0, 0, false); }, {}) + .ToPtr()); } diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/RobotContainer.h b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/RobotContainer.h index e3ad375c6e2..c6f8afc703c 100644 --- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/RobotContainer.h +++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/RobotContainer.h @@ -9,11 +9,11 @@ #include #include #include +#include #include #include #include #include -#include #include "Constants.h" #include "subsystems/DriveSubsystem.h" @@ -45,6 +45,5 @@ class RobotContainer { frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); }, {}}; - void ConfigureButtonBindings(); }; diff --git a/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/RobotContainer.h b/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/RobotContainer.h index 16e86a7f78b..21657aac4af 100644 --- a/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/RobotContainer.h +++ b/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/RobotContainer.h @@ -5,8 +5,8 @@ #pragma once #include -#include #include +#include /** * This class is where the bulk of the robot should be declared. Since diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/RobotContainer.cpp index 9adaf01280d..7f41c35d878 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/RobotContainer.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/RobotContainer.cpp @@ -11,11 +11,11 @@ #include #include #include +#include #include #include #include #include -#include #include #include @@ -79,18 +79,20 @@ frc2::CommandPtr RobotContainer::GetAutonomousCommand() { // no auto return frc2::cmd::Sequence( - frc2::SwerveControllerCommand<4>( - exampleTrajectory, [this]() { return m_drive.GetPose(); }, - - m_drive.kDriveKinematics, + frc2::SwerveControllerCommand<4>( + exampleTrajectory, [this]() { return m_drive.GetPose(); }, - frc::PIDController{AutoConstants::kPXController, 0, 0}, - frc::PIDController{AutoConstants::kPYController, 0, 0}, thetaController, + m_drive.kDriveKinematics, - [this](auto moduleStates) { m_drive.SetModuleStates(moduleStates); }, + frc::PIDController{AutoConstants::kPXController, 0, 0}, + frc::PIDController{AutoConstants::kPYController, 0, 0}, + thetaController, - {&m_drive}).ToPtr(), - frc2::InstantCommand([this] { m_drive.Drive(0_mps, 0_mps, 0_rad_per_s, false); }, {}).ToPtr() - ); + [this](auto moduleStates) { m_drive.SetModuleStates(moduleStates); }, + {&m_drive}) + .ToPtr(), + frc2::InstantCommand( + [this] { m_drive.Drive(0_mps, 0_mps, 0_rad_per_s, false); }, {}) + .ToPtr()); } diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/RobotContainer.h b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/RobotContainer.h index ef5c7c74d66..4c7916456ab 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/RobotContainer.h +++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/RobotContainer.h @@ -9,11 +9,11 @@ #include #include #include +#include #include #include #include #include -#include #include "Constants.h" #include "subsystems/DriveSubsystem.h"