From 6e5be11c5e726c4bbb9b89a45d1bf9f81bd22bb6 Mon Sep 17 00:00:00 2001 From: Aalaa Mahmoud Date: Thu, 25 Jan 2024 09:08:22 -0600 Subject: [PATCH 001/108] files not recognized --- -s | 1 + .wpilib/wpilib_preferences.json | 2 +- lib | 2 +- ln | 1 + src/Constants.h | 4 ++-- src/Robot.cpp | 4 +++- src/RobotContainer.cpp | 15 +++++++++++++-- src/RobotContainer.h | 2 ++ .../{ExampleCommand.cpp => ArmCommand.cpp} | 5 +++-- .../{ExampleCommand.h => ArmCommand.h} | 11 ++++++----- src/commands/Autos.cpp | 14 -------------- src/commands/Autos.h | 16 ---------------- src/subsystems/arm/ArmConstants.h | 18 +++++++++--------- src/subsystems/arm/ArmSubsystem.cpp | 2 +- src/subsystems/arm/ArmSubsystem.h | 4 ++-- src/subsystems/arm/IntakeSubsystem.cpp | 12 +++++++++++- src/subsystems/arm/IntakeSubsystem.h | 10 +++++++++- src/subsystems/drive/DriveConstants.h | 2 +- src/subsystems/drive/DriveSubsystem.h | 4 ++++ 19 files changed, 70 insertions(+), 59 deletions(-) create mode 120000 -s create mode 120000 ln rename src/commands/{ExampleCommand.cpp => ArmCommand.cpp} (74%) rename src/commands/{ExampleCommand.h => ArmCommand.h} (73%) delete mode 100644 src/commands/Autos.cpp delete mode 100644 src/commands/Autos.h diff --git a/-s b/-s new file mode 120000 index 0000000..412b2d1 --- /dev/null +++ b/-s @@ -0,0 +1 @@ +-s \ No newline at end of file diff --git a/.wpilib/wpilib_preferences.json b/.wpilib/wpilib_preferences.json index cbd1ead..0628316 100644 --- a/.wpilib/wpilib_preferences.json +++ b/.wpilib/wpilib_preferences.json @@ -1,5 +1,5 @@ { - "enableCppIntellisense": true, + "enableCppIntellisense": false, "currentLanguage": "cpp", "projectYear": "2024", "teamNumber": 4330 diff --git a/lib b/lib index e44f612..f594b56 160000 --- a/lib +++ b/lib @@ -1 +1 @@ -Subproject commit e44f612388cde92573f44bdd4a8c5c1cdef41aba +Subproject commit f594b56ff30865046bc9b6ed5a65f3240066c3b7 diff --git a/ln b/ln new file mode 120000 index 0000000..dbed61a --- /dev/null +++ b/ln @@ -0,0 +1 @@ +ln \ No newline at end of file diff --git a/src/Constants.h b/src/Constants.h index 05c1d7b..5e2c03b 100644 --- a/src/Constants.h +++ b/src/Constants.h @@ -6,8 +6,8 @@ #include -#include -#include +// #include +// #include #include diff --git a/src/Robot.cpp b/src/Robot.cpp index 62ce066..bd4f325 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -3,6 +3,7 @@ // the WPILib BSD license file in the root directory of this project. #include "Robot.h" +#include "RobotContainer.h" #include @@ -39,7 +40,8 @@ void Robot::AutonomousInit() { } } -void Robot::AutonomousPeriodic() {} +void Robot::AutonomousPeriodic() { +} void Robot::TeleopInit() { // This makes sure that the autonomous stops running when diff --git a/src/RobotContainer.cpp b/src/RobotContainer.cpp index 4300501..8aeb5bd 100644 --- a/src/RobotContainer.cpp +++ b/src/RobotContainer.cpp @@ -6,8 +6,11 @@ #include -#include "commands/Autos.h" #include "commands/ExampleCommand.h" +#include "frc/Joystick.h" +#include "frc2/cmd/" +#include "subsystems/arm/ArmConstants.h" +#include "subsystems/arm/IntakeSubsystem.h" RobotContainer::RobotContainer() { // Initialize all of your commands and subsystems here @@ -31,5 +34,13 @@ void RobotContainer::ConfigureBindings() { frc2::CommandPtr RobotContainer::GetAutonomousCommand() { // An example command will be run in autonomous - return autos::ExampleAuto(&m_subsystem); + // return autos::ExampleAuto(&m_subsystem); + + return FunctionalCommand( + []() {}, + [this](m_controller, frontIntakeVelocityController, + backIntakeVelocityController) { + runIntake(m_controller, frontIntakeVelocityController, + backIntakeVelocityController); + }, [this](){}, [](){}, IntakeSubsystem).ToPtr(); } diff --git a/src/RobotContainer.h b/src/RobotContainer.h index 68283f7..39a5bf9 100644 --- a/src/RobotContainer.h +++ b/src/RobotContainer.h @@ -31,5 +31,7 @@ class RobotContainer { // The robot's subsystems are defined here... ExampleSubsystem m_subsystem; + + void ConfigureBindings(); }; diff --git a/src/commands/ExampleCommand.cpp b/src/commands/ArmCommand.cpp similarity index 74% rename from src/commands/ExampleCommand.cpp rename to src/commands/ArmCommand.cpp index a0c51b2..273263c 100644 --- a/src/commands/ExampleCommand.cpp +++ b/src/commands/ArmCommand.cpp @@ -2,9 +2,10 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include "commands/ExampleCommand.h" +#include "ArmCommand.h" +#include "subsystems/arm/ArmSubsystem.h" -ExampleCommand::ExampleCommand(ExampleSubsystem *subsystem) +ArmCommand::ArmCommand(ArmSubsystem *subsystem) : m_subsystem{subsystem} { // Register that this command requires the subsystem. AddRequirements(m_subsystem); diff --git a/src/commands/ExampleCommand.h b/src/commands/ArmCommand.h similarity index 73% rename from src/commands/ExampleCommand.h rename to src/commands/ArmCommand.h index dccdfaf..0fd4613 100644 --- a/src/commands/ExampleCommand.h +++ b/src/commands/ArmCommand.h @@ -7,7 +7,8 @@ #include #include -#include "subsystems/ExampleSubsystem.h" +#include "subsystems/arm/ArmSubsystem.h" +#include "subsystems/arm/IntakeSubsystem.h" /** * An example command that uses an example subsystem. @@ -16,16 +17,16 @@ * directly; this is crucially important, or else the decorator functions in * Command will *not* work! */ -class ExampleCommand - : public frc2::CommandHelper { +class ArmCommand + : public frc2::CommandHelper { public: /** * Creates a new ExampleCommand. * * @param subsystem The subsystem used by this command. */ - explicit ExampleCommand(ExampleSubsystem *subsystem); + explicit ArmCommand(ArmCommand *subsystem); private: - ExampleSubsystem *m_subsystem; + ArmCommand *m_subsystem; }; diff --git a/src/commands/Autos.cpp b/src/commands/Autos.cpp deleted file mode 100644 index feaec5f..0000000 --- a/src/commands/Autos.cpp +++ /dev/null @@ -1,14 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#include "commands/Autos.h" - -#include - -#include "commands/ExampleCommand.h" - -frc2::CommandPtr autos::ExampleAuto(ExampleSubsystem *subsystem) { - return frc2::cmd::Sequence(subsystem->ExampleMethodCommand(), - ExampleCommand(subsystem).ToPtr()); -} diff --git a/src/commands/Autos.h b/src/commands/Autos.h deleted file mode 100644 index 9eb0e0c..0000000 --- a/src/commands/Autos.h +++ /dev/null @@ -1,16 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#pragma once - -#include - -#include "subsystems/ExampleSubsystem.h" - -namespace autos { -/** - * Example static factory for an autonomous command. - */ -frc2::CommandPtr ExampleAuto(ExampleSubsystem *subsystem); -} // namespace autos diff --git a/src/subsystems/arm/ArmConstants.h b/src/subsystems/arm/ArmConstants.h index 5481859..f024db1 100644 --- a/src/subsystems/arm/ArmConstants.h +++ b/src/subsystems/arm/ArmConstants.h @@ -1,7 +1,7 @@ #pragma once -#include "rmb/motorcontrol/feedforward/ArmFeedforward.h" -#include "rmb/motorcontrol/feedforward/Feedforward.h" +#include "lib/rmb/motorcontrol/feedforward/ArmFeedforward.h" +#include "lib/rmb/motorcontrol/feedforward/Feedforward.h" #include #include @@ -44,7 +44,7 @@ const rmb::SparkMaxPositionController::CreateInfo }, .feedbackConfig = { - 1.0 /* <- gearRatio */, // TODO: Ask Adi about gear ratio + 9.0 /* <- gearRatio */, // TODO: Ask Adi about gear ratio rmb::SparkMaxPositionController::EncoderType:: HallSensor /* <- encoder */, 42 /* <- countPerRev */, @@ -90,7 +90,7 @@ const rmb::SparkMaxPositionController::CreateInfo }, .feedbackConfig = { - 1.0 /* <- gearRatio */, // TODO: Ask Adi about gear ratio + 9.0 /* <- gearRatio */, // TODO: Ask Adi about gear ratio rmb::SparkMaxPositionController::EncoderType:: HallSensor /* <- encoder */, 42 /* <- countPerRev */, @@ -135,7 +135,7 @@ const rmb::SparkMaxPositionController::CreateInfo }, .feedbackConfig = { - 1.0 /* <- gearRatio */, // TODO: Ask Adi about gear ratio + 9.0 /* <- gearRatio */, // TODO: Ask Adi about gear ratio rmb::SparkMaxPositionController::EncoderType:: HallSensor /* <- encoder */, 42 /* <- countPerRev */, @@ -151,7 +151,7 @@ const rmb::SparkMaxVelocityController::CreateInfo intakeFrontVelocityControllerCreateInfo{ .motorConfig = { - .id = 55, + .id = 1, .motorType = rev::CANSparkMax::MotorType::kBrushless, .inverted = false, }, @@ -177,7 +177,7 @@ const rmb::SparkMaxVelocityController::CreateInfo }, .feedbackConfig = { - 1.0 /* <- gearRatio */, // TODO: Ask Adi about gear ratio + 81.0 /* <- gearRatio */, // TODO: Ask Adi about gear ratio rmb::SparkMaxVelocityControllerHelper::EncoderType:: HallSensor /* <- encoder */, 42 /* <- countPerRev */, @@ -193,7 +193,7 @@ const rmb::SparkMaxVelocityController::CreateInfo intakeBackVelocityControllerCreateInfo{ .motorConfig = { - .id = 56, + .id = 21, .motorType = rev::CANSparkMax::MotorType::kBrushless, .inverted = false, }, @@ -219,7 +219,7 @@ const rmb::SparkMaxVelocityController::CreateInfo }, .feedbackConfig = { - 1.0 /* <- gearRatio */, // TODO: Ask Adi about gear ratio + 9.0 /* <- gearRatio */, // TODO: Ask Adi about gear ratio rmb::SparkMaxVelocityControllerHelper::EncoderType:: HallSensor /* <- encoder */, 42 /* <- countPerRev */, diff --git a/src/subsystems/arm/ArmSubsystem.cpp b/src/subsystems/arm/ArmSubsystem.cpp index a958d1a..7586259 100644 --- a/src/subsystems/arm/ArmSubsystem.cpp +++ b/src/subsystems/arm/ArmSubsystem.cpp @@ -2,7 +2,7 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include "subsystems/arm/ArmSubsystem.h" +#include "ArmSubsystem.h" #include "ArmConstants.h" #include "frc2/command/CommandPtr.h" diff --git a/src/subsystems/arm/ArmSubsystem.h b/src/subsystems/arm/ArmSubsystem.h index fb9db89..884fe2f 100644 --- a/src/subsystems/arm/ArmSubsystem.h +++ b/src/subsystems/arm/ArmSubsystem.h @@ -4,8 +4,8 @@ #pragma once -#include "rmb/motorcontrol/sparkmax/SparkMaxPositionController.h" -#include "rmb/motorcontrol/sparkmax/SparkMaxVelocityController.h" +#include "lib/rmb/motorcontrol/sparkmax/SparkMaxPositionController.h" +#include "lib/rmb/motorcontrol/sparkmax/SparkMaxVelocityController.h" #include "units/angular_velocity.h" #include #include diff --git a/src/subsystems/arm/IntakeSubsystem.cpp b/src/subsystems/arm/IntakeSubsystem.cpp index 9272691..9d30fae 100644 --- a/src/subsystems/arm/IntakeSubsystem.cpp +++ b/src/subsystems/arm/IntakeSubsystem.cpp @@ -2,9 +2,10 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include "subsystems/arm/IntakeSubsystem.h" +#include "IntakeSubsystem.h" #include "ArmConstants.h" +#include IntakeSubsystem::IntakeSubsystem() : frontIntakeVelocityController( @@ -21,3 +22,12 @@ void IntakeSubsystem::Periodic() { void IntakeSubsystem::SimulationPeriodic() { // Implementation of subsystem simulation periodic method goes here. } + +void IntakeSubsystem::runIntake(frc::Joystick m_controller, + frontIntakeVelocityController, + backIntakeVelocityController) { + frontIntakeVelocityController.Set( + m_controller.GerThrottle()); + backIntakeVelocityController.Set( + -m_controller.GetThrottle()); +} diff --git a/src/subsystems/arm/IntakeSubsystem.h b/src/subsystems/arm/IntakeSubsystem.h index 7da01bf..a7b424c 100644 --- a/src/subsystems/arm/IntakeSubsystem.h +++ b/src/subsystems/arm/IntakeSubsystem.h @@ -4,10 +4,12 @@ #pragma once +#include "ArmConstants.h" #include #include -#include +#include +#include class IntakeSubsystem : public frc2::SubsystemBase { public: @@ -36,10 +38,16 @@ class IntakeSubsystem : public frc2::SubsystemBase { setBackPower(back); } + void runIntake(frc::Joystick m_controller, frontIntakeVelocityController, backIntakeVelocityController); + + + private: // Components (e.g. motor controllers and sensors) should generally be // declared private and exposed only through public methods. rmb::SparkMaxVelocityController frontIntakeVelocityController; rmb::SparkMaxVelocityController backIntakeVelocityController; + + frc::Joystick m_controller; }; diff --git a/src/subsystems/drive/DriveConstants.h b/src/subsystems/drive/DriveConstants.h index 1838c5c..10fe5f6 100644 --- a/src/subsystems/drive/DriveConstants.h +++ b/src/subsystems/drive/DriveConstants.h @@ -1,7 +1,7 @@ // Copyright (c) FIRST and other WPILib contributors. // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. - +/* #pragma once #include diff --git a/src/subsystems/drive/DriveSubsystem.h b/src/subsystems/drive/DriveSubsystem.h index f140be8..1712bdc 100644 --- a/src/subsystems/drive/DriveSubsystem.h +++ b/src/subsystems/drive/DriveSubsystem.h @@ -19,6 +19,8 @@ class DriveSubsystem : public frc2::SubsystemBase { /** * Will be called periodically whenever the CommandScheduler runs. */ + + void Periodic() override; // TODO: support other types of joysticks @@ -32,6 +34,8 @@ class DriveSubsystem : public frc2::SubsystemBase { * Will be called periodically whenever the CommandScheduler runs during * simulation. */ + + void SimulationPeriodic() override; private: From e89bc0edfc75339329a04ac2fc4155d088db09a9 Mon Sep 17 00:00:00 2001 From: sullivanlm Date: Thu, 25 Jan 2024 15:12:30 +0000 Subject: [PATCH 002/108] BOT: Apply Formatting --- src/Robot.cpp | 3 +-- src/RobotContainer.cpp | 16 +++++++++------- src/RobotContainer.h | 2 -- src/commands/ArmCommand.cpp | 3 +-- src/commands/ArmCommand.h | 3 +-- src/subsystems/arm/IntakeSubsystem.cpp | 6 ++---- src/subsystems/arm/IntakeSubsystem.h | 7 +++---- src/subsystems/drive/DriveSubsystem.h | 2 -- 8 files changed, 17 insertions(+), 25 deletions(-) diff --git a/src/Robot.cpp b/src/Robot.cpp index bd4f325..440a5dc 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -40,8 +40,7 @@ void Robot::AutonomousInit() { } } -void Robot::AutonomousPeriodic() { -} +void Robot::AutonomousPeriodic() {} void Robot::TeleopInit() { // This makes sure that the autonomous stops running when diff --git a/src/RobotContainer.cpp b/src/RobotContainer.cpp index 8aeb5bd..553cfb4 100644 --- a/src/RobotContainer.cpp +++ b/src/RobotContainer.cpp @@ -36,11 +36,13 @@ frc2::CommandPtr RobotContainer::GetAutonomousCommand() { // An example command will be run in autonomous // return autos::ExampleAuto(&m_subsystem); - return FunctionalCommand( - []() {}, - [this](m_controller, frontIntakeVelocityController, - backIntakeVelocityController) { - runIntake(m_controller, frontIntakeVelocityController, - backIntakeVelocityController); - }, [this](){}, [](){}, IntakeSubsystem).ToPtr(); + return FunctionalCommand([]() {}, + [this](m_controller, frontIntakeVelocityController, + backIntakeVelocityController) { + runIntake(m_controller, + frontIntakeVelocityController, + backIntakeVelocityController); + }, + [this]() {}, []() {}, IntakeSubsystem) + .ToPtr(); } diff --git a/src/RobotContainer.h b/src/RobotContainer.h index 39a5bf9..68283f7 100644 --- a/src/RobotContainer.h +++ b/src/RobotContainer.h @@ -31,7 +31,5 @@ class RobotContainer { // The robot's subsystems are defined here... ExampleSubsystem m_subsystem; - - void ConfigureBindings(); }; diff --git a/src/commands/ArmCommand.cpp b/src/commands/ArmCommand.cpp index 273263c..7845d0e 100644 --- a/src/commands/ArmCommand.cpp +++ b/src/commands/ArmCommand.cpp @@ -5,8 +5,7 @@ #include "ArmCommand.h" #include "subsystems/arm/ArmSubsystem.h" -ArmCommand::ArmCommand(ArmSubsystem *subsystem) - : m_subsystem{subsystem} { +ArmCommand::ArmCommand(ArmSubsystem *subsystem) : m_subsystem{subsystem} { // Register that this command requires the subsystem. AddRequirements(m_subsystem); } diff --git a/src/commands/ArmCommand.h b/src/commands/ArmCommand.h index 0fd4613..86ca20d 100644 --- a/src/commands/ArmCommand.h +++ b/src/commands/ArmCommand.h @@ -17,8 +17,7 @@ * directly; this is crucially important, or else the decorator functions in * Command will *not* work! */ -class ArmCommand - : public frc2::CommandHelper { +class ArmCommand : public frc2::CommandHelper { public: /** * Creates a new ExampleCommand. diff --git a/src/subsystems/arm/IntakeSubsystem.cpp b/src/subsystems/arm/IntakeSubsystem.cpp index 9d30fae..7135356 100644 --- a/src/subsystems/arm/IntakeSubsystem.cpp +++ b/src/subsystems/arm/IntakeSubsystem.cpp @@ -26,8 +26,6 @@ void IntakeSubsystem::SimulationPeriodic() { void IntakeSubsystem::runIntake(frc::Joystick m_controller, frontIntakeVelocityController, backIntakeVelocityController) { - frontIntakeVelocityController.Set( - m_controller.GerThrottle()); - backIntakeVelocityController.Set( - -m_controller.GetThrottle()); + frontIntakeVelocityController.Set(m_controller.GerThrottle()); + backIntakeVelocityController.Set(-m_controller.GetThrottle()); } diff --git a/src/subsystems/arm/IntakeSubsystem.h b/src/subsystems/arm/IntakeSubsystem.h index a7b424c..24cbbbb 100644 --- a/src/subsystems/arm/IntakeSubsystem.h +++ b/src/subsystems/arm/IntakeSubsystem.h @@ -38,9 +38,8 @@ class IntakeSubsystem : public frc2::SubsystemBase { setBackPower(back); } - void runIntake(frc::Joystick m_controller, frontIntakeVelocityController, backIntakeVelocityController); - - + void runIntake(frc::Joystick m_controller, frontIntakeVelocityController, + backIntakeVelocityController); private: // Components (e.g. motor controllers and sensors) should generally be @@ -49,5 +48,5 @@ class IntakeSubsystem : public frc2::SubsystemBase { rmb::SparkMaxVelocityController frontIntakeVelocityController; rmb::SparkMaxVelocityController backIntakeVelocityController; - frc::Joystick m_controller; + frc::Joystick m_controller; }; diff --git a/src/subsystems/drive/DriveSubsystem.h b/src/subsystems/drive/DriveSubsystem.h index 1712bdc..496bd5f 100644 --- a/src/subsystems/drive/DriveSubsystem.h +++ b/src/subsystems/drive/DriveSubsystem.h @@ -20,7 +20,6 @@ class DriveSubsystem : public frc2::SubsystemBase { * Will be called periodically whenever the CommandScheduler runs. */ - void Periodic() override; // TODO: support other types of joysticks @@ -35,7 +34,6 @@ class DriveSubsystem : public frc2::SubsystemBase { * simulation. */ - void SimulationPeriodic() override; private: From d90d5848a9196928bc244c4ad517139ca016b6aa Mon Sep 17 00:00:00 2001 From: theVerySharpFlat Date: Thu, 25 Jan 2024 09:19:36 -0600 Subject: [PATCH 003/108] need to switch --- build.gradle | 8 ++++++++ src/Robot.h | 1 + src/subsystems/drive/DriveConstants.h | 8 ++++---- src/subsystems/drive/DriveSubsystem.cpp | 20 ++++++++++---------- 4 files changed, 23 insertions(+), 14 deletions(-) diff --git a/build.gradle b/build.gradle index acb4d1e..3cd3344 100644 --- a/build.gradle +++ b/build.gradle @@ -116,3 +116,11 @@ model { } } } + +task listrepos { + doLast { + println "Repositories:" + project.repositories.each { println "Name: " + it.name + "; url: " + it.url } + } +} + diff --git a/src/Robot.h b/src/Robot.h index f2c9b5c..7b409e9 100644 --- a/src/Robot.h +++ b/src/Robot.h @@ -13,6 +13,7 @@ class Robot : public frc::TimedRobot { public: + Robot() : frc::TimedRobot(40_ms) {} void RobotInit() override; void RobotPeriodic() override; void DisabledInit() override; diff --git a/src/subsystems/drive/DriveConstants.h b/src/subsystems/drive/DriveConstants.h index 1838c5c..3eb3782 100644 --- a/src/subsystems/drive/DriveConstants.h +++ b/src/subsystems/drive/DriveConstants.h @@ -31,10 +31,10 @@ const rmb::TalonFXVelocityControllerHelper::PIDConfig velocityModulePIDConfig = const rmb::TalonFXPositionControllerHelper::PIDConfig positionModulePIDConfig = {.p = 2.5f, .i = 0.0000f, .d = 0.0f, .ff = 0.000}; -const units::turn_t module1MagnetOffset(-0.169778); -const units::turn_t module2MagnetOffset(-0.190430); -const units::turn_t module3MagnetOffset(-0.726318 + 0.5); -const units::turn_t module4MagnetOffset(-0.37963 + 0.5); +const units::turn_t module1MagnetOffset(-0.403564); +const units::turn_t module2MagnetOffset(-0.223145); +const units::turn_t module3MagnetOffset(-0.382812 - 0.5); +const units::turn_t module4MagnetOffset(-0.948486); const units::meter_t wheelCircumference = 1.0_m; // TODO: CHANGE const units::meter_t robotDimX = 1.0_m; diff --git a/src/subsystems/drive/DriveSubsystem.cpp b/src/subsystems/drive/DriveSubsystem.cpp index 465190b..3ab68a1 100644 --- a/src/subsystems/drive/DriveSubsystem.cpp +++ b/src/subsystems/drive/DriveSubsystem.cpp @@ -23,7 +23,7 @@ DriveSubsystem::DriveSubsystem(std::shared_ptr gyro) { std::make_unique( constants::drive::positionControllerCreateInfo), frc::Translation2d(-constants::drive::robotDimX / 2.0, - constants::drive::robotDimY), + constants::drive::robotDimY / 2.0), true), rmb::SwerveModule( rmb::asLinear(std::make_unique( @@ -31,8 +31,8 @@ DriveSubsystem::DriveSubsystem(std::shared_ptr gyro) { constants::drive::wheelCircumference / 1_tr), std::make_unique( constants::drive::positionControllerCreateInfo1), - frc::Translation2d(constants::drive::robotDimX, - constants::drive::robotDimY), + frc::Translation2d(constants::drive::robotDimX / 2.0, + constants::drive::robotDimY / 2.0), true), rmb::SwerveModule( rmb::asLinear(std::make_unique( @@ -40,8 +40,8 @@ DriveSubsystem::DriveSubsystem(std::shared_ptr gyro) { constants::drive::wheelCircumference / 1_tr), std::make_unique( constants::drive::positionControllerCreateInfo2), - frc::Translation2d(constants::drive::robotDimX, - -constants::drive::robotDimY), + frc::Translation2d(constants::drive::robotDimX / 2.0, + -constants::drive::robotDimY / 2.0), true), rmb::SwerveModule( rmb::asLinear(std::make_unique( @@ -49,8 +49,8 @@ DriveSubsystem::DriveSubsystem(std::shared_ptr gyro) { constants::drive::wheelCircumference / 1_tr), std::make_unique( constants::drive::positionControllerCreateInfo3), - frc::Translation2d(-constants::drive::robotDimX, - -constants::drive::robotDimY), + frc::Translation2d(-constants::drive::robotDimX / 2.0, + -constants::drive::robotDimY / 2.0), true), }; @@ -74,13 +74,13 @@ void DriveSubsystem::Periodic() { void DriveSubsystem::driveTeleop(const rmb::LogitechGamepad &gamepad) { // TODO: add filters - drive->driveCartesian(gamepad.GetLeftX(), gamepad.GetLeftY(), - gamepad.GetRightX(), true); + drive->driveCartesian(gamepad.GetLeftY(), gamepad.GetLeftX(), + gamepad.GetRightY(), false); } frc2::CommandPtr DriveSubsystem::driveTeleopCommand(const rmb::LogitechGamepad &gamepad) { - return frc2::RunCommand([&] { driveTeleop(gamepad); }).ToPtr(); + return frc2::RunCommand([&] { driveTeleop(gamepad); }, {this}).ToPtr(); } frc2::CommandPtr DriveSubsystem::driveTeleopCommand(double x, double y, From 2d8b87b290f3eb82796f79a1f0467862445b089a Mon Sep 17 00:00:00 2001 From: Aalaa Mahmoud Date: Thu, 25 Jan 2024 10:16:28 -0600 Subject: [PATCH 004/108] fixed stuff --- src/RobotContainer.cpp | 11 ++++------- src/RobotContainer.h | 4 ++++ src/commands/ArmCommand.cpp | 6 +++--- src/commands/ArmCommand.h | 6 +++--- src/subsystems/arm/IntakeSubsystem.cpp | 10 +++------- src/subsystems/arm/IntakeSubsystem.h | 5 +++-- src/subsystems/drive/DriveConstants.h | 2 +- 7 files changed, 21 insertions(+), 23 deletions(-) diff --git a/src/RobotContainer.cpp b/src/RobotContainer.cpp index cf9bb22..411f276 100644 --- a/src/RobotContainer.cpp +++ b/src/RobotContainer.cpp @@ -7,7 +7,6 @@ #include #include "frc/Joystick.h" -#include "frc2/cmd/" #include "subsystems/arm/ArmConstants.h" #include "subsystems/arm/IntakeSubsystem.h" #include "frc2/command/Commands.h" @@ -38,13 +37,11 @@ frc2::CommandPtr RobotContainer::GetAutonomousCommand() { // An example command will be run in autonomous // return autos::ExampleAuto(&m_subsystem); - return FunctionalCommand( + return frc2::FunctionalCommand( []() {}, - [this](m_controller, frontIntakeVelocityController, - backIntakeVelocityController) { - runIntake(m_controller, frontIntakeVelocityController, - backIntakeVelocityController); - }, [this](){}, [](){}, IntakeSubsystem).ToPtr(); + [this]() { + intake.runIntake(controller); + }, [](){}, [](){return false;}, {&intake}).ToPtr(); } void RobotContainer::setTeleopDefaults() { diff --git a/src/RobotContainer.h b/src/RobotContainer.h index 9217f55..7875ad1 100644 --- a/src/RobotContainer.h +++ b/src/RobotContainer.h @@ -8,8 +8,10 @@ #include #include "Constants.h" +#include "frc/Joystick.h" #include "rmb/controller/LogitechGamepad.h" #include "rmb/sensors/AHRS/AHRSGyro.h" +#include "subsystems/arm/IntakeSubsystem.h" #include "subsystems/drive/DriveSubsystem.h" /** @@ -43,4 +45,6 @@ class RobotContainer { void ConfigureBindings(); + frc::Joystick controller{1}; + IntakeSubsystem intake; }; diff --git a/src/commands/ArmCommand.cpp b/src/commands/ArmCommand.cpp index 273263c..9880aa9 100644 --- a/src/commands/ArmCommand.cpp +++ b/src/commands/ArmCommand.cpp @@ -5,8 +5,8 @@ #include "ArmCommand.h" #include "subsystems/arm/ArmSubsystem.h" -ArmCommand::ArmCommand(ArmSubsystem *subsystem) - : m_subsystem{subsystem} { +ArmCommand::ArmCommand(ArmSubsystem &armSubsystem) + : armSubsystem(armSubsystem) { // Register that this command requires the subsystem. - AddRequirements(m_subsystem); + AddRequirements(&armSubsystem); } diff --git a/src/commands/ArmCommand.h b/src/commands/ArmCommand.h index 0fd4613..f46d022 100644 --- a/src/commands/ArmCommand.h +++ b/src/commands/ArmCommand.h @@ -23,10 +23,10 @@ class ArmCommand /** * Creates a new ExampleCommand. * - * @param subsystem The subsystem used by this command. + * @param ArmSubsystem The subsystem used by this command. */ - explicit ArmCommand(ArmCommand *subsystem); + explicit ArmCommand(ArmSubsystem &armSubsystem); private: - ArmCommand *m_subsystem; + ArmSubsystem &armSubsystem; }; diff --git a/src/subsystems/arm/IntakeSubsystem.cpp b/src/subsystems/arm/IntakeSubsystem.cpp index 9d30fae..cf09c83 100644 --- a/src/subsystems/arm/IntakeSubsystem.cpp +++ b/src/subsystems/arm/IntakeSubsystem.cpp @@ -5,6 +5,7 @@ #include "IntakeSubsystem.h" #include "ArmConstants.h" +#include "frc/Joystick.h" #include IntakeSubsystem::IntakeSubsystem() @@ -23,11 +24,6 @@ void IntakeSubsystem::SimulationPeriodic() { // Implementation of subsystem simulation periodic method goes here. } -void IntakeSubsystem::runIntake(frc::Joystick m_controller, - frontIntakeVelocityController, - backIntakeVelocityController) { - frontIntakeVelocityController.Set( - m_controller.GerThrottle()); - backIntakeVelocityController.Set( - -m_controller.GetThrottle()); +void IntakeSubsystem::runIntake(frc::Joystick &m_controller) { + setPower(m_controller.GetThrottle(), -m_controller.GetThrottle() ); } diff --git a/src/subsystems/arm/IntakeSubsystem.h b/src/subsystems/arm/IntakeSubsystem.h index 503d75c..4b309a4 100644 --- a/src/subsystems/arm/IntakeSubsystem.h +++ b/src/subsystems/arm/IntakeSubsystem.h @@ -7,6 +7,7 @@ #include "ArmConstants.h" #include #include +#include "frc/Joystick.h" #include #include @@ -38,7 +39,7 @@ class IntakeSubsystem : public frc2::SubsystemBase { setBackPower(back); } - void runIntake(frc::Joystick m_controller, frontIntakeVelocityController, backIntakeVelocityController); + void runIntake(frc::Joystick & m_controller); @@ -49,5 +50,5 @@ class IntakeSubsystem : public frc2::SubsystemBase { rmb::SparkMaxVelocityController frontIntakeVelocityController; rmb::SparkMaxVelocityController backIntakeVelocityController; - frc::Joystick m_controller; + }; diff --git a/src/subsystems/drive/DriveConstants.h b/src/subsystems/drive/DriveConstants.h index 10fe5f6..1838c5c 100644 --- a/src/subsystems/drive/DriveConstants.h +++ b/src/subsystems/drive/DriveConstants.h @@ -1,7 +1,7 @@ // Copyright (c) FIRST and other WPILib contributors. // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -/* + #pragma once #include From 2bf3db9f80eca3111411f1f386eee7810732cf69 Mon Sep 17 00:00:00 2001 From: sullivanlm Date: Thu, 25 Jan 2024 16:21:45 +0000 Subject: [PATCH 005/108] BOT: Apply Formatting --- src/RobotContainer.cpp | 13 ++++++------- src/RobotContainer.h | 2 +- src/subsystems/arm/IntakeSubsystem.cpp | 2 +- src/subsystems/arm/IntakeSubsystem.h | 4 ++-- 4 files changed, 10 insertions(+), 11 deletions(-) diff --git a/src/RobotContainer.cpp b/src/RobotContainer.cpp index e08db17..a6feb2d 100644 --- a/src/RobotContainer.cpp +++ b/src/RobotContainer.cpp @@ -7,10 +7,10 @@ #include #include "frc/Joystick.h" -#include "subsystems/arm/ArmConstants.h" -#include "subsystems/arm/IntakeSubsystem.h" #include "frc2/command/Commands.h" #include "frc2/command/RunCommand.h" +#include "subsystems/arm/ArmConstants.h" +#include "subsystems/arm/IntakeSubsystem.h" #include "subsystems/drive/DriveSubsystem.h" RobotContainer::RobotContainer() : driveSubsystem(gyro) { @@ -38,11 +38,10 @@ frc2::CommandPtr RobotContainer::GetAutonomousCommand() { // return autos::ExampleAuto(&m_subsystem); <<<<<<< HEAD - return frc2::FunctionalCommand( - []() {}, - [this]() { - intake.runIntake(controller); - }, [](){}, [](){return false;}, {&intake}).ToPtr(); + return frc2::FunctionalCommand([]() {}, + [this]() { intake.runIntake(controller); }, + []() {}, []() { return false; }, {&intake}) + .ToPtr(); } void RobotContainer::setTeleopDefaults() { diff --git a/src/RobotContainer.h b/src/RobotContainer.h index 6bb81ea..2345ee2 100644 --- a/src/RobotContainer.h +++ b/src/RobotContainer.h @@ -44,5 +44,5 @@ class RobotContainer { void ConfigureBindings(); frc::Joystick controller{1}; - IntakeSubsystem intake; + IntakeSubsystem intake; }; diff --git a/src/subsystems/arm/IntakeSubsystem.cpp b/src/subsystems/arm/IntakeSubsystem.cpp index 73f6303..1ad55b8 100644 --- a/src/subsystems/arm/IntakeSubsystem.cpp +++ b/src/subsystems/arm/IntakeSubsystem.cpp @@ -26,7 +26,7 @@ void IntakeSubsystem::SimulationPeriodic() { <<<<<<< HEAD void IntakeSubsystem::runIntake(frc::Joystick &m_controller) { - setPower(m_controller.GetThrottle(), -m_controller.GetThrottle() ); + setPower(m_controller.GetThrottle(), -m_controller.GetThrottle()); ======= void IntakeSubsystem::runIntake(frc::Joystick m_controller, frontIntakeVelocityController, diff --git a/src/subsystems/arm/IntakeSubsystem.h b/src/subsystems/arm/IntakeSubsystem.h index 51ab3ea..b22b145 100644 --- a/src/subsystems/arm/IntakeSubsystem.h +++ b/src/subsystems/arm/IntakeSubsystem.h @@ -5,9 +5,9 @@ #pragma once #include "ArmConstants.h" +#include "frc/Joystick.h" #include #include -#include "frc/Joystick.h" #include #include @@ -40,7 +40,7 @@ class IntakeSubsystem : public frc2::SubsystemBase { } <<<<<<< HEAD - void runIntake(frc::Joystick & m_controller); + void runIntake(frc::Joystick &m_controller); ======= From ed71f93310c401a0b1423badb991def3c58782b0 Mon Sep 17 00:00:00 2001 From: theVerySharpFlat Date: Thu, 25 Jan 2024 13:56:30 -0600 Subject: [PATCH 006/108] fix intake --- src/Robot.cpp | 10 +++++---- src/RobotContainer.cpp | 30 +++++++++++--------------- src/RobotContainer.h | 11 ++++++---- src/subsystems/arm/ArmConstants.h | 4 ++-- src/subsystems/arm/IntakeSubsystem.cpp | 14 ++++-------- src/subsystems/arm/IntakeSubsystem.h | 14 +----------- 6 files changed, 32 insertions(+), 51 deletions(-) diff --git a/src/Robot.cpp b/src/Robot.cpp index a35de02..ce9e27f 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -33,14 +33,15 @@ void Robot::DisabledPeriodic() {} * RobotContainer} class. */ void Robot::AutonomousInit() { - m_autonomousCommand = container.GetAutonomousCommand(); + m_autonomousCommand = container.getAutonomousCommand(); + + // TODO: Check to see if we need to remove this + frc2::CommandScheduler::GetInstance().CancelAll(); if (m_autonomousCommand) { m_autonomousCommand->Schedule(); } - // TODO: Check to see if we need to remove this - frc2::CommandScheduler::GetInstance().CancelAll(); } void Robot::AutonomousPeriodic() {} @@ -63,7 +64,8 @@ void Robot::TeleopInit() { /** * This function is called periodically during operator control. */ -void Robot::TeleopPeriodic() {} +void Robot::TeleopPeriodic() { +} /** * This function is called periodically during test mode. diff --git a/src/RobotContainer.cpp b/src/RobotContainer.cpp index e08db17..872edff 100644 --- a/src/RobotContainer.cpp +++ b/src/RobotContainer.cpp @@ -13,7 +13,7 @@ #include "frc2/command/RunCommand.h" #include "subsystems/drive/DriveSubsystem.h" -RobotContainer::RobotContainer() : driveSubsystem(gyro) { +RobotContainer::RobotContainer() {//: driveSubsystem(gyro) { // Initialize all of your commands and subsystems here // Configure the button bindings @@ -33,34 +33,28 @@ void RobotContainer::ConfigureBindings() { // m_driverController.B().WhileTrue(m_subsystem.ExampleMethodCommand()); } -frc2::CommandPtr RobotContainer::GetAutonomousCommand() { +frc2::CommandPtr RobotContainer::getAutonomousCommand() { // An example command will be run in autonomous // return autos::ExampleAuto(&m_subsystem); + return frc2::cmd::None(); +} -<<<<<<< HEAD +frc2::CommandPtr RobotContainer::getIntakeCommand() { + // Joystick input is blocked during teleop return frc2::FunctionalCommand( []() {}, [this]() { + std::cout << "right here" << std::endl; intake.runIntake(controller); - }, [](){}, [](){return false;}, {&intake}).ToPtr(); + }, [](bool canceled){}, [](){return false;}, {&intake}).ToPtr(); } void RobotContainer::setTeleopDefaults() { - driveSubsystem.SetDefaultCommand(driveSubsystem.driveTeleopCommand(gamepad)); + // driveSubsystem.SetDefaultCommand(driveSubsystem.driveTeleopCommand(gamepad)); + intake.SetDefaultCommand(getIntakeCommand()); } void RobotContainer::setAutoDefaults() { - driveSubsystem.SetDefaultCommand( - frc2::RunCommand([this] { driveSubsystem.stop(); }).ToPtr()); -======= - return FunctionalCommand([]() {}, - [this](m_controller, frontIntakeVelocityController, - backIntakeVelocityController) { - runIntake(m_controller, - frontIntakeVelocityController, - backIntakeVelocityController); - }, - [this]() {}, []() {}, IntakeSubsystem) - .ToPtr(); ->>>>>>> e89bc0edfc75339329a04ac2fc4155d088db09a9 + // driveSubsystem.SetDefaultCommand( + // frc2::RunCommand([this] { driveSubsystem.stop(); }).ToPtr()); } diff --git a/src/RobotContainer.h b/src/RobotContainer.h index 6bb81ea..29cfc50 100644 --- a/src/RobotContainer.h +++ b/src/RobotContainer.h @@ -25,7 +25,9 @@ class RobotContainer { public: RobotContainer(); - frc2::CommandPtr GetAutonomousCommand(); + frc2::CommandPtr getAutonomousCommand(); + + frc2::CommandPtr getIntakeCommand(); void setTeleopDefaults(); void setAutoDefaults(); @@ -36,13 +38,14 @@ class RobotContainer { // constants::driverControllerPort}; // The robot's subsystems are defined here... - std::shared_ptr gyro = - std::make_shared(constants::gyroPort); - DriveSubsystem driveSubsystem; + // std::shared_ptr gyro = + // std::make_shared(constants::gyroPort); + // DriveSubsystem driveSubsystem; rmb::LogitechGamepad gamepad{constants::driverControllerPort}; void ConfigureBindings(); frc::Joystick controller{1}; + IntakeSubsystem intake; }; diff --git a/src/subsystems/arm/ArmConstants.h b/src/subsystems/arm/ArmConstants.h index bc6090b..05cf54c 100644 --- a/src/subsystems/arm/ArmConstants.h +++ b/src/subsystems/arm/ArmConstants.h @@ -151,7 +151,7 @@ const rmb::SparkMaxVelocityController::CreateInfo intakeFrontVelocityControllerCreateInfo{ .motorConfig = { - .id = 1, + .id = 59, .motorType = rev::CANSparkMax::MotorType::kBrushless, .inverted = false, }, @@ -193,7 +193,7 @@ const rmb::SparkMaxVelocityController::CreateInfo intakeBackVelocityControllerCreateInfo{ .motorConfig = { - .id = 21, + .id = 58, .motorType = rev::CANSparkMax::MotorType::kBrushless, .inverted = false, }, diff --git a/src/subsystems/arm/IntakeSubsystem.cpp b/src/subsystems/arm/IntakeSubsystem.cpp index 73f6303..4d96719 100644 --- a/src/subsystems/arm/IntakeSubsystem.cpp +++ b/src/subsystems/arm/IntakeSubsystem.cpp @@ -4,6 +4,8 @@ #include "IntakeSubsystem.h" +#include + #include "ArmConstants.h" #include "frc/Joystick.h" #include @@ -24,14 +26,6 @@ void IntakeSubsystem::SimulationPeriodic() { // Implementation of subsystem simulation periodic method goes here. } -<<<<<<< HEAD -void IntakeSubsystem::runIntake(frc::Joystick &m_controller) { - setPower(m_controller.GetThrottle(), -m_controller.GetThrottle() ); -======= -void IntakeSubsystem::runIntake(frc::Joystick m_controller, - frontIntakeVelocityController, - backIntakeVelocityController) { - frontIntakeVelocityController.Set(m_controller.GerThrottle()); - backIntakeVelocityController.Set(-m_controller.GetThrottle()); ->>>>>>> e89bc0edfc75339329a04ac2fc4155d088db09a9 +void IntakeSubsystem::runIntake(const frc::Joystick &controller) { + setPower(controller.GetThrottle(), -controller.GetThrottle() ); } diff --git a/src/subsystems/arm/IntakeSubsystem.h b/src/subsystems/arm/IntakeSubsystem.h index 51ab3ea..2bfa051 100644 --- a/src/subsystems/arm/IntakeSubsystem.h +++ b/src/subsystems/arm/IntakeSubsystem.h @@ -39,25 +39,13 @@ class IntakeSubsystem : public frc2::SubsystemBase { setBackPower(back); } -<<<<<<< HEAD - void runIntake(frc::Joystick & m_controller); + void runIntake(const frc::Joystick & m_controller); -======= - void runIntake(frc::Joystick m_controller, frontIntakeVelocityController, - backIntakeVelocityController); ->>>>>>> e89bc0edfc75339329a04ac2fc4155d088db09a9 - private: // Components (e.g. motor controllers and sensors) should generally be // declared private and exposed only through public methods. rmb::SparkMaxVelocityController frontIntakeVelocityController; rmb::SparkMaxVelocityController backIntakeVelocityController; - -<<<<<<< HEAD - -======= - frc::Joystick m_controller; ->>>>>>> e89bc0edfc75339329a04ac2fc4155d088db09a9 }; From 4adeac58b7ed45b38ea4e0fb5c78a5618714c6e4 Mon Sep 17 00:00:00 2001 From: theVerySharpFlat Date: Thu, 25 Jan 2024 20:10:50 +0000 Subject: [PATCH 007/108] BOT: Apply Formatting --- src/Robot.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/Robot.cpp b/src/Robot.cpp index ce9e27f..fc5a468 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -41,7 +41,6 @@ void Robot::AutonomousInit() { if (m_autonomousCommand) { m_autonomousCommand->Schedule(); } - } void Robot::AutonomousPeriodic() {} @@ -64,8 +63,7 @@ void Robot::TeleopInit() { /** * This function is called periodically during operator control. */ -void Robot::TeleopPeriodic() { -} +void Robot::TeleopPeriodic() {} /** * This function is called periodically during test mode. From 1bd88905148950a424cdc3cc06aaaaa7e499e18f Mon Sep 17 00:00:00 2001 From: theVerySharpFlat Date: Fri, 26 Jan 2024 15:24:38 -0600 Subject: [PATCH 008/108] bump lib --- lib | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lib b/lib index 597f5bc..f594b56 160000 --- a/lib +++ b/lib @@ -1 +1 @@ -Subproject commit 597f5bc415a0b063757571655c17898f25947a28 +Subproject commit f594b56ff30865046bc9b6ed5a65f3240066c3b7 From 52df7a5746757b710d2bb7672879c9b262eddae0 Mon Sep 17 00:00:00 2001 From: theVerySharpFlat Date: Sat, 27 Jan 2024 16:28:13 -0600 Subject: [PATCH 009/108] delete uneeded files --- -s | 1 - ln | 1 - 2 files changed, 2 deletions(-) delete mode 120000 -s delete mode 120000 ln diff --git a/-s b/-s deleted file mode 120000 index 412b2d1..0000000 --- a/-s +++ /dev/null @@ -1 +0,0 @@ --s \ No newline at end of file diff --git a/ln b/ln deleted file mode 120000 index dbed61a..0000000 --- a/ln +++ /dev/null @@ -1 +0,0 @@ -ln \ No newline at end of file From 1b0f94937c748170964f830686aff57b2d1a818e Mon Sep 17 00:00:00 2001 From: theVerySharpFlat Date: Sat, 27 Jan 2024 17:57:37 -0600 Subject: [PATCH 010/108] enforce counter clockwise positive in swerve modules --- lib/src/rmb/drive/SwerveDrive.inl | 28 ++++++++----------- .../Talon/TalonFXPositionController.h | 2 +- 2 files changed, 12 insertions(+), 18 deletions(-) diff --git a/lib/src/rmb/drive/SwerveDrive.inl b/lib/src/rmb/drive/SwerveDrive.inl index f32195e..bc51643 100644 --- a/lib/src/rmb/drive/SwerveDrive.inl +++ b/lib/src/rmb/drive/SwerveDrive.inl @@ -4,61 +4,52 @@ #include "pathplanner/lib/path/PathConstraints.h" #include "pathplanner/lib/path/PathPlannerPath.h" #include "pathplanner/lib/util/HolonomicPathFollowerConfig.h" -#include "pathplanner/lib/util/PIDConstants.h" #include "pathplanner/lib/util/ReplanningConfig.h" -#include "rmb/drive/BaseDrive.h" -#include "units/acceleration.h" #include "units/angle.h" -#include "units/angular_velocity.h" #include "units/base.h" #include "units/length.h" -#include "units/math.h" -#include "units/time.h" #include "units/velocity.h" #include "frc/controller/HolonomicDriveController.h" #include "frc/estimator/SwerveDrivePoseEstimator.h" #include "frc/geometry/Rotation2d.h" -#include "frc/interfaces/Gyro.h" +#include "frc/geometry/Translation2d.h" #include "frc/kinematics/ChassisSpeeds.h" #include "frc/kinematics/SwerveDriveKinematics.h" #include "frc/kinematics/SwerveModulePosition.h" #include "frc/kinematics/SwerveModuleState.h" -#include "frc/geometry/Translation2d.h" - #include "frc2/command//SwerveControllerCommand.h" #include "frc2/command/CommandPtr.h" #include "frc2/command/Commands.h" #include "frc2/command/Subsystem.h" + #include "networktables/NetworkTable.h" #include "networktables/NetworkTableInstance.h" + #include "rmb/drive/SwerveDrive.h" #include "rmb/drive/SwerveModule.h" -#include "rmb/motorcontrol/feedforward/Feedforward.h" + #include "units/angle.h" -#include "units/angular_velocity.h" #include "units/length.h" -#include "units/math.h" #include "units/velocity.h" + #include "wpi/array.h" -#include "wpi/sendable/SendableRegistry.h" #include #include -#include #include -#include #include + #include +#include #include "pathplanner/lib/commands/FollowPathHolonomic.h" #include "pathplanner/lib/commands/PathfindHolonomic.h" #include "pathplanner/lib/path/PathConstraints.h" #include "pathplanner/lib/util/HolonomicPathFollowerConfig.h" #include "pathplanner/lib/util/ReplanningConfig.h" -#include namespace rmb { @@ -183,7 +174,10 @@ void SwerveDrive::driveCartesian(double xSpeed, double ySpeed, robotRelativeVXY.y() + zRotation * -module.getModuleTranslation().X() / largestModuleDistance; - frc::Rotation2d moduleRotation{output_x, output_y}; + // Enforce a forward-facing 0_deg that increases in the counterclockwise + // direction + frc::Rotation2d moduleRotation = + -1.0 * frc::Rotation2d(output_x, output_y).Radians(); double modulePower = std::sqrt(output_x * output_x + output_y * output_y); powers[i] = SwerveModulePower{modulePower, moduleRotation}; diff --git a/lib/src/rmb/motorcontrol/Talon/TalonFXPositionController.h b/lib/src/rmb/motorcontrol/Talon/TalonFXPositionController.h index d19641e..ee4e072 100644 --- a/lib/src/rmb/motorcontrol/Talon/TalonFXPositionController.h +++ b/lib/src/rmb/motorcontrol/Talon/TalonFXPositionController.h @@ -18,7 +18,7 @@ namespace rmb { namespace TalonFXPositionControllerHelper { struct MotorConfig { int id; - bool inverted = false; + bool inverted = false; /*< false for counterclockwise positive*/ bool brake = false; double minOutput = -1.0, maxOutput = 1.0; /*< Applies to both open and closed loop*/ From 1984bee8ffb4dca91d326775788f7298473a92c7 Mon Sep 17 00:00:00 2001 From: theVerySharpFlat Date: Sun, 28 Jan 2024 04:10:24 -0600 Subject: [PATCH 011/108] add odometry --- lib/src/rmb/drive/SwerveDrive.h | 2 +- lib/src/rmb/drive/SwerveDrive.inl | 10 ++-- .../Talon/TalonFXPositionController.cpp | 60 ++++++++++++++++--- .../Talon/TalonFXPositionController.h | 7 +++ .../Talon/TalonFXVelocityController.cpp | 54 ++++++++++++++--- .../Talon/TalonFXVelocityController.h | 6 ++ lib/src/rmb/sensors/AHRS/AHRSGyro.cpp | 2 +- 7 files changed, 119 insertions(+), 22 deletions(-) diff --git a/lib/src/rmb/drive/SwerveDrive.h b/lib/src/rmb/drive/SwerveDrive.h index c158094..e775295 100644 --- a/lib/src/rmb/drive/SwerveDrive.h +++ b/lib/src/rmb/drive/SwerveDrive.h @@ -294,7 +294,7 @@ template class SwerveDrive : public BaseDrive { /** * Mutex to protect position estimations between vision threads. */ - mutable std::mutex visionThreadMutex; + // mutable std::mutex visionThreadMutex; units::meters_per_second_t maxModuleSpeed; diff --git a/lib/src/rmb/drive/SwerveDrive.inl b/lib/src/rmb/drive/SwerveDrive.inl index bc51643..131c804 100644 --- a/lib/src/rmb/drive/SwerveDrive.inl +++ b/lib/src/rmb/drive/SwerveDrive.inl @@ -244,12 +244,12 @@ frc::ChassisSpeeds SwerveDrive::getChassisSpeeds() const { template frc::Pose2d SwerveDrive::getPose() const { - std::lock_guard lock(visionThreadMutex); + // std::lock_guard lock(visionThreadMutex); return poseEstimator.GetEstimatedPosition(); } template frc::Pose2d SwerveDrive::updatePose() { - std::lock_guard lock(visionThreadMutex); + // std::lock_guard lock(visionThreadMutex); return poseEstimator.Update( frc::Rotation2d((units::radian_t)gyro->getZRotation()), getModulePositions()); @@ -330,21 +330,21 @@ SwerveDrive::getTargetModuleStates() const { template void SwerveDrive::resetPose(const frc::Pose2d &pose) { - std::lock_guard lock(visionThreadMutex); + // std::lock_guard lock(visionThreadMutex); poseEstimator.ResetPosition(gyro->getRotation(), getModulePositions(), pose); } template void SwerveDrive::addVisionMeasurments( const frc::Pose2d &poseEstimate, units::second_t time) { - std::lock_guard lock(visionThreadMutex); + // std::lock_guard lock(visionThreadMutex); poseEstimator.AddVisionMeasurement(poseEstimate, time); } template void SwerveDrive::setVisionSTDevs( wpi::array standardDevs) { - std::lock_guard lock(visionThreadMutex); + // std::lock_guard lock(visionThreadMutex); poseEstimator.SetVisionMeasurementStdDevs(standardDevs); } diff --git a/lib/src/rmb/motorcontrol/Talon/TalonFXPositionController.cpp b/lib/src/rmb/motorcontrol/Talon/TalonFXPositionController.cpp index dd1c48a..3ff99a1 100644 --- a/lib/src/rmb/motorcontrol/Talon/TalonFXPositionController.cpp +++ b/lib/src/rmb/motorcontrol/Talon/TalonFXPositionController.cpp @@ -1,8 +1,12 @@ #include "TalonFXPositionController.h" +#include "ctre/phoenix6/StatusSignal.hpp" #include "ctre/phoenix6/configs/Configs.hpp" #include "ctre/phoenix6/core/CoreCANcoder.hpp" #include "ctre/phoenix6/core/CoreTalonFX.hpp" +#include "frc/Watchdog.h" +#include "frc2/command/CommandScheduler.h" #include "units/angle.h" +#include "units/angular_velocity.h" #include @@ -124,8 +128,20 @@ void TalonFXPositionController::setPosition(units::radian_t position) { motorcontroller.SetControl(request); } +ctre::phoenix6::StatusSignal & +TalonFXPositionController::getTargetPositionStatusSignal() const { + thread_local auto signal = ctre::phoenix6::StatusSignal( + motorcontroller.GetClosedLoopReference()); + + return signal; +} + units::radian_t TalonFXPositionController::getTargetPosition() const { - return units::turn_t(motorcontroller.GetClosedLoopReference().GetValue()); + auto signal = getTargetPositionStatusSignal(); + + signal.Refresh(); + + return units::turn_t(signal.GetValue()); } units::radian_t TalonFXPositionController::getMinPosition() const { @@ -140,22 +156,52 @@ void TalonFXPositionController::disable() { motorcontroller.Disable(); } void TalonFXPositionController::stop() { motorcontroller.StopMotor(); } -units::radians_per_second_t TalonFXPositionController::getVelocity() const { +ctre::phoenix6::StatusSignal & +TalonFXPositionController::getVelocityStatusSignal() const { if (usingCANCoder) { - return canCoder->GetVelocity().GetValue(); + thread_local auto signal = + ctre::phoenix6::StatusSignal(canCoder->GetVelocity()); + + return signal; } else { - return motorcontroller.GetVelocity().GetValue(); + thread_local auto signal = + ctre::phoenix6::StatusSignal(motorcontroller.GetVelocity()); + + return signal; } } -units::radian_t TalonFXPositionController::getPosition() const { +units::radians_per_second_t TalonFXPositionController::getVelocity() const { + auto signal = getVelocityStatusSignal(); + + signal.Refresh(); + + return signal.GetValue(); +} + +ctre::phoenix6::StatusSignal & +TalonFXPositionController::getPositionStatusSignal() const { if (usingCANCoder) { - return canCoder->GetPosition().GetValue(); + thread_local auto signal = + ctre::phoenix6::StatusSignal(canCoder->GetPosition()); + + return signal; } else { - return motorcontroller.GetPosition().GetValue(); + thread_local auto signal = + ctre::phoenix6::StatusSignal(motorcontroller.GetPosition()); + + return signal; } } +units::radian_t TalonFXPositionController::getPosition() const { + auto signal = getPositionStatusSignal(); + + signal.Refresh(); + + return signal.GetValue(); +} + void TalonFXPositionController::setEncoderPosition(units::radian_t position) { if (canCoder.has_value()) { canCoder->SetPosition(position); diff --git a/lib/src/rmb/motorcontrol/Talon/TalonFXPositionController.h b/lib/src/rmb/motorcontrol/Talon/TalonFXPositionController.h index ee4e072..f045bda 100644 --- a/lib/src/rmb/motorcontrol/Talon/TalonFXPositionController.h +++ b/lib/src/rmb/motorcontrol/Talon/TalonFXPositionController.h @@ -180,6 +180,8 @@ class TalonFXPositionController : public AngularPositionController { */ virtual double getPower() const override; + ctre::phoenix6::StatusSignal &getTargetPositionStatusSignal() const; + /** * Queries the Phoenix API for the current set point of the motor */ @@ -207,12 +209,17 @@ class TalonFXPositionController : public AngularPositionController { */ void stop() override; + ctre::phoenix6::StatusSignal & + getVelocityStatusSignal() const; + /** * Get the current velocity of the motor * @return The velocity of the motor in a units::angular_velocity container */ units::radians_per_second_t getVelocity() const override; + ctre::phoenix6::StatusSignal &getPositionStatusSignal() const; + /** * Get the current position of the motor * @return The current position of the motor as measured by the selected diff --git a/lib/src/rmb/motorcontrol/Talon/TalonFXVelocityController.cpp b/lib/src/rmb/motorcontrol/Talon/TalonFXVelocityController.cpp index f932e52..ee081c8 100644 --- a/lib/src/rmb/motorcontrol/Talon/TalonFXVelocityController.cpp +++ b/lib/src/rmb/motorcontrol/Talon/TalonFXVelocityController.cpp @@ -1,4 +1,5 @@ #include "TalonFXVelocityController.h" +#include "ctre/phoenix6/StatusSignal.hpp" #include "ctre/phoenix6/controls/DutyCycleOut.hpp" #include "units/angular_velocity.h" @@ -126,20 +127,46 @@ void TalonFXVelocityController::setVelocity( ctre::phoenix6::controls::VelocityDutyCycle(velocity)); } +ctre::phoenix6::StatusSignal & +TalonFXVelocityController::getTargetVelocityStatusSignal() const { + thread_local auto signal = ctre::phoenix6::StatusSignal( + motorcontroller.GetClosedLoopReference()); + + return signal; +} + units::radians_per_second_t TalonFXVelocityController::getTargetVelocity() const { - return units::turns_per_second_t( - motorcontroller.GetClosedLoopReference().GetValue()); + auto signal = getTargetVelocityStatusSignal(); + + signal.Refresh(); + + return units::turns_per_second_t(signal.GetValue()); } -units::radians_per_second_t TalonFXVelocityController::getVelocity() const { +ctre::phoenix6::StatusSignal & +TalonFXVelocityController::getVelocityStatusSignal() const { if (usingCANCoder) { - return canCoder->GetVelocity().GetValue(); + thread_local auto signal = + ctre::phoenix6::StatusSignal(canCoder->GetVelocity()); + + return signal; } else { - return motorcontroller.GetVelocity().GetValue(); + thread_local auto signal = + ctre::phoenix6::StatusSignal(motorcontroller.GetVelocity()); + + return signal; } } +units::radians_per_second_t TalonFXVelocityController::getVelocity() const { + auto signal = getVelocityStatusSignal(); + + signal.Refresh(); + + return signal.GetValue(); +} + void TalonFXVelocityController::setPower(double power) { motorcontroller.SetControl(ctre::phoenix6::controls::DutyCycleOut(power)); // motorcontroller.Set(power); @@ -156,14 +183,25 @@ void TalonFXVelocityController::disable() { motorcontroller.Disable(); } void TalonFXVelocityController::stop() { motorcontroller.StopMotor(); } -units::radian_t TalonFXVelocityController::getPosition() const { +ctre::phoenix6::StatusSignal & +TalonFXVelocityController::getPositionStatusSignal() const { if (usingCANCoder) { - return canCoder->GetPosition().GetValue(); + thread_local auto signal = + ctre::phoenix6::StatusSignal(canCoder->GetPosition()); + + return signal; } else { - return motorcontroller.GetPosition().GetValue(); + thread_local auto signal = + ctre::phoenix6::StatusSignal(motorcontroller.GetPosition()); + + return signal; } } +units::radian_t TalonFXVelocityController::getPosition() const { + return getPositionStatusSignal().Refresh().GetValue(); +} + void TalonFXVelocityController::setEncoderPosition(units::radian_t position) { if (canCoder.has_value()) { canCoder->SetPosition(position); diff --git a/lib/src/rmb/motorcontrol/Talon/TalonFXVelocityController.h b/lib/src/rmb/motorcontrol/Talon/TalonFXVelocityController.h index 11a8602..6f54081 100644 --- a/lib/src/rmb/motorcontrol/Talon/TalonFXVelocityController.h +++ b/lib/src/rmb/motorcontrol/Talon/TalonFXVelocityController.h @@ -58,6 +58,7 @@ class TalonFXVelocityController : public AngularVelocityController { */ void setVelocity(units::radians_per_second_t velocity) override; + ctre::phoenix6::StatusSignal &getTargetVelocityStatusSignal() const; /** * Gets the target angular velocity. * @@ -88,6 +89,9 @@ class TalonFXVelocityController : public AngularVelocityController { //--------------------------------------- // Methods Inherited from AngularEncoder //--------------------------------------- + // + ctre::phoenix6::StatusSignal & + getVelocityStatusSignal() const; /** * Gets the angular velocity of the motor. @@ -96,6 +100,8 @@ class TalonFXVelocityController : public AngularVelocityController { */ units::radians_per_second_t getVelocity() const override; + ctre::phoenix6::StatusSignal &getPositionStatusSignal() const; + /** * Gets the angular position of an motor. * diff --git a/lib/src/rmb/sensors/AHRS/AHRSGyro.cpp b/lib/src/rmb/sensors/AHRS/AHRSGyro.cpp index 1d5ec0c..c5c4cba 100644 --- a/lib/src/rmb/sensors/AHRS/AHRSGyro.cpp +++ b/lib/src/rmb/sensors/AHRS/AHRSGyro.cpp @@ -11,7 +11,7 @@ AHRSGyro::AHRSGyro(frc::SerialPort::Port port) : gyro(std::make_unique(port)) {} units::turn_t AHRSGyro::AHRSGyro::getZRotation() const { - return units::degree_t(-gyro->GetRotation2d().Degrees()); + return -gyro->GetRotation2d().Degrees(); } frc::Rotation2d AHRSGyro::getRotation() const { return gyro->GetRotation2d(); } From 20ffb98399f131a81c55e20f12caa8ee42652f89 Mon Sep 17 00:00:00 2001 From: theVerySharpFlat Date: Sun, 28 Jan 2024 14:39:18 -0600 Subject: [PATCH 012/108] move odometry to separate thread --- src/subsystems/drive/DriveSubsystem.cpp | 23 ++++++++++++++++++++++- src/subsystems/drive/DriveSubsystem.h | 14 ++++++++++++-- 2 files changed, 34 insertions(+), 3 deletions(-) diff --git a/src/subsystems/drive/DriveSubsystem.cpp b/src/subsystems/drive/DriveSubsystem.cpp index 3ab68a1..8f54ec1 100644 --- a/src/subsystems/drive/DriveSubsystem.cpp +++ b/src/subsystems/drive/DriveSubsystem.cpp @@ -5,6 +5,8 @@ #include "subsystems/drive/DriveSubsystem.h" #include "Constants.h" +#include "frc/TimedRobot.h" +#include "frc/geometry/Pose2d.h" #include "subsystems/drive/DriveConstants.h" #include "frc2/command/CommandPtr.h" @@ -12,6 +14,8 @@ #include "rmb/sensors/gyro.h" #include +#include +#include DriveSubsystem::DriveSubsystem(std::shared_ptr gyro) { // Implementation of subsystem constructor goes here. @@ -65,11 +69,28 @@ DriveSubsystem::DriveSubsystem(std::shared_ptr gyro) { frc::TrapezoidProfile::Constraints( 6.28_rad_per_s, 3.14_rad_per_s / 1_s))), constants::drive::maxModuleSpeed); + + odometryThread = std::thread(&DriveSubsystem::odometryThreadMain, this); +} + +void DriveSubsystem::odometryThreadMain() { + while (true) { + frc::Pose2d newPose = drive->updatePose(); + { + std::lock_guard lock(currentPoseContainer.mutex); + currentPoseContainer._pose = newPose; + } + std::this_thread::yield(); + } +} + +frc::Pose2d DriveSubsystem::getPoseEstimation() { + std::lock_guard lock(currentPoseContainer.mutex); + return currentPoseContainer._pose; } void DriveSubsystem::Periodic() { // Implementation of subsystem periodic method goes here. - drive->updatePose(); } void DriveSubsystem::driveTeleop(const rmb::LogitechGamepad &gamepad) { diff --git a/src/subsystems/drive/DriveSubsystem.h b/src/subsystems/drive/DriveSubsystem.h index c2dd7ae..89b0a67 100644 --- a/src/subsystems/drive/DriveSubsystem.h +++ b/src/subsystems/drive/DriveSubsystem.h @@ -4,6 +4,7 @@ #pragma once +#include "frc/geometry/Pose2d.h" #include "rmb/sensors/gyro.h" #include #include @@ -11,6 +12,7 @@ #include #include #include +#include class DriveSubsystem : public frc2::SubsystemBase { public: @@ -28,6 +30,8 @@ class DriveSubsystem : public frc2::SubsystemBase { frc2::CommandPtr driveTeleopCommand(const rmb::LogitechGamepad &gamepad); frc2::CommandPtr driveTeleopCommand(double x, double y, double twist); + frc::Pose2d getPoseEstimation(); + void stop(); /** @@ -37,8 +41,14 @@ class DriveSubsystem : public frc2::SubsystemBase { void SimulationPeriodic() override; private: - // Components (e.g. motor controllers and sensors) should generally be - // declared private and exposed only through public methods. + void odometryThreadMain(); std::unique_ptr> drive; + + std::thread odometryThread; + + struct { + frc::Pose2d _pose; + std::mutex mutex; + } currentPoseContainer; }; From 47186575789e8bd2651723d4214b6ae73b49679f Mon Sep 17 00:00:00 2001 From: theVerySharpFlat Date: Mon, 29 Jan 2024 10:53:29 -0600 Subject: [PATCH 013/108] initial pathplanner auto setup --- lib/src/rmb/drive/SwerveDrive.h | 2 + src/Constants.h | 3 + src/Robot.h | 3 +- src/RobotContainer.cpp | 21 ++++++ src/RobotContainer.h | 7 ++ src/main/deploy/pathplanner/navgrid.json | 1 + .../pathplanner/paths/Example Path.path | 67 +++++++++++++++++++ .../deploy/pathplanner/paths/New Path.path | 65 ++++++++++++++++++ src/subsystems/drive/DriveConstants.h | 4 ++ src/subsystems/drive/DriveSubsystem.cpp | 47 ++++++++++++- src/subsystems/drive/DriveSubsystem.h | 9 ++- 11 files changed, 225 insertions(+), 4 deletions(-) create mode 100644 src/main/deploy/pathplanner/navgrid.json create mode 100644 src/main/deploy/pathplanner/paths/Example Path.path create mode 100644 src/main/deploy/pathplanner/paths/New Path.path diff --git a/lib/src/rmb/drive/SwerveDrive.h b/lib/src/rmb/drive/SwerveDrive.h index e775295..de76786 100644 --- a/lib/src/rmb/drive/SwerveDrive.h +++ b/lib/src/rmb/drive/SwerveDrive.h @@ -227,6 +227,8 @@ template class SwerveDrive : public BaseDrive { frc::Pose2d targetPose, pathplanner::PathConstraints constraints, std::initializer_list driveRequirements); + inline units::meter_t getMaxDriveRadius() { return largestModuleDistance; } + void updateNTDebugInfo(bool openLoopVelocity = false); void stop(); diff --git a/src/Constants.h b/src/Constants.h index 3d2dd25..8d992be 100644 --- a/src/Constants.h +++ b/src/Constants.h @@ -4,6 +4,7 @@ #pragma once +#include "units/time.h" #include #include @@ -23,6 +24,8 @@ namespace constants { +const units::millisecond_t robotLoopTime = 20_ms; + inline constexpr int driverControllerPort = 0; const frc::SerialPort::Port gyroPort = frc::SerialPort::Port::kMXP; diff --git a/src/Robot.h b/src/Robot.h index 7b409e9..ef21135 100644 --- a/src/Robot.h +++ b/src/Robot.h @@ -9,11 +9,12 @@ #include #include +#include "Constants.h" #include "RobotContainer.h" class Robot : public frc::TimedRobot { public: - Robot() : frc::TimedRobot(40_ms) {} + Robot() : frc::TimedRobot(constants::robotLoopTime) {} void RobotInit() override; void RobotPeriodic() override; void DisabledInit() override; diff --git a/src/RobotContainer.cpp b/src/RobotContainer.cpp index ab80270..6631720 100644 --- a/src/RobotContainer.cpp +++ b/src/RobotContainer.cpp @@ -6,8 +6,13 @@ #include +#include +#include + #include "frc2/command/Commands.h" #include "frc2/command/RunCommand.h" +#include "pathplanner/lib/path/PathPlannerPath.h" +#include "pathplanner/lib/auto/NamedCommands.h" #include "subsystems/drive/DriveSubsystem.h" RobotContainer::RobotContainer() : driveSubsystem(gyro) { @@ -30,6 +35,22 @@ void RobotContainer::ConfigureBindings() { // m_driverController.B().WhileTrue(m_subsystem.ExampleMethodCommand()); } +void RobotContainer::loadPPPaths() { + std::string pathDir = + frc::filesystem::GetDeployDirectory() + "/pathplanner/paths/"; + + for (const auto &entry : std::filesystem::directory_iterator(pathDir)) { + if (entry.is_regular_file() && entry.path().extension() == ".path") { + paths[entry.path().stem()] = + pathplanner::PathPlannerPath::fromPathFile(entry.path().stem()); + } + } + + // Register named commands here + // with + // pathplanner::NamedCommands::registerCommand() +} + frc2::CommandPtr RobotContainer::GetAutonomousCommand() { // An example command will be run in autonomous // return autos::ExampleAuto(&m_subsystem); diff --git a/src/RobotContainer.h b/src/RobotContainer.h index 66419b6..d5997df 100644 --- a/src/RobotContainer.h +++ b/src/RobotContainer.h @@ -12,6 +12,8 @@ #include "rmb/sensors/AHRS/AHRSGyro.h" #include "subsystems/drive/DriveSubsystem.h" +#include + /** * This class is where the bulk of the robot should be declared. Since * Command-based is a "declarative" paradigm, very little robot logic should @@ -28,6 +30,8 @@ class RobotContainer { void setTeleopDefaults(); void setAutoDefaults(); + void loadPPPaths(); + private: // Replace with CommandPS4Controller or CommandJoystick if needed // frc2::CommandXboxController m_driverController{ @@ -41,4 +45,7 @@ class RobotContainer { rmb::LogitechGamepad gamepad{constants::driverControllerPort}; void ConfigureBindings(); + + std::unordered_map> + paths; }; diff --git a/src/main/deploy/pathplanner/navgrid.json b/src/main/deploy/pathplanner/navgrid.json new file mode 100644 index 0000000..bab0da9 --- /dev/null +++ b/src/main/deploy/pathplanner/navgrid.json @@ -0,0 +1 @@ +{"field_size":{"x":16.54,"y":8.21},"nodeSizeMeters":0.3,"grid":[[true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true],[true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true],[true,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true],[true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,true,true,true],[true,true,true,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,true,true,true,true],[true,true,true,true,false,false,false,false,false,false,true,true,true,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,true,true,true,false,false,false,false,false,false,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true],[true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true],[true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true],[true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true],[true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true]]} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/paths/Example Path.path b/src/main/deploy/pathplanner/paths/Example Path.path new file mode 100644 index 0000000..8aebdad --- /dev/null +++ b/src/main/deploy/pathplanner/paths/Example Path.path @@ -0,0 +1,67 @@ +{ + "version": 1.0, + "waypoints": [ + { + "anchor": { + "x": 3.0, + "y": 7.0 + }, + "prevControl": null, + "nextControl": { + "x": 3.9566940893141047, + "y": 7.004446772782435 + }, + "isLocked": false, + "linkedName": null + }, + { + "anchor": { + "x": 6.0, + "y": 7.0 + }, + "prevControl": { + "x": 5.296976201602062, + "y": 7.0 + }, + "nextControl": null, + "isLocked": false, + "linkedName": null + } + ], + "rotationTargets": [], + "constraintZones": [], + "eventMarkers": [ + { + "name": "New Event Marker", + "waypointRelativePos": 0.4, + "command": { + "type": "sequential", + "data": { + "commands": [ + { + "type": "wait", + "data": { + "waitTime": 1.0 + } + } + ] + } + } + } + ], + "globalConstraints": { + "maxVelocity": 3.0, + "maxAcceleration": 3.0, + "maxAngularVelocity": 540.0, + "maxAngularAcceleration": 720.0 + }, + "goalEndState": { + "velocity": 0, + "rotation": 0, + "rotateFast": false + }, + "reversed": false, + "folder": null, + "previewStartingState": null, + "useDefaultConstraints": false +} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/paths/New Path.path b/src/main/deploy/pathplanner/paths/New Path.path new file mode 100644 index 0000000..8eb50ac --- /dev/null +++ b/src/main/deploy/pathplanner/paths/New Path.path @@ -0,0 +1,65 @@ +{ + "version": 1.0, + "waypoints": [ + { + "anchor": { + "x": 7.562929213821391, + "y": 3.9206754061656275 + }, + "prevControl": null, + "nextControl": { + "x": 8.562929213821379, + "y": 3.4206754061656275 + }, + "isLocked": false, + "linkedName": null + }, + { + "anchor": { + "x": 9.429202062107828, + "y": 2.055649629817778 + }, + "prevControl": { + "x": 8.429202062107828, + "y": 3.0556496298177787 + }, + "nextControl": { + "x": 10.429202062107828, + "y": 1.0556496298177782 + }, + "isLocked": false, + "linkedName": null + }, + { + "anchor": { + "x": 7.0, + "y": 1.0 + }, + "prevControl": { + "x": 6.75, + "y": 2.5 + }, + "nextControl": null, + "isLocked": false, + "linkedName": null + } + ], + "rotationTargets": [], + "constraintZones": [], + "eventMarkers": [], + "globalConstraints": { + "maxVelocity": 3.0, + "maxAcceleration": 3.0, + "maxAngularVelocity": 540.0, + "maxAngularAcceleration": 720.0 + }, + "goalEndState": { + "velocity": 0, + "rotation": 0, + "rotateFast": false + }, + "reversed": false, + "folder": null, + "previewStartingState": null, + "useDefaultConstraints": false +} \ No newline at end of file diff --git a/src/subsystems/drive/DriveConstants.h b/src/subsystems/drive/DriveConstants.h index 3eb3782..87317c1 100644 --- a/src/subsystems/drive/DriveConstants.h +++ b/src/subsystems/drive/DriveConstants.h @@ -4,6 +4,7 @@ #pragma once +#include "pathplanner/lib/util/PIDConstants.h" #include #include @@ -24,6 +25,9 @@ namespace constants { namespace drive { +const pathplanner::PIDConstants pathTranslationalConstants(5.0, 0.0, 0.0, 1.0); +const pathplanner::PIDConstants pathRotationalConstants(5.0, 0.0, 0.0, 1.0); + using rmb::TalonFXPositionControllerHelper::CANCoderConfig; const rmb::TalonFXVelocityControllerHelper::PIDConfig velocityModulePIDConfig = diff --git a/src/subsystems/drive/DriveSubsystem.cpp b/src/subsystems/drive/DriveSubsystem.cpp index 8f54ec1..d9608d0 100644 --- a/src/subsystems/drive/DriveSubsystem.cpp +++ b/src/subsystems/drive/DriveSubsystem.cpp @@ -5,8 +5,11 @@ #include "subsystems/drive/DriveSubsystem.h" #include "Constants.h" +#include "frc/DriverStation.h" +#include "frc/RobotBase.h" #include "frc/TimedRobot.h" #include "frc/geometry/Pose2d.h" +#include "pathplanner/lib/auto/AutoBuilder.h" #include "subsystems/drive/DriveConstants.h" #include "frc2/command/CommandPtr.h" @@ -71,24 +74,64 @@ DriveSubsystem::DriveSubsystem(std::shared_ptr gyro) { constants::drive::maxModuleSpeed); odometryThread = std::thread(&DriveSubsystem::odometryThreadMain, this); + + pathplanner::AutoBuilder::configureHolonomic( + [this]() { return getPoseEstimation(); }, + [this](frc::Pose2d pose) { setPoseEstimation(pose); }, + [this]() { return getChassisSpeedsEstimation(); }, + [this](frc::ChassisSpeeds speeds) { // should be robot relative + drive->driveChassisSpeeds(speeds); + }, + pathplanner::HolonomicPathFollowerConfig{ + constants::drive::pathTranslationalConstants, + constants::drive::pathRotationalConstants, + constants::drive::maxModuleSpeed, drive->getMaxDriveRadius(), + pathplanner::ReplanningConfig(), constants::robotLoopTime}, + []() { + // Plan all autos on the blue side + auto alliance = frc::DriverStation::GetAlliance(); + if (alliance) { + return alliance.value() == frc::DriverStation::Alliance::kRed; + } + return false; + }, + this); } void DriveSubsystem::odometryThreadMain() { while (true) { frc::Pose2d newPose = drive->updatePose(); + frc::ChassisSpeeds newChassisSpeeds = drive->getChassisSpeeds(); { - std::lock_guard lock(currentPoseContainer.mutex); + std::lock_guard lock(currentPoseContainer.poseMutex); currentPoseContainer._pose = newPose; } + + { + + std::lock_guard lock(currentPoseContainer.chassisSpeedsMutex); + currentPoseContainer._chassisSpeeds = newChassisSpeeds; + } std::this_thread::yield(); } } +frc::ChassisSpeeds DriveSubsystem::getChassisSpeedsEstimation() { + std::lock_guard lock(currentPoseContainer.chassisSpeedsMutex); + return currentPoseContainer._chassisSpeeds; +} + frc::Pose2d DriveSubsystem::getPoseEstimation() { - std::lock_guard lock(currentPoseContainer.mutex); + std::lock_guard lock(currentPoseContainer.poseMutex); return currentPoseContainer._pose; } +void DriveSubsystem::setPoseEstimation(frc::Pose2d pose) { + std::lock_guard lock(currentPoseContainer.poseMutex); + drive->resetPose(pose); + currentPoseContainer._pose = pose; +} + void DriveSubsystem::Periodic() { // Implementation of subsystem periodic method goes here. } diff --git a/src/subsystems/drive/DriveSubsystem.h b/src/subsystems/drive/DriveSubsystem.h index 89b0a67..62b5426 100644 --- a/src/subsystems/drive/DriveSubsystem.h +++ b/src/subsystems/drive/DriveSubsystem.h @@ -5,6 +5,7 @@ #pragma once #include "frc/geometry/Pose2d.h" +#include "frc/kinematics/ChassisSpeeds.h" #include "rmb/sensors/gyro.h" #include #include @@ -31,6 +32,9 @@ class DriveSubsystem : public frc2::SubsystemBase { frc2::CommandPtr driveTeleopCommand(double x, double y, double twist); frc::Pose2d getPoseEstimation(); + void setPoseEstimation(frc::Pose2d pose); + + frc::ChassisSpeeds getChassisSpeedsEstimation(); void stop(); @@ -49,6 +53,9 @@ class DriveSubsystem : public frc2::SubsystemBase { struct { frc::Pose2d _pose; - std::mutex mutex; + std::mutex poseMutex; + + frc::ChassisSpeeds _chassisSpeeds; + std::mutex chassisSpeedsMutex; } currentPoseContainer; }; From f2f9acfd241801b30492aefe3ca6df66501a1ea5 Mon Sep 17 00:00:00 2001 From: theVerySharpFlat Date: Mon, 29 Jan 2024 17:01:07 +0000 Subject: [PATCH 014/108] BOT: Apply Formatting --- src/RobotContainer.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/RobotContainer.cpp b/src/RobotContainer.cpp index 6631720..5804cba 100644 --- a/src/RobotContainer.cpp +++ b/src/RobotContainer.cpp @@ -11,8 +11,8 @@ #include "frc2/command/Commands.h" #include "frc2/command/RunCommand.h" -#include "pathplanner/lib/path/PathPlannerPath.h" #include "pathplanner/lib/auto/NamedCommands.h" +#include "pathplanner/lib/path/PathPlannerPath.h" #include "subsystems/drive/DriveSubsystem.h" RobotContainer::RobotContainer() : driveSubsystem(gyro) { From 47cd688d0d8175b75d75ac8a7d52a228abb01099 Mon Sep 17 00:00:00 2001 From: theVerySharpFlat Date: Thu, 1 Feb 2024 13:49:20 -0600 Subject: [PATCH 015/108] properly enforce postive y axis and counterclockwise rotation --- lib/src/rmb/drive/SwerveDrive.inl | 15 +++++++-------- 1 file changed, 7 insertions(+), 8 deletions(-) diff --git a/lib/src/rmb/drive/SwerveDrive.inl b/lib/src/rmb/drive/SwerveDrive.inl index 131c804..d7efce6 100644 --- a/lib/src/rmb/drive/SwerveDrive.inl +++ b/lib/src/rmb/drive/SwerveDrive.inl @@ -153,11 +153,12 @@ void SwerveDrive::driveCartesian(double xSpeed, double ySpeed, * from the center * * And we define our perpendicular functions as - * perpendicular(x, y) => (y, -x) + * perpendicular(x, y) => (-y, x) + * to enforce a counterclockwise positive angle * * so, - * output_x = vx * 1 + vy * 0 + w * y - * output_y = vx * 0 + vy * 1 + w * -x + * output_x = vx * 1 + vy * 0 + w * -y + * output_y = vx * 0 + vy * 1 + w * x */ std::array powers; @@ -168,16 +169,14 @@ void SwerveDrive::driveCartesian(double xSpeed, double ySpeed, double output_x = robotRelativeVXY.x() + - zRotation * module.getModuleTranslation().Y() / largestModuleDistance; + zRotation * -(module.getModuleTranslation().Y() / largestModuleDistance); double output_y = robotRelativeVXY.y() + - zRotation * -module.getModuleTranslation().X() / largestModuleDistance; + zRotation * module.getModuleTranslation().X() / largestModuleDistance; - // Enforce a forward-facing 0_deg that increases in the counterclockwise - // direction frc::Rotation2d moduleRotation = - -1.0 * frc::Rotation2d(output_x, output_y).Radians(); + frc::Rotation2d(output_x, output_y).Radians(); double modulePower = std::sqrt(output_x * output_x + output_y * output_y); powers[i] = SwerveModulePower{modulePower, moduleRotation}; From 4c500d929da4f22b8d0a012290c75632c72c117c Mon Sep 17 00:00:00 2001 From: theVerySharpFlat Date: Thu, 1 Feb 2024 13:49:49 -0600 Subject: [PATCH 016/108] change deploy dir --- build.gradle | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/build.gradle b/build.gradle index 3cd3344..6897d99 100644 --- a/build.gradle +++ b/build.gradle @@ -30,7 +30,7 @@ deploy { // Static files artifact frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) { - files = project.fileTree('src/deploy') + files = project.fileTree('src/main/deploy') directory = '/home/lvuser/deploy' } } From 288fc38525681e42063148bcba9274fefd6087a5 Mon Sep 17 00:00:00 2001 From: theVerySharpFlat Date: Thu, 1 Feb 2024 13:51:49 -0600 Subject: [PATCH 017/108] switch over to autos instead of paths --- .pathplanner/settings.json | 12 ++ src/RobotContainer.cpp | 27 +++-- src/RobotContainer.h | 12 +- src/deploy/example.txt | 4 - .../deploy/pathplanner/autos/New Auto.auto | 31 +++++ .../pathplanner/autos/Ring-amp direct.auto | 31 +++++ src/main/deploy/pathplanner/navgrid.json | 2 +- .../{Example Path.path => Move to ring.path} | 26 ++-- .../pathplanner/paths/Roundabout amp.path | 113 ++++++++++++++++++ .../paths/{New Path.path => move to amp.path} | 34 ++---- 10 files changed, 238 insertions(+), 54 deletions(-) create mode 100644 .pathplanner/settings.json delete mode 100644 src/deploy/example.txt create mode 100644 src/main/deploy/pathplanner/autos/New Auto.auto create mode 100644 src/main/deploy/pathplanner/autos/Ring-amp direct.auto rename src/main/deploy/pathplanner/paths/{Example Path.path => Move to ring.path} (70%) create mode 100644 src/main/deploy/pathplanner/paths/Roundabout amp.path rename src/main/deploy/pathplanner/paths/{New Path.path => move to amp.path} (56%) diff --git a/.pathplanner/settings.json b/.pathplanner/settings.json new file mode 100644 index 0000000..e5e0d93 --- /dev/null +++ b/.pathplanner/settings.json @@ -0,0 +1,12 @@ +{ + "robotWidth": 0.9, + "robotLength": 0.9, + "holonomicMode": true, + "pathFolders": [], + "autoFolders": [], + "defaultMaxVel": 10.0, + "defaultMaxAccel": 3.0, + "defaultMaxAngVel": 540.0, + "defaultMaxAngAccel": 720.0, + "maxModuleSpeed": 10.0 +} \ No newline at end of file diff --git a/src/RobotContainer.cpp b/src/RobotContainer.cpp index 5804cba..55c6d7f 100644 --- a/src/RobotContainer.cpp +++ b/src/RobotContainer.cpp @@ -9,9 +9,11 @@ #include #include +#include "frc/smartdashboard/SmartDashboard.h" #include "frc2/command/Commands.h" #include "frc2/command/RunCommand.h" #include "pathplanner/lib/auto/NamedCommands.h" +#include "pathplanner/lib/commands/PathPlannerAuto.h" #include "pathplanner/lib/path/PathPlannerPath.h" #include "subsystems/drive/DriveSubsystem.h" @@ -35,26 +37,37 @@ void RobotContainer::ConfigureBindings() { // m_driverController.B().WhileTrue(m_subsystem.ExampleMethodCommand()); } -void RobotContainer::loadPPPaths() { +void RobotContainer::loadPPAutos() { std::string pathDir = - frc::filesystem::GetDeployDirectory() + "/pathplanner/paths/"; + frc::filesystem::GetDeployDirectory() + "/pathplanner/autos/"; for (const auto &entry : std::filesystem::directory_iterator(pathDir)) { - if (entry.is_regular_file() && entry.path().extension() == ".path") { - paths[entry.path().stem()] = - pathplanner::PathPlannerPath::fromPathFile(entry.path().stem()); + if (entry.is_regular_file() && + entry.path().extension().string() == ".auto") { + autoCommands[entry.path().stem().string()] = + pathplanner::PathPlannerAuto(entry.path().stem().string()).ToPtr(); } } + for (const auto &kv : autoCommands) { + autonomousChooser.AddOption(kv.first, kv.first); + } + // Register named commands here // with // pathplanner::NamedCommands::registerCommand() } -frc2::CommandPtr RobotContainer::GetAutonomousCommand() { +frc2::CommandPtr &RobotContainer::GetAutonomousCommand() { // An example command will be run in autonomous // return autos::ExampleAuto(&m_subsystem); - return frc2::cmd::None(); + // + static auto noCommand = frc2::cmd::None(); + + if (!autonomousChooser.GetSelected().empty()) { + return autoCommands[autonomousChooser.GetSelected()]; + } + return noCommand; } void RobotContainer::setTeleopDefaults() { diff --git a/src/RobotContainer.h b/src/RobotContainer.h index d5997df..e6dd1ee 100644 --- a/src/RobotContainer.h +++ b/src/RobotContainer.h @@ -7,6 +7,8 @@ #include #include +#include + #include "Constants.h" #include "rmb/controller/LogitechGamepad.h" #include "rmb/sensors/AHRS/AHRSGyro.h" @@ -25,12 +27,12 @@ class RobotContainer { public: RobotContainer(); - frc2::CommandPtr GetAutonomousCommand(); + frc2::CommandPtr& GetAutonomousCommand(); void setTeleopDefaults(); void setAutoDefaults(); - void loadPPPaths(); + void loadPPAutos(); private: // Replace with CommandPS4Controller or CommandJoystick if needed @@ -46,6 +48,8 @@ class RobotContainer { void ConfigureBindings(); - std::unordered_map> - paths; + std::unordered_map + autoCommands; + + frc::SendableChooser autonomousChooser; }; diff --git a/src/deploy/example.txt b/src/deploy/example.txt deleted file mode 100644 index 6839539..0000000 --- a/src/deploy/example.txt +++ /dev/null @@ -1,4 +0,0 @@ -Files placed in this directory will be deployed to the RoboRIO into the - 'deploy' directory in the home folder. Use the 'frc::filesystem::GetDeployDirectory' - function from the 'frc/Filesystem.h' header to get a proper path relative to the deploy - directory. \ No newline at end of file diff --git a/src/main/deploy/pathplanner/autos/New Auto.auto b/src/main/deploy/pathplanner/autos/New Auto.auto new file mode 100644 index 0000000..9036351 --- /dev/null +++ b/src/main/deploy/pathplanner/autos/New Auto.auto @@ -0,0 +1,31 @@ +{ + "version": 1.0, + "startingPose": null, + "command": { + "type": "sequential", + "data": { + "commands": [ + { + "type": "path", + "data": { + "pathName": "Move to ring" + } + }, + { + "type": "named", + "data": { + "name": "Pick Up Ring" + } + }, + { + "type": "path", + "data": { + "pathName": "Roundabout amp" + } + } + ] + } + }, + "folder": null, + "choreoAuto": false +} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/autos/Ring-amp direct.auto b/src/main/deploy/pathplanner/autos/Ring-amp direct.auto new file mode 100644 index 0000000..b4727e0 --- /dev/null +++ b/src/main/deploy/pathplanner/autos/Ring-amp direct.auto @@ -0,0 +1,31 @@ +{ + "version": 1.0, + "startingPose": { + "position": { + "x": 2, + "y": 2 + }, + "rotation": 0 + }, + "command": { + "type": "sequential", + "data": { + "commands": [ + { + "type": "path", + "data": { + "pathName": "Move to ring" + } + }, + { + "type": "path", + "data": { + "pathName": "move to amp" + } + } + ] + } + }, + "folder": null, + "choreoAuto": false +} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/navgrid.json b/src/main/deploy/pathplanner/navgrid.json index bab0da9..d7877eb 100644 --- a/src/main/deploy/pathplanner/navgrid.json +++ b/src/main/deploy/pathplanner/navgrid.json @@ -1 +1 @@ -{"field_size":{"x":16.54,"y":8.21},"nodeSizeMeters":0.3,"grid":[[true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true],[true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true],[true,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true],[true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,true,true,true],[true,true,true,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,true,true,true,true],[true,true,true,true,false,false,false,false,false,false,true,true,true,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,true,true,true,false,false,false,false,false,false,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true],[true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true],[true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true],[true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true],[true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true]]} \ No newline at end of file +{"field_size":{"x":16.54,"y":8.21},"nodeSizeMeters":0.3,"grid":[[true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true],[true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true],[true,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true],[true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,true,true,true],[true,true,true,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,true,true,true,true],[true,true,true,true,false,false,false,false,false,false,true,true,true,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,true,true,true,false,false,false,false,false,false,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true],[true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true],[true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true],[true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true],[true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true]]} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/paths/Example Path.path b/src/main/deploy/pathplanner/paths/Move to ring.path similarity index 70% rename from src/main/deploy/pathplanner/paths/Example Path.path rename to src/main/deploy/pathplanner/paths/Move to ring.path index 8aebdad..0073606 100644 --- a/src/main/deploy/pathplanner/paths/Example Path.path +++ b/src/main/deploy/pathplanner/paths/Move to ring.path @@ -3,25 +3,25 @@ "waypoints": [ { "anchor": { - "x": 3.0, - "y": 7.0 + "x": 1.2073755397510797, + "y": 2.1677079511566437 }, "prevControl": null, "nextControl": { - "x": 3.9566940893141047, - "y": 7.004446772782435 + "x": 2.0553352139506273, + "y": 2.219170453155725 }, "isLocked": false, "linkedName": null }, { "anchor": { - "x": 6.0, - "y": 7.0 + "x": 2.891991575649818, + "y": 3.04451829274029 }, "prevControl": { - "x": 5.296976201602062, - "y": 7.0 + "x": 2.9148901918174204, + "y": 2.6256683976330923 }, "nextControl": null, "isLocked": false, @@ -33,7 +33,7 @@ "eventMarkers": [ { "name": "New Event Marker", - "waypointRelativePos": 0.4, + "waypointRelativePos": 0.2, "command": { "type": "sequential", "data": { @@ -50,18 +50,18 @@ } ], "globalConstraints": { - "maxVelocity": 3.0, + "maxVelocity": 10.0, "maxAcceleration": 3.0, "maxAngularVelocity": 540.0, "maxAngularAcceleration": 720.0 }, "goalEndState": { "velocity": 0, - "rotation": 0, - "rotateFast": false + "rotation": 90.31903243749512, + "rotateFast": true }, "reversed": false, "folder": null, "previewStartingState": null, - "useDefaultConstraints": false + "useDefaultConstraints": true } \ No newline at end of file diff --git a/src/main/deploy/pathplanner/paths/Roundabout amp.path b/src/main/deploy/pathplanner/paths/Roundabout amp.path new file mode 100644 index 0000000..bdd5f98 --- /dev/null +++ b/src/main/deploy/pathplanner/paths/Roundabout amp.path @@ -0,0 +1,113 @@ +{ + "version": 1.0, + "waypoints": [ + { + "anchor": { + "x": 2.863232737156263, + "y": 3.382284132989319 + }, + "prevControl": null, + "nextControl": { + "x": 2.8739922488068657, + "y": 2.1873981700266034 + }, + "isLocked": false, + "linkedName": null + }, + { + "anchor": { + "x": 4.861601055438952, + "y": 1.7888742973209637 + }, + "prevControl": { + "x": 4.280587426306431, + "y": 1.8163532461933347 + }, + "nextControl": { + "x": 5.372383264036966, + "y": 1.764716932517082 + }, + "isLocked": false, + "linkedName": null + }, + { + "anchor": { + "x": 6.776952357358661, + "y": 2.9417770677646624 + }, + "prevControl": { + "x": 6.671519691723594, + "y": 1.6887159021028564 + }, + "nextControl": { + "x": 6.82290320400338, + "y": 3.4879002366417096 + }, + "isLocked": false, + "linkedName": null + }, + { + "anchor": { + "x": 6.776952357358661, + "y": 5.194417962849084 + }, + "prevControl": { + "x": 6.903956788999103, + "y": 4.872792952822747 + }, + "nextControl": { + "x": 6.595238985705875, + "y": 5.654587456345218 + }, + "isLocked": false, + "linkedName": null + }, + { + "anchor": { + "x": 4.861601055438952, + "y": 6.491888485421708 + }, + "prevControl": { + "x": 6.321202650628985, + "y": 5.752224802146974 + }, + "nextControl": { + "x": 4.042439479226521, + "y": 6.907004549048329 + }, + "isLocked": false, + "linkedName": null + }, + { + "anchor": { + "x": 1.9298451014665183, + "y": 7.093049827547024 + }, + "prevControl": { + "x": 2.435542149044824, + "y": 7.053229085898961 + }, + "nextControl": null, + "isLocked": false, + "linkedName": null + } + ], + "rotationTargets": [], + "constraintZones": [], + "eventMarkers": [], + "globalConstraints": { + "maxVelocity": 10.0, + "maxAcceleration": 3.0, + "maxAngularVelocity": 540.0, + "maxAngularAcceleration": 720.0 + }, + "goalEndState": { + "velocity": 0, + "rotation": 89.9506070988623, + "rotateFast": true + }, + "reversed": false, + "folder": null, + "previewStartingState": null, + "useDefaultConstraints": true +} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/paths/New Path.path b/src/main/deploy/pathplanner/paths/move to amp.path similarity index 56% rename from src/main/deploy/pathplanner/paths/New Path.path rename to src/main/deploy/pathplanner/paths/move to amp.path index 8eb50ac..d2469de 100644 --- a/src/main/deploy/pathplanner/paths/New Path.path +++ b/src/main/deploy/pathplanner/paths/move to amp.path @@ -3,41 +3,25 @@ "waypoints": [ { "anchor": { - "x": 7.562929213821391, - "y": 3.9206754061656275 + "x": 1.9518774870883078, + "y": 4.022460230105646 }, "prevControl": null, "nextControl": { - "x": 8.562929213821379, - "y": 3.4206754061656275 + "x": 1.9704198103134507, + "y": 4.708945272886728 }, "isLocked": false, "linkedName": null }, { "anchor": { - "x": 9.429202062107828, - "y": 2.055649629817778 + "x": 1.8418382346004207, + "y": 7.13895238901916 }, "prevControl": { - "x": 8.429202062107828, - "y": 3.0556496298177787 - }, - "nextControl": { - "x": 10.429202062107828, - "y": 1.0556496298177782 - }, - "isLocked": false, - "linkedName": null - }, - { - "anchor": { - "x": 7.0, - "y": 1.0 - }, - "prevControl": { - "x": 6.75, - "y": 2.5 + "x": 1.8134106633084803, + "y": 6.280026045778995 }, "nextControl": null, "isLocked": false, @@ -55,7 +39,7 @@ }, "goalEndState": { "velocity": 0, - "rotation": 0, + "rotation": 90.0, "rotateFast": false }, "reversed": false, From 784570c959678340bcd6a8a9b05ec82d7be1e467 Mon Sep 17 00:00:00 2001 From: theVerySharpFlat Date: Thu, 1 Feb 2024 19:57:51 +0000 Subject: [PATCH 018/108] BOT: Apply Formatting --- lib/src/rmb/drive/SwerveDrive.inl | 4 ++-- src/RobotContainer.h | 5 ++--- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/lib/src/rmb/drive/SwerveDrive.inl b/lib/src/rmb/drive/SwerveDrive.inl index d7efce6..c734a41 100644 --- a/lib/src/rmb/drive/SwerveDrive.inl +++ b/lib/src/rmb/drive/SwerveDrive.inl @@ -168,8 +168,8 @@ void SwerveDrive::driveCartesian(double xSpeed, double ySpeed, SwerveModule &module = modules[i]; double output_x = - robotRelativeVXY.x() + - zRotation * -(module.getModuleTranslation().Y() / largestModuleDistance); + robotRelativeVXY.x() + zRotation * -(module.getModuleTranslation().Y() / + largestModuleDistance); double output_y = robotRelativeVXY.y() + diff --git a/src/RobotContainer.h b/src/RobotContainer.h index e6dd1ee..09ebc55 100644 --- a/src/RobotContainer.h +++ b/src/RobotContainer.h @@ -27,7 +27,7 @@ class RobotContainer { public: RobotContainer(); - frc2::CommandPtr& GetAutonomousCommand(); + frc2::CommandPtr &GetAutonomousCommand(); void setTeleopDefaults(); void setAutoDefaults(); @@ -48,8 +48,7 @@ class RobotContainer { void ConfigureBindings(); - std::unordered_map - autoCommands; + std::unordered_map autoCommands; frc::SendableChooser autonomousChooser; }; From c09ef87f17a0e3be6ab56a2b02615e268f52be26 Mon Sep 17 00:00:00 2001 From: theVerySharpFlat Date: Thu, 1 Feb 2024 14:12:38 -0600 Subject: [PATCH 019/108] fix autonomousCommand type issue --- src/Robot.cpp | 7 ++++--- src/Robot.h | 2 +- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/src/Robot.cpp b/src/Robot.cpp index edaf0e2..884e60f 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -5,6 +5,7 @@ #include "Robot.h" #include +#include void Robot::RobotInit() {} @@ -32,10 +33,10 @@ void Robot::DisabledPeriodic() {} * RobotContainer} class. */ void Robot::AutonomousInit() { - m_autonomousCommand = container.GetAutonomousCommand(); + m_autonomousCommand = &container.GetAutonomousCommand(); if (m_autonomousCommand) { - m_autonomousCommand->Schedule(); + m_autonomousCommand.value()->Schedule(); } // TODO: Check to see if we need to remove this @@ -50,7 +51,7 @@ void Robot::TeleopInit() { // continue until interrupted by another command, remove // this line or comment it out. if (m_autonomousCommand) { - m_autonomousCommand->Cancel(); + m_autonomousCommand.value()->Cancel(); } // TODO: Check to see if we need to remove this diff --git a/src/Robot.h b/src/Robot.h index ef21135..9c85aaf 100644 --- a/src/Robot.h +++ b/src/Robot.h @@ -30,7 +30,7 @@ class Robot : public frc::TimedRobot { private: // Have it empty by default so that if testing teleop it // doesn't have undefined behavior and potentially crash. - std::optional m_autonomousCommand; + std::optional m_autonomousCommand = std::nullopt; RobotContainer container; }; From b184ce9dd0b4d3d27bdd8569499c07d29a25694d Mon Sep 17 00:00:00 2001 From: theVerySharpFlat Date: Thu, 1 Feb 2024 20:18:26 +0000 Subject: [PATCH 020/108] BOT: Apply Formatting --- src/Robot.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/Robot.h b/src/Robot.h index 9c85aaf..850b55d 100644 --- a/src/Robot.h +++ b/src/Robot.h @@ -30,7 +30,7 @@ class Robot : public frc::TimedRobot { private: // Have it empty by default so that if testing teleop it // doesn't have undefined behavior and potentially crash. - std::optional m_autonomousCommand = std::nullopt; + std::optional m_autonomousCommand = std::nullopt; RobotContainer container; }; From 96fefe900fb0aa6427cd331416cd44d9df871d4b Mon Sep 17 00:00:00 2001 From: theVerySharpFlat Date: Thu, 1 Feb 2024 23:24:58 -0600 Subject: [PATCH 021/108] avoid frc2::CommandPtr default constructor --- src/Robot.cpp | 11 +---------- src/RobotContainer.cpp | 20 +++++++++++--------- src/RobotContainer.h | 2 +- 3 files changed, 13 insertions(+), 20 deletions(-) diff --git a/src/Robot.cpp b/src/Robot.cpp index 884e60f..6af72da 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -32,16 +32,7 @@ void Robot::DisabledPeriodic() {} * This autonomous runs the autonomous command selected by your {@link * RobotContainer} class. */ -void Robot::AutonomousInit() { - m_autonomousCommand = &container.GetAutonomousCommand(); - - if (m_autonomousCommand) { - m_autonomousCommand.value()->Schedule(); - } - - // TODO: Check to see if we need to remove this - frc2::CommandScheduler::GetInstance().CancelAll(); -} +void Robot::AutonomousInit() { container.RunAutonomousCommand(); } void Robot::AutonomousPeriodic() {} diff --git a/src/RobotContainer.cpp b/src/RobotContainer.cpp index 55c6d7f..db09874 100644 --- a/src/RobotContainer.cpp +++ b/src/RobotContainer.cpp @@ -4,6 +4,7 @@ #include "RobotContainer.h" +#include #include #include @@ -44,8 +45,9 @@ void RobotContainer::loadPPAutos() { for (const auto &entry : std::filesystem::directory_iterator(pathDir)) { if (entry.is_regular_file() && entry.path().extension().string() == ".auto") { - autoCommands[entry.path().stem().string()] = - pathplanner::PathPlannerAuto(entry.path().stem().string()).ToPtr(); + autoCommands.insert( + {entry.path().stem().string(), + pathplanner::PathPlannerAuto(entry.path().stem().string()).ToPtr()}); } } @@ -58,16 +60,16 @@ void RobotContainer::loadPPAutos() { // pathplanner::NamedCommands::registerCommand() } -frc2::CommandPtr &RobotContainer::GetAutonomousCommand() { - // An example command will be run in autonomous - // return autos::ExampleAuto(&m_subsystem); - // - static auto noCommand = frc2::cmd::None(); +void RobotContainer::RunAutonomousCommand() { if (!autonomousChooser.GetSelected().empty()) { - return autoCommands[autonomousChooser.GetSelected()]; + try { + autoCommands.at(autonomousChooser.GetSelected()).Schedule(); + } catch (const std::exception &_e) { + std::cout << "Error: no such command \"" + << autonomousChooser.GetSelected() << "\"" << std::endl; + } } - return noCommand; } void RobotContainer::setTeleopDefaults() { diff --git a/src/RobotContainer.h b/src/RobotContainer.h index 09ebc55..992d959 100644 --- a/src/RobotContainer.h +++ b/src/RobotContainer.h @@ -27,7 +27,7 @@ class RobotContainer { public: RobotContainer(); - frc2::CommandPtr &GetAutonomousCommand(); + void RunAutonomousCommand(); void setTeleopDefaults(); void setAutoDefaults(); From ff3acd265fdb9ccb808d9383d9ed8956d98b0ff3 Mon Sep 17 00:00:00 2001 From: theVerySharpFlat Date: Sun, 4 Feb 2024 01:03:50 -0600 Subject: [PATCH 022/108] delete uneeded directory --- lib/librmb-main/.editorconfig | 17 - .../.github/workflows/doxygen-publish.yml | 23 - lib/librmb-main/.github/workflows/merge.yml | 88 - lib/librmb-main/.github/workflows/pr.yml | 40 - lib/librmb-main/.gitignore | 197 -- lib/librmb-main/.gitpod.yml | 8 - .../.wpilib/wpilib_preferences.json | 6 - lib/librmb-main/LICENSE | 21 - lib/librmb-main/README.md | 24 - lib/librmb-main/build.gradle | 100 - lib/librmb-main/build.old.gradle | 90 - lib/librmb-main/config.gradle | 179 -- lib/librmb-main/docs/Doxyfile | 2646 ----------------- .../docs/additional/pancakerecipe.md | 39 - lib/librmb-main/docs/building.md | 37 - lib/librmb-main/docs/doxygen-awesome.css | 1524 ---------- lib/librmb-main/docs/doxygen.h | 33 - lib/librmb-main/docs/errors.out | 379 --- lib/librmb-main/docs/favicon.png | Bin 4106 -> 0 bytes lib/librmb-main/docs/mainpage.md | 9 - .../gradle/wrapper/gradle-wrapper.jar | Bin 61574 -> 0 bytes .../gradle/wrapper/gradle-wrapper.properties | 6 - lib/librmb-main/gradlew | 244 -- lib/librmb-main/gradlew.bat | 92 - lib/librmb-main/publish.gradle | 288 -- .../scripts/find-not-documented.sh | 3 - lib/librmb-main/scripts/rioCDGen.py | 153 - lib/librmb-main/settings.gradle | 55 - .../src/rmb/controller/LogitechGamepad.h | 233 -- .../src/rmb/controller/LogitechJoystick.h | 90 - lib/librmb-main/src/rmb/drive/BaseDrive.cpp | 178 -- lib/librmb-main/src/rmb/drive/BaseDrive.h | 293 -- .../src/rmb/drive/DifferentialDrive.cpp | 187 -- .../src/rmb/drive/DifferentialDrive.h | 288 -- lib/librmb-main/src/rmb/drive/SwerveDrive.cpp | 5 - lib/librmb-main/src/rmb/drive/SwerveDrive.h | 305 -- lib/librmb-main/src/rmb/drive/SwerveDrive.inc | 243 -- lib/librmb-main/src/rmb/drive/SwerveDrive.inl | 421 --- .../src/rmb/drive/SwerveModule.cpp | 127 - lib/librmb-main/src/rmb/drive/SwerveModule.h | 161 - .../motorcontrol/AngularPositionController.h | 137 - .../motorcontrol/AngularVelocityController.h | 133 - .../src/rmb/motorcontrol/Conversions.cpp | 248 -- .../motorcontrol/LinearPositionController.h | 144 - .../motorcontrol/LinearVelocityController.h | 129 - .../motorcontrol/ServoPositionController.h | 90 - .../Talon/TalonFXPositionController.cpp | 181 -- .../Talon/TalonFXPositionController.h | 255 -- .../Talon/TalonFXVelocityController.cpp | 180 -- .../Talon/TalonFXVelocityController.h | 143 - .../AngularFeedforwardController.h | 103 - .../motorcontrol/feedforward/ArmFeedforward.h | 178 -- .../feedforward/ElevatorFeedforward.h | 171 -- .../motorcontrol/feedforward/Feedforward.h | 147 - .../feedforward/LinearFeedforwardController.h | 103 - .../feedforward/SimpleFeedforward.h | 172 -- .../src/rmb/motorcontrol/math/misc.h | 45 - .../sparkmax/SparkMaxPositionController.cpp | 241 -- .../sparkmax/SparkMaxPositionController.h | 198 -- .../sparkmax/SparkMaxVelocityController.cpp | 232 -- .../sparkmax/SparkMaxVelocityController.h | 175 -- .../src/rmb/sensors/AHRS/AHRSGyro.cpp | 44 - .../src/rmb/sensors/AHRS/AHRSGyro.h | 32 - lib/librmb-main/src/rmb/sensors/gyro.h | 27 - lib/librmb-main/testbench/.gitignore | 172 -- .../testbench/.pathplanner/settings.json | 14 - .../testbench/.wpilib/wpilib_preferences.json | 6 - lib/librmb-main/testbench/WPILib-License.md | 24 - lib/librmb-main/testbench/build.gradle | 100 - .../gradle/wrapper/gradle-wrapper.jar | Bin 60756 -> 0 bytes .../gradle/wrapper/gradle-wrapper.properties | 5 - lib/librmb-main/testbench/gradlew | 240 -- lib/librmb-main/testbench/gradlew.bat | 91 - lib/librmb-main/testbench/rioCDGen.py | 149 - lib/librmb-main/testbench/settings.gradle | 27 - lib/librmb-main/testbench/src/Constants.h | 159 - lib/librmb-main/testbench/src/Robot.cpp | 135 - lib/librmb-main/testbench/src/Robot.h | 59 - .../testbench/src/RobotContainer.cpp | 17 - .../testbench/src/RobotContainer.h | 17 - .../testbench/src/deploy/example.txt | 4 - .../src/main/deploy/pathplanner/navgrid.json | 1 - .../deploy/pathplanner/paths/bruhPath.path | 121 - .../testbench/vendordeps/NavX.json | 40 - .../testbench/vendordeps/PathplannerLib.json | 38 - .../vendordeps/Phoenix6-frc2024-latest.json | 339 --- .../testbench/vendordeps/REVLib-2024.json | 74 - .../vendordeps/WPILibNewCommands.json | 38 - lib/librmb-main/vendordeps/NavX.json | 40 - .../vendordeps/PathplannerLib.json | 38 - .../vendordeps/Phoenix6-frc2024-latest.json | 339 --- lib/librmb-main/vendordeps/REVLib-2024.json | 74 - .../vendordeps/WPILibNewCommands.json | 38 - 93 files changed, 14739 deletions(-) delete mode 100644 lib/librmb-main/.editorconfig delete mode 100644 lib/librmb-main/.github/workflows/doxygen-publish.yml delete mode 100644 lib/librmb-main/.github/workflows/merge.yml delete mode 100644 lib/librmb-main/.github/workflows/pr.yml delete mode 100644 lib/librmb-main/.gitignore delete mode 100644 lib/librmb-main/.gitpod.yml delete mode 100644 lib/librmb-main/.wpilib/wpilib_preferences.json delete mode 100644 lib/librmb-main/LICENSE delete mode 100644 lib/librmb-main/README.md delete mode 100644 lib/librmb-main/build.gradle delete mode 100644 lib/librmb-main/build.old.gradle delete mode 100644 lib/librmb-main/config.gradle delete mode 100644 lib/librmb-main/docs/Doxyfile delete mode 100644 lib/librmb-main/docs/additional/pancakerecipe.md delete mode 100644 lib/librmb-main/docs/building.md delete mode 100644 lib/librmb-main/docs/doxygen-awesome.css delete mode 100644 lib/librmb-main/docs/doxygen.h delete mode 100644 lib/librmb-main/docs/errors.out delete mode 100644 lib/librmb-main/docs/favicon.png delete mode 100644 lib/librmb-main/docs/mainpage.md delete mode 100644 lib/librmb-main/gradle/wrapper/gradle-wrapper.jar delete mode 100644 lib/librmb-main/gradle/wrapper/gradle-wrapper.properties delete mode 100755 lib/librmb-main/gradlew delete mode 100644 lib/librmb-main/gradlew.bat delete mode 100644 lib/librmb-main/publish.gradle delete mode 100755 lib/librmb-main/scripts/find-not-documented.sh delete mode 100755 lib/librmb-main/scripts/rioCDGen.py delete mode 100644 lib/librmb-main/settings.gradle delete mode 100644 lib/librmb-main/src/rmb/controller/LogitechGamepad.h delete mode 100644 lib/librmb-main/src/rmb/controller/LogitechJoystick.h delete mode 100644 lib/librmb-main/src/rmb/drive/BaseDrive.cpp delete mode 100644 lib/librmb-main/src/rmb/drive/BaseDrive.h delete mode 100644 lib/librmb-main/src/rmb/drive/DifferentialDrive.cpp delete mode 100644 lib/librmb-main/src/rmb/drive/DifferentialDrive.h delete mode 100644 lib/librmb-main/src/rmb/drive/SwerveDrive.cpp delete mode 100644 lib/librmb-main/src/rmb/drive/SwerveDrive.h delete mode 100644 lib/librmb-main/src/rmb/drive/SwerveDrive.inc delete mode 100644 lib/librmb-main/src/rmb/drive/SwerveDrive.inl delete mode 100644 lib/librmb-main/src/rmb/drive/SwerveModule.cpp delete mode 100644 lib/librmb-main/src/rmb/drive/SwerveModule.h delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/AngularPositionController.h delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/AngularVelocityController.h delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/Conversions.cpp delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/LinearPositionController.h delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/LinearVelocityController.h delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/ServoPositionController.h delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/Talon/TalonFXPositionController.cpp delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/Talon/TalonFXPositionController.h delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/Talon/TalonFXVelocityController.cpp delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/Talon/TalonFXVelocityController.h delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/feedforward/AngularFeedforwardController.h delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/feedforward/ArmFeedforward.h delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/feedforward/ElevatorFeedforward.h delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/feedforward/Feedforward.h delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/feedforward/LinearFeedforwardController.h delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/feedforward/SimpleFeedforward.h delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/math/misc.h delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/sparkmax/SparkMaxPositionController.cpp delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/sparkmax/SparkMaxPositionController.h delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/sparkmax/SparkMaxVelocityController.cpp delete mode 100644 lib/librmb-main/src/rmb/motorcontrol/sparkmax/SparkMaxVelocityController.h delete mode 100644 lib/librmb-main/src/rmb/sensors/AHRS/AHRSGyro.cpp delete mode 100644 lib/librmb-main/src/rmb/sensors/AHRS/AHRSGyro.h delete mode 100644 lib/librmb-main/src/rmb/sensors/gyro.h delete mode 100644 lib/librmb-main/testbench/.gitignore delete mode 100644 lib/librmb-main/testbench/.pathplanner/settings.json delete mode 100644 lib/librmb-main/testbench/.wpilib/wpilib_preferences.json delete mode 100644 lib/librmb-main/testbench/WPILib-License.md delete mode 100644 lib/librmb-main/testbench/build.gradle delete mode 100644 lib/librmb-main/testbench/gradle/wrapper/gradle-wrapper.jar delete mode 100644 lib/librmb-main/testbench/gradle/wrapper/gradle-wrapper.properties delete mode 100755 lib/librmb-main/testbench/gradlew delete mode 100644 lib/librmb-main/testbench/gradlew.bat delete mode 100644 lib/librmb-main/testbench/rioCDGen.py delete mode 100644 lib/librmb-main/testbench/settings.gradle delete mode 100644 lib/librmb-main/testbench/src/Constants.h delete mode 100644 lib/librmb-main/testbench/src/Robot.cpp delete mode 100644 lib/librmb-main/testbench/src/Robot.h delete mode 100644 lib/librmb-main/testbench/src/RobotContainer.cpp delete mode 100644 lib/librmb-main/testbench/src/RobotContainer.h delete mode 100644 lib/librmb-main/testbench/src/deploy/example.txt delete mode 100644 lib/librmb-main/testbench/src/main/deploy/pathplanner/navgrid.json delete mode 100644 lib/librmb-main/testbench/src/main/deploy/pathplanner/paths/bruhPath.path delete mode 100644 lib/librmb-main/testbench/vendordeps/NavX.json delete mode 100644 lib/librmb-main/testbench/vendordeps/PathplannerLib.json delete mode 100644 lib/librmb-main/testbench/vendordeps/Phoenix6-frc2024-latest.json delete mode 100644 lib/librmb-main/testbench/vendordeps/REVLib-2024.json delete mode 100644 lib/librmb-main/testbench/vendordeps/WPILibNewCommands.json delete mode 100644 lib/librmb-main/vendordeps/NavX.json delete mode 100644 lib/librmb-main/vendordeps/PathplannerLib.json delete mode 100644 lib/librmb-main/vendordeps/Phoenix6-frc2024-latest.json delete mode 100644 lib/librmb-main/vendordeps/REVLib-2024.json delete mode 100644 lib/librmb-main/vendordeps/WPILibNewCommands.json diff --git a/lib/librmb-main/.editorconfig b/lib/librmb-main/.editorconfig deleted file mode 100644 index e85c364..0000000 --- a/lib/librmb-main/.editorconfig +++ /dev/null @@ -1,17 +0,0 @@ -# EditorConfig is awesome: https://EditorConfig.org - -# top-most EditorConfig file -root = true - -# Unix-style newlines with a newline ending every file -[*] -end_of_line = lf -insert_final_newline = true -charset = utf-8 -indent_size = 2 -indent_style = space - -# 4 space indentation -[*.py] -indent_style = space -indent_size = 4 diff --git a/lib/librmb-main/.github/workflows/doxygen-publish.yml b/lib/librmb-main/.github/workflows/doxygen-publish.yml deleted file mode 100644 index 110ba64..0000000 --- a/lib/librmb-main/.github/workflows/doxygen-publish.yml +++ /dev/null @@ -1,23 +0,0 @@ -name: doxygen-publish - -on: - push: - branches: [ main ] - -jobs: - build: - runs-on: ubuntu-latest - - steps: - - uses: actions/checkout@v2 - - - name: Build documentation - uses: mattnotmitt/doxygen-action@v1.1.0 - with: - doxyfile-path: "./docs/Doxyfile" - - - name: Publish to GitHub Pages - uses: peaceiris/actions-gh-pages@v3 - with: - github_token: ${{ secrets.GITHUB_TOKEN }} - publish_dir: ./docs/html diff --git a/lib/librmb-main/.github/workflows/merge.yml b/lib/librmb-main/.github/workflows/merge.yml deleted file mode 100644 index 4f8a5ed..0000000 --- a/lib/librmb-main/.github/workflows/merge.yml +++ /dev/null @@ -1,88 +0,0 @@ -name: Run Gradle on Merge and publish -on: - push: - branches: - - main -jobs: - gradle: - strategy: - matrix: - os: [ubuntu-latest, macos-latest, windows-latest] - runs-on: ${{ matrix.os }} - steps: - - uses: actions/checkout@v4 - - uses: actions/setup-java@v4 - with: - distribution: temurin - java-version: 17 - - - name: Setup Gradle - uses: gradle/gradle-build-action@v2 - - - name: Install Toolchain - run: gradle installRoboRioToolchain - - - name: Execute Gradle build - run: gradle build - - - name: Publish - run: gradle publish - - - name: Upload a Build Artifact - if: ${{ matrix.os == 'ubuntu-latest' }} - uses: actions/upload-artifact@v4.0.0 - with: - name: LibRmb.json - path: build/LibRmb.json - - - name: Upload a Build Artifact - uses: actions/upload-artifact@v4.0.0 - with: - name: ${{ matrix.os }}-repo - path: build/repos - - publish: - needs: [gradle] - runs-on: ubuntu-latest - steps: - - uses: actions/checkout@v4 - with: - ref: 'maven-repo' - - name: Create archive dirs - run: mkdir -p archives/ubuntu-latest | - mkdir -p archives/macos-latest | - mkdir -p archives/windows-latest | - mkdir -p repos - - name: Download Linux Artifact - uses: actions/download-artifact@v4.1.0 - with: - name: ubuntu-latest-repo - path: archives/ubuntu-latest - - name: Download MacOS Artifact - uses: actions/download-artifact@v4.1.0 - with: - name: macos-latest-repo - path: archives/macos-latest - - name: Download Windows Artifact - uses: actions/download-artifact@v4.1.0 - with: - name: windows-latest-repo - path: archives/windows-latest - - - name: Download Vendordep Json - uses: actions/download-artifact@v4.1.0 - with: - name: LibRmb.json - - - name: Merge repos with rsync - run: rsync -aviuzP archives/ubuntu-latest/* ./repos | - rsync -aviuzP archives/macos-latest/* ./repos | - rsync -aviuzP archives/windows-latest/* ./repos - - - name: Clean - run: rm -rf archives - - - name: Commit - uses: stefanzweifel/git-auto-commit-action@v5 - with: - commit_message: "BOT: Update Repos" diff --git a/lib/librmb-main/.github/workflows/pr.yml b/lib/librmb-main/.github/workflows/pr.yml deleted file mode 100644 index 89a2a13..0000000 --- a/lib/librmb-main/.github/workflows/pr.yml +++ /dev/null @@ -1,40 +0,0 @@ -name: Run Gradle on PRs -on: pull_request -jobs: - format: - runs-on: ubuntu-latest - permissions: - contents: write - if: ${{ always() }} - needs: gradle - steps: - - uses: actions/checkout@v4 - - uses: DoozyX/clang-format-lint-action@v0.13 - with: - source: '.' - extensions: 'h,cpp,inl,inc' - style: llvm - inplace: true - - uses: stefanzweifel/git-auto-commit-action@v5 - with: - commit_message: "BOT: Apply Formatting" - gradle: - strategy: - matrix: - os: [ubuntu-latest, macos-latest, windows-latest] - runs-on: ${{ matrix.os }} - steps: - - uses: actions/checkout@v4 - - uses: actions/setup-java@v4 - with: - distribution: temurin - java-version: 17 - - - name: Setup Gradle - uses: gradle/gradle-build-action@v2 - - - name: Install Toolchain - run: gradle installRoboRioToolchain - - - name: Execute Gradle build - run: gradle build diff --git a/lib/librmb-main/.gitignore b/lib/librmb-main/.gitignore deleted file mode 100644 index 660cc20..0000000 --- a/lib/librmb-main/.gitignore +++ /dev/null @@ -1,197 +0,0 @@ -# This gitignore has been specially created by the WPILib team. -# If you remove items from this file, intellisense might break. - -### C++ ### -# Prerequisites -*.d - -# Compiled Object files -*.slo -*.lo -*.o -*.obj - -# Precompiled Headers -*.gch -*.pch - -# Compiled Dynamic libraries -*.so -*.dylib -*.dll - -# Fortran module files -*.mod -*.smod - -# Compiled Static libraries -*.lai -*.la -*.a -*.lib - -# Executables -*.exe -*.out -*.app - -### Java ### -# Compiled class file -*.class - -# Log file -*.log - -# BlueJ files -*.ctxt - -# Mobile Tools for Java (J2ME) -.mtj.tmp/ - -# Package Files # -*.jar -*.war -*.nar -*.ear -*.zip -*.tar.gz -*.rar - -# virtual machine crash logs, see http://www.java.com/en/download/help/error_hotspot.xml -hs_err_pid* - -### Linux ### -*~ - -# temporary files which can be created if a process still has a handle open of a deleted file -.fuse_hidden* - -# KDE directory preferences -.directory - -# Linux trash folder which might appear on any partition or disk -.Trash-* - -# .nfs files are created when an open file is removed but is still being accessed -.nfs* - -### macOS ### -# General -.DS_Store -.AppleDouble -.LSOverride -.history - -# Icon must end with two \r -Icon - -# Thumbnails -._* - -# Files that might appear in the root of a volume -.DocumentRevisions-V100 -.fseventsd -.Spotlight-V100 -.TemporaryItems -.Trashes -.VolumeIcon.icns -.com.apple.timemachine.donotpresent - -# Directories potentially created on remote AFP share -.AppleDB -.AppleDesktop -Network Trash Folder -Temporary Items -.apdisk - -### VisualStudioCode ### -.vscode/* -# !.vscode/settings.json -# !.vscode/tasks.json -# !.vscode/launch.json -# !.vscode/extensions.json - -### Windows ### -# Windows thumbnail cache files -Thumbs.db -ehthumbs.db -ehthumbs_vista.db - -# Dump file -*.stackdump - -# Folder config file -[Dd]esktop.ini - -# Recycle Bin used on file shares -$RECYCLE.BIN/ - -# Windows Installer files -*.cab -*.msi -*.msix -*.msm -*.msp - -# Windows shortcuts -*.lnk - -### Gradle ### -.gradle -build/ - -# Ignore Gradle GUI config -gradle-app.setting - -# Avoid ignoring Gradle wrapper jar file (.jar files are usually ignored) -!gradle-wrapper.jar - -# Cache of project -.gradletasknamecache - -# # Work around https://youtrack.jetbrains.com/issue/IDEA-116898 -# gradle/wrapper/gradle-wrapper.properties - -# # VS Code Specific Java Settings -# DO NOT REMOVE .classpath and .project -.classpath -.project -.settings/ -bin/ - -# Simulation GUI and other tools window save file -*-window.json - -########## -# CUSTOM # -########## - -# Vim temporary files -*~ -*.swp -*.swo - -# Doxygen-generated HTML docs -docs/* -!docs/additional -!docs/mainpage.md -!docs/doxygen-awesome.css -!docs/Doxyfile -!docs/favicon.png -!docs/favicon.png -!docs/building.md -!docs/errors.out -!docs/doxygen.h - -.idea/ -.cache/ - -.project.alt.json - -compile_commands.json -compile_flags.txt - -simgui*.json -networktables.json - -ctre_sim diff --git a/lib/librmb-main/.gitpod.yml b/lib/librmb-main/.gitpod.yml deleted file mode 100644 index e4709bf..0000000 --- a/lib/librmb-main/.gitpod.yml +++ /dev/null @@ -1,8 +0,0 @@ -# This configuration file was automatically generated by Gitpod. -# Please adjust to your needs (see https://www.gitpod.io/docs/config-gitpod-file) -# and commit this file to your remote git repository to share the goodness with others. - -tasks: - - init: ./gradlew installRoboRioToolchain && ./gradlew build - - diff --git a/lib/librmb-main/.wpilib/wpilib_preferences.json b/lib/librmb-main/.wpilib/wpilib_preferences.json deleted file mode 100644 index db3e62e..0000000 --- a/lib/librmb-main/.wpilib/wpilib_preferences.json +++ /dev/null @@ -1,6 +0,0 @@ -{ - "enableCppIntellisense": true, - "currentLanguage": "cpp", - "projectYear": "2022", - "teamNumber": 4330 -} \ No newline at end of file diff --git a/lib/librmb-main/LICENSE b/lib/librmb-main/LICENSE deleted file mode 100644 index e95b197..0000000 --- a/lib/librmb-main/LICENSE +++ /dev/null @@ -1,21 +0,0 @@ -MIT License - -Copyright (c) 2022 Rambunction 4330 - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. diff --git a/lib/librmb-main/README.md b/lib/librmb-main/README.md deleted file mode 100644 index 799c180..0000000 --- a/lib/librmb-main/README.md +++ /dev/null @@ -1,24 +0,0 @@ -

- -

- -

-

librmb

-

- -- - - - -

- - - - - -

- -- - - - -Utility library for FRC robots. The initial version was written by team 4330's 2022 season programming team. - -## Building -see https://rambunction4330.github.io/librmb/md_docs_building.html diff --git a/lib/librmb-main/build.gradle b/lib/librmb-main/build.gradle deleted file mode 100644 index ffc9a61..0000000 --- a/lib/librmb-main/build.gradle +++ /dev/null @@ -1,100 +0,0 @@ -plugins { - id 'cpp' - id 'java' - id 'edu.wpi.first.wpilib.repositories.WPILibRepositoriesPlugin' version '2020.2' - id 'edu.wpi.first.NativeUtils' version '2024.7.0' - id 'edu.wpi.first.GradleJni' version '1.0.0' -} - -sourceCompatibility = JavaVersion.VERSION_11 -targetCompatibility = JavaVersion.VERSION_11 - -repositories { - mavenCentral() -} - -wpilibRepositories.addAllReleaseRepositories(project) -// wpilibRepositories.addAllDevelopmentRepositories(project) - -// Apply C++ configuration -apply from: 'config.gradle' - -// Apply Java configuration -dependencies { -} - -// Set up exports properly -nativeUtils { - exportsConfigs { - LibRmb { - x64ExcludeSymbols = [ - '_CT??_R0?AV_System_error', - '_CT??_R0?AVexception', - '_CT??_R0?AVfailure', - '_CT??_R0?AVruntime_error', - '_CT??_R0?AVsystem_error', - '_CTA5?AVfailure', - '_TI5?AVfailure', - '_CT??_R0?AVout_of_range', - '_CTA3?AVout_of_range', - '_TI3?AVout_of_range', - '_CT??_R0?AVbad_cast' - ] - x86ExcludeSymbols = [ - '_CT??_R0?AV_System_error', - '_CT??_R0?AVexception', - '_CT??_R0?AVfailure', - '_CT??_R0?AVruntime_error', - '_CT??_R0?AVsystem_error', - '_CTA5?AVfailure', - '_TI5?AVfailure', - '_CT??_R0?AVout_of_range', - '_CTA3?AVout_of_range', - '_TI3?AVout_of_range', - '_CT??_R0?AVbad_cast' - ] - } - } -} - -model { - components { - LibRmb(NativeLibrarySpec) { - sources { - cpp { - source { - srcDirs 'src/' - include '**/*.cpp' - } - exportedHeaders { - srcDirs 'src/' - } - } - } - nativeUtils.useRequiredLibrary(it, 'wpilib_shared') - } - } -} - -apply from: 'publish.gradle' - -wrapper { - gradleVersion '8.4' -} - -test { - useJUnitPlatform() -} - -task resolveAllDependencies { - description "Resolves all transitive dependencies so you can run using the --offline flag" - doLast { - try { - configurations.all { - it.resolve() - } - } catch (Exception e) { - logger.quiet("dependency download exception: " + e.message); - } - } -} diff --git a/lib/librmb-main/build.old.gradle b/lib/librmb-main/build.old.gradle deleted file mode 100644 index 3f8cd78..0000000 --- a/lib/librmb-main/build.old.gradle +++ /dev/null @@ -1,90 +0,0 @@ -plugins { - id "cpp" - id "edu.wpi.first.GradleRIO" version "2023.4.2" -} - -// Define my targets (RoboRIO) and artifacts (deployable files) -// This is added by GradleRIO's backing project DeployUtils. -deploy { - targets { - roborio(getTargetTypeClass('RoboRIO')) { - // Team number is loaded either from the .wpilib/wpilib_preferences.json - // or from command line. If not found an exception will be thrown. - // You can use getTeamOrDefault(team) instead of getTeamNumber if you - // want to store a team number in this file. - team = project.frc.getTeamNumber() - debug = project.frc.getDebugOrDefault(false) - - artifacts { - // First part is artifact name, 2nd is artifact type - // getTargetTypeClass is a shortcut to get the class type using a string - - frcCpp(getArtifactTypeClass('FRCNativeArtifact')) { - } - - // // Static files artifact - // frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) { - // files = project.fileTree('src/main/deploy') - // directory = '/home/lvuser/deploy' - // } - } - } - } -} - -//def deployArtifact = deploy.targets.roborio.artifacts.frcCpp - -// Set this to true to enable desktop support. -def includeDesktopSupport = false - -// Set to true to run simulation in debug mode -wpi.cpp.debugSimulation = false - -// Default enable simgui -wpi.sim.addGui().defaultEnabled = true -// Enable DS but not by default -wpi.sim.addDriverstation() - -abstract class DocumentationTask extends DefaultTask { - @TaskAction - def run() { - "doxygen docs/Doxyfile".execute() - } -} - -tasks.register("docs", DocumentationTask) - -model { - components { - librmb(NativeLibrarySpec) { - targetPlatform wpi.platforms.roborio - if (includeDesktopSupport) { - targetPlatform wpi.platforms.desktop - } - - sources.cpp { - source { - include '**/*.cpp', '**/*.cc' - - srcDir 'src' - } - exportedHeaders { - srcDir 'src' - } - } - - // Set deploy task to deploy this component - //deployArtifact.component = it - - // Enable run tasks for this component - wpi.cpp.enableExternalTasks(it) - - // Enable simulation for this component - wpi.sim.enable(it) - // Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries. - wpi.cpp.vendor.cpp(it) - wpi.cpp.deps.wpilib(it) - } - } -} - diff --git a/lib/librmb-main/config.gradle b/lib/librmb-main/config.gradle deleted file mode 100644 index 2837c12..0000000 --- a/lib/librmb-main/config.gradle +++ /dev/null @@ -1,179 +0,0 @@ -import org.gradle.internal.os.OperatingSystem - -nativeUtils.addWpiNativeUtils() -nativeUtils.withCrossRoboRIO() - -nativeUtils { - wpi { - configureDependencies { - wpiVersion = "2024.+" - niLibVersion = "2024.+" - opencvVersion = "4.8.0-2" - wpimathVersion = "2024.+" - } - } -} - -nativeUtils.platformConfigs.linuxathena.cppCompiler.args << "-fPIC" - -nativeUtils.wpi.addWarnings() -//nativeUtils.wpi.addWarningsAsErrors() - -nativeUtils.setSinglePrintPerPlatform() - -nativeUtils.wpi.addVendorDeps() -nativeUtils.wpi.getVendorDeps().loadAll() -nativeUtils.wpi.getVendorDeps().getNativeVendor().initializeNativeDependencies() -nativeUtils.wpi.getVendorDeps().addVendorReposToMaven(true) - -model { - components { - all { - //targetPlatform nativeUtils.wpi.platforms.roborio - nativeUtils.useAllPlatforms(it) - } - } - - binaries { - withType(NativeBinarySpec).all { - nativeUtils.usePlatformArguments(it) - nativeUtils.wpi.getVendorDeps().getNativeVendor().cpp(it) - } - } -} - -ext.appendDebugPathToBinaries = { binaries-> - binaries.withType(StaticLibraryBinarySpec) { - if (it.buildType.name.contains('debug')) { - def staticFileDir = it.staticLibraryFile.parentFile - def staticFileName = it.staticLibraryFile.name - def staticFileExtension = staticFileName.substring(staticFileName.lastIndexOf('.')) - staticFileName = staticFileName.substring(0, staticFileName.lastIndexOf('.')) - staticFileName = staticFileName + 'd' + staticFileExtension - def newStaticFile = new File(staticFileDir, staticFileName) - it.staticLibraryFile = newStaticFile - } - } - binaries.withType(SharedLibraryBinarySpec) { - if (it.buildType.name.contains('debug')) { - def sharedFileDir = it.sharedLibraryFile.parentFile - def sharedFileName = it.sharedLibraryFile.name - def sharedFileExtension = sharedFileName.substring(sharedFileName.lastIndexOf('.')) - sharedFileName = sharedFileName.substring(0, sharedFileName.lastIndexOf('.')) - sharedFileName = sharedFileName + 'd' + sharedFileExtension - def newSharedFile = new File(sharedFileDir, sharedFileName) - - def sharedLinkFileDir = it.sharedLibraryLinkFile.parentFile - def sharedLinkFileName = it.sharedLibraryLinkFile.name - def sharedLinkFileExtension = sharedLinkFileName.substring(sharedLinkFileName.lastIndexOf('.')) - sharedLinkFileName = sharedLinkFileName.substring(0, sharedLinkFileName.lastIndexOf('.')) - sharedLinkFileName = sharedLinkFileName + 'd' + sharedLinkFileExtension - def newLinkFile = new File(sharedLinkFileDir, sharedLinkFileName) - - it.sharedLibraryLinkFile = newLinkFile - it.sharedLibraryFile = newSharedFile - } - } -} - -ext.createComponentZipTasks = { components, names, base, type, project, func -> - def stringNames = names.collect {it.toString()} - def configMap = [:] - components.each { - if (it in NativeLibrarySpec && stringNames.contains(it.name)) { - it.binaries.each { - if (!it.buildable) return - def target = nativeUtils.getPublishClassifier(it) - if (configMap.containsKey(target)) { - configMap.get(target).add(it) - } else { - configMap.put(target, []) - configMap.get(target).add(it) - } - } - } - } - def taskList = [] - def outputsFolder = file("$project.buildDir/outputs") - configMap.each { key, value -> - def task = project.tasks.create(base + "-${key}", type) { - description = 'Creates component archive for platform ' + key - destinationDirectory = outputsFolder - archiveClassifier = key - archiveBaseName = '_M_' + base - duplicatesStrategy = 'exclude' - - from(licenseFile) { - into '/' - } - - func(it, value) - } - taskList.add(task) - - project.build.dependsOn task - - project.artifacts { - task - } - addTaskToCopyAllOutputs(task) - } - return taskList -} - -ext.createAllCombined = { list, name, base, type, project -> - def outputsFolder = file("$project.buildDir/outputs") - - def task = project.tasks.create(base + "-all", type) { - description = "Creates component archive for all classifiers" - destinationDirectory = outputsFolder - classifier = "all" - archiveBaseName = base - duplicatesStrategy = 'exclude' - - list.each { - if (it.name.endsWith('debug')) return - from project.zipTree(it.archivePath) - dependsOn it - } - } - - project.build.dependsOn task - - project.artifacts { - task - } - - return task - -} - -ext.includeStandardZipFormat = { task, value -> - value.each { binary -> - if (binary.buildable) { - if (binary instanceof SharedLibraryBinarySpec) { - task.dependsOn binary.tasks.link - task.from(new File(binary.sharedLibraryFile.absolutePath + ".debug")) { - into nativeUtils.getPlatformPath(binary) + '/shared' - } - def sharedPath = binary.sharedLibraryFile.absolutePath - sharedPath = sharedPath.substring(0, sharedPath.length() - 4) - - task.from(new File(sharedPath + '.pdb')) { - into nativeUtils.getPlatformPath(binary) + '/shared' - } - task.from(binary.sharedLibraryFile) { - into nativeUtils.getPlatformPath(binary) + '/shared' - } - task.from(binary.sharedLibraryLinkFile) { - into nativeUtils.getPlatformPath(binary) + '/shared' - } - } else if (binary instanceof StaticLibraryBinarySpec) { - task.dependsOn binary.tasks.createStaticLib - task.from(binary.staticLibraryFile) { - into nativeUtils.getPlatformPath(binary) + '/static' - } - } - } - } -} diff --git a/lib/librmb-main/docs/Doxyfile b/lib/librmb-main/docs/Doxyfile deleted file mode 100644 index f175598..0000000 --- a/lib/librmb-main/docs/Doxyfile +++ /dev/null @@ -1,2646 +0,0 @@ -# Doxyfile 1.9.3 - -# This file describes the settings to be used by the documentation system -# doxygen (www.doxygen.org) for a project. -# -# All text after a double hash (##) is considered a comment and is placed in -# front of the TAG it is preceding. -# -# All text after a single hash (#) is considered a comment and will be ignored. -# The format is: -# TAG = value [value, ...] -# For lists, items can also be appended using: -# TAG += value [value, ...] -# Values that contain spaces should be placed between quotes (\" \"). - -#--------------------------------------------------------------------------- -# Project related configuration options -#--------------------------------------------------------------------------- - -# This tag specifies the encoding used for all characters in the configuration -# file that follow. The default is UTF-8 which is also the encoding used for all -# text before the first occurrence of this tag. Doxygen uses libiconv (or the -# iconv built into libc) for the transcoding. See -# https://www.gnu.org/software/libiconv/ for the list of possible encodings. -# The default value is: UTF-8. - -DOXYFILE_ENCODING = UTF-8 - -# The PROJECT_NAME tag is a single word (or a sequence of words surrounded by -# double-quotes, unless you are using Doxywizard) that should identify the -# project for which the documentation is generated. This name is used in the -# title of most generated pages and in a few other places. -# The default value is: My Project. - -PROJECT_NAME = "librmb" - -# The PROJECT_NUMBER tag can be used to enter a project or revision number. This -# could be handy for archiving the generated documentation or if some version -# control system is used. - -PROJECT_NUMBER = 1.0 - -# Using the PROJECT_BRIEF tag one can provide an optional one line description -# for a project that appears at the top of each page and should give viewer a -# quick idea about the purpose of the project. Keep the description short. - -PROJECT_BRIEF = "Rambunction 4330 Utility Library" - -# With the PROJECT_LOGO tag one can specify a logo or an icon that is included -# in the documentation. The maximum height of the logo should not exceed 55 -# pixels and the maximum width should not exceed 200 pixels. Doxygen will copy -# the logo to the output directory. - -PROJECT_LOGO = "docs/favicon.png" - -# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) path -# into which the generated documentation will be written. If a relative path is -# entered, it will be relative to the location where doxygen was started. If -# left blank the current directory will be used. - -OUTPUT_DIRECTORY = "." - -# If the CREATE_SUBDIRS tag is set to YES then doxygen will create 4096 sub- -# directories (in 2 levels) under the output directory of each output format and -# will distribute the generated files over these directories. Enabling this -# option can be useful when feeding doxygen a huge amount of source files, where -# putting all generated files in the same directory would otherwise causes -# performance problems for the file system. -# The default value is: NO. - -CREATE_SUBDIRS = NO - -# If the ALLOW_UNICODE_NAMES tag is set to YES, doxygen will allow non-ASCII -# characters to appear in the names of generated files. If set to NO, non-ASCII -# characters will be escaped, for example _xE3_x81_x84 will be used for Unicode -# U+3044. -# The default value is: NO. - -ALLOW_UNICODE_NAMES = NO - -# The OUTPUT_LANGUAGE tag is used to specify the language in which all -# documentation generated by doxygen is written. Doxygen will use this -# information to generate all constant output in the proper language. -# Possible values are: Afrikaans, Arabic, Armenian, Brazilian, Catalan, Chinese, -# Chinese-Traditional, Croatian, Czech, Danish, Dutch, English (United States), -# Esperanto, Farsi (Persian), Finnish, French, German, Greek, Hungarian, -# Indonesian, Italian, Japanese, Japanese-en (Japanese with English messages), -# Korean, Korean-en (Korean with English messages), Latvian, Lithuanian, -# Macedonian, Norwegian, Persian (Farsi), Polish, Portuguese, Romanian, Russian, -# Serbian, Serbian-Cyrillic, Slovak, Slovene, Spanish, Swedish, Turkish, -# Ukrainian and Vietnamese. -# The default value is: English. - -OUTPUT_LANGUAGE = English - -# If the BRIEF_MEMBER_DESC tag is set to YES, doxygen will include brief member -# descriptions after the members that are listed in the file and class -# documentation (similar to Javadoc). Set to NO to disable this. -# The default value is: YES. - -BRIEF_MEMBER_DESC = YES - -# If the REPEAT_BRIEF tag is set to YES, doxygen will prepend the brief -# description of a member or function before the detailed description -# -# Note: If both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the -# brief descriptions will be completely suppressed. -# The default value is: YES. - -REPEAT_BRIEF = YES - -# This tag implements a quasi-intelligent brief description abbreviator that is -# used to form the text in various listings. Each string in this list, if found -# as the leading text of the brief description, will be stripped from the text -# and the result, after processing the whole list, is used as the annotated -# text. Otherwise, the brief description is used as-is. If left blank, the -# following values are used ($name is automatically replaced with the name of -# the entity):The $name class, The $name widget, The $name file, is, provides, -# specifies, contains, represents, a, an and the. - -ABBREVIATE_BRIEF = "The $name class" \ - "The $name widget" \ - "The $name file" \ - is \ - provides \ - specifies \ - contains \ - represents \ - a \ - an \ - the - -# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then -# doxygen will generate a detailed section even if there is only a brief -# description. -# The default value is: NO. - -ALWAYS_DETAILED_SEC = NO - -# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all -# inherited members of a class in the documentation of that class as if those -# members were ordinary class members. Constructors, destructors and assignment -# operators of the base classes will not be shown. -# The default value is: NO. - -INLINE_INHERITED_MEMB = NO - -# If the FULL_PATH_NAMES tag is set to YES, doxygen will prepend the full path -# before files name in the file list and in the header files. If set to NO the -# shortest path that makes the file name unique will be used -# The default value is: YES. - -FULL_PATH_NAMES = YES - -# The STRIP_FROM_PATH tag can be used to strip a user-defined part of the path. -# Stripping is only done if one of the specified strings matches the left-hand -# part of the path. The tag can be used to show relative paths in the file list. -# If left blank the directory from which doxygen is run is used as the path to -# strip. -# -# Note that you can specify absolute paths here, but also relative paths, which -# will be relative from the directory where doxygen is started. -# This tag requires that the tag FULL_PATH_NAMES is set to YES. - -STRIP_FROM_PATH = - -# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of the -# path mentioned in the documentation of a class, which tells the reader which -# header file to include in order to use a class. If left blank only the name of -# the header file containing the class definition is used. Otherwise one should -# specify the list of include paths that are normally passed to the compiler -# using the -I flag. - -STRIP_FROM_INC_PATH = src/ - -# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter (but -# less readable) file names. This can be useful is your file systems doesn't -# support long names like on DOS, Mac, or CD-ROM. -# The default value is: NO. - -SHORT_NAMES = NO - -# If the JAVADOC_AUTOBRIEF tag is set to YES then doxygen will interpret the -# first line (until the first dot) of a Javadoc-style comment as the brief -# description. If set to NO, the Javadoc-style will behave just like regular Qt- -# style comments (thus requiring an explicit @brief command for a brief -# description.) -# The default value is: NO. - -JAVADOC_AUTOBRIEF = NO - -# If the JAVADOC_BANNER tag is set to YES then doxygen will interpret a line -# such as -# /*************** -# as being the beginning of a Javadoc-style comment "banner". If set to NO, the -# Javadoc-style will behave just like regular comments and it will not be -# interpreted by doxygen. -# The default value is: NO. - -JAVADOC_BANNER = NO - -# If the QT_AUTOBRIEF tag is set to YES then doxygen will interpret the first -# line (until the first dot) of a Qt-style comment as the brief description. If -# set to NO, the Qt-style will behave just like regular Qt-style comments (thus -# requiring an explicit \brief command for a brief description.) -# The default value is: NO. - -QT_AUTOBRIEF = NO - -# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make doxygen treat a -# multi-line C++ special comment block (i.e. a block of //! or /// comments) as -# a brief description. This used to be the default behavior. The new default is -# to treat a multi-line C++ comment block as a detailed description. Set this -# tag to YES if you prefer the old behavior instead. -# -# Note that setting this tag to YES also means that rational rose comments are -# not recognized any more. -# The default value is: NO. - -MULTILINE_CPP_IS_BRIEF = NO - -# By default Python docstrings are displayed as preformatted text and doxygen's -# special commands cannot be used. By setting PYTHON_DOCSTRING to NO the -# doxygen's special commands can be used and the contents of the docstring -# documentation blocks is shown as doxygen documentation. -# The default value is: YES. - -PYTHON_DOCSTRING = YES - -# If the INHERIT_DOCS tag is set to YES then an undocumented member inherits the -# documentation from any documented member that it re-implements. -# The default value is: YES. - -INHERIT_DOCS = YES - -# If the SEPARATE_MEMBER_PAGES tag is set to YES then doxygen will produce a new -# page for each member. If set to NO, the documentation of a member will be part -# of the file/class/namespace that contains it. -# The default value is: NO. - -SEPARATE_MEMBER_PAGES = NO - -# The TAB_SIZE tag can be used to set the number of spaces in a tab. Doxygen -# uses this value to replace tabs by spaces in code fragments. -# Minimum value: 1, maximum value: 16, default value: 4. - -TAB_SIZE = 4 - -# This tag can be used to specify a number of aliases that act as commands in -# the documentation. An alias has the form: -# name=value -# For example adding -# "sideeffect=@par Side Effects:^^" -# will allow you to put the command \sideeffect (or @sideeffect) in the -# documentation, which will result in a user-defined paragraph with heading -# "Side Effects:". Note that you cannot put \n's in the value part of an alias -# to insert newlines (in the resulting output). You can put ^^ in the value part -# of an alias to insert a newline as if a physical newline was in the original -# file. When you need a literal { or } or , in the value part of an alias you -# have to escape them by means of a backslash (\), this can lead to conflicts -# with the commands \{ and \} for these it is advised to use the version @{ and -# @} or use a double escape (\\{ and \\}) - -ALIASES = - -# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C sources -# only. Doxygen will then generate output that is more tailored for C. For -# instance, some of the names that are used will be different. The list of all -# members will be omitted, etc. -# The default value is: NO. - -OPTIMIZE_OUTPUT_FOR_C = NO - -# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java or -# Python sources only. Doxygen will then generate output that is more tailored -# for that language. For instance, namespaces will be presented as packages, -# qualified scopes will look different, etc. -# The default value is: NO. - -OPTIMIZE_OUTPUT_JAVA = NO - -# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran -# sources. Doxygen will then generate output that is tailored for Fortran. -# The default value is: NO. - -OPTIMIZE_FOR_FORTRAN = NO - -# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL -# sources. Doxygen will then generate output that is tailored for VHDL. -# The default value is: NO. - -OPTIMIZE_OUTPUT_VHDL = NO - -# Set the OPTIMIZE_OUTPUT_SLICE tag to YES if your project consists of Slice -# sources only. Doxygen will then generate output that is more tailored for that -# language. For instance, namespaces will be presented as modules, types will be -# separated into more groups, etc. -# The default value is: NO. - -OPTIMIZE_OUTPUT_SLICE = NO - -# Doxygen selects the parser to use depending on the extension of the files it -# parses. With this tag you can assign which parser to use for a given -# extension. Doxygen has a built-in mapping, but you can override or extend it -# using this tag. The format is ext=language, where ext is a file extension, and -# language is one of the parsers supported by doxygen: IDL, Java, JavaScript, -# Csharp (C#), C, C++, Lex, D, PHP, md (Markdown), Objective-C, Python, Slice, -# VHDL, Fortran (fixed format Fortran: FortranFixed, free formatted Fortran: -# FortranFree, unknown formatted Fortran: Fortran. In the later case the parser -# tries to guess whether the code is fixed or free formatted code, this is the -# default for Fortran type files). For instance to make doxygen treat .inc files -# as Fortran files (default is PHP), and .f files as C (default is Fortran), -# use: inc=Fortran f=C. -# -# Note: For files without extension you can use no_extension as a placeholder. -# -# Note that for custom extensions you also need to set FILE_PATTERNS otherwise -# the files are not read by doxygen. When specifying no_extension you should add -# * to the FILE_PATTERNS. -# -# Note see also the list of default file extension mappings. - -EXTENSION_MAPPING = - -# If the MARKDOWN_SUPPORT tag is enabled then doxygen pre-processes all comments -# according to the Markdown format, which allows for more readable -# documentation. See https://daringfireball.net/projects/markdown/ for details. -# The output of markdown processing is further processed by doxygen, so you can -# mix doxygen, HTML, and XML commands with Markdown formatting. Disable only in -# case of backward compatibilities issues. -# The default value is: YES. - -MARKDOWN_SUPPORT = YES - -# When the TOC_INCLUDE_HEADINGS tag is set to a non-zero value, all headings up -# to that level are automatically included in the table of contents, even if -# they do not have an id attribute. -# Note: This feature currently applies only to Markdown headings. -# Minimum value: 0, maximum value: 99, default value: 5. -# This tag requires that the tag MARKDOWN_SUPPORT is set to YES. - -TOC_INCLUDE_HEADINGS = 5 - -# When enabled doxygen tries to link words that correspond to documented -# classes, or namespaces to their corresponding documentation. Such a link can -# be prevented in individual cases by putting a % sign in front of the word or -# globally by setting AUTOLINK_SUPPORT to NO. -# The default value is: YES. - -AUTOLINK_SUPPORT = YES - -# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want -# to include (a tag file for) the STL sources as input, then you should set this -# tag to YES in order to let doxygen match functions declarations and -# definitions whose arguments contain STL classes (e.g. func(std::string); -# versus func(std::string) {}). This also make the inheritance and collaboration -# diagrams that involve STL classes more complete and accurate. -# The default value is: NO. - -BUILTIN_STL_SUPPORT = NO - -# If you use Microsoft's C++/CLI language, you should set this option to YES to -# enable parsing support. -# The default value is: NO. - -CPP_CLI_SUPPORT = NO - -# Set the SIP_SUPPORT tag to YES if your project consists of sip (see: -# https://www.riverbankcomputing.com/software/sip/intro) sources only. Doxygen -# will parse them like normal C++ but will assume all classes use public instead -# of private inheritance when no explicit protection keyword is present. -# The default value is: NO. - -SIP_SUPPORT = NO - -# For Microsoft's IDL there are propget and propput attributes to indicate -# getter and setter methods for a property. Setting this option to YES will make -# doxygen to replace the get and set methods by a property in the documentation. -# This will only work if the methods are indeed getting or setting a simple -# type. If this is not the case, or you want to show the methods anyway, you -# should set this option to NO. -# The default value is: YES. - -IDL_PROPERTY_SUPPORT = YES - -# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC -# tag is set to YES then doxygen will reuse the documentation of the first -# member in the group (if any) for the other members of the group. By default -# all members of a group must be documented explicitly. -# The default value is: NO. - -DISTRIBUTE_GROUP_DOC = NO - -# If one adds a struct or class to a group and this option is enabled, then also -# any nested class or struct is added to the same group. By default this option -# is disabled and one has to add nested compounds explicitly via \ingroup. -# The default value is: NO. - -GROUP_NESTED_COMPOUNDS = NO - -# Set the SUBGROUPING tag to YES to allow class member groups of the same type -# (for instance a group of public functions) to be put as a subgroup of that -# type (e.g. under the Public Functions section). Set it to NO to prevent -# subgrouping. Alternatively, this can be done per class using the -# \nosubgrouping command. -# The default value is: YES. - -SUBGROUPING = YES - -# When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and unions -# are shown inside the group in which they are included (e.g. using \ingroup) -# instead of on a separate page (for HTML and Man pages) or section (for LaTeX -# and RTF). -# -# Note that this feature does not work in combination with -# SEPARATE_MEMBER_PAGES. -# The default value is: NO. - -INLINE_GROUPED_CLASSES = NO - -# When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and unions -# with only public data fields or simple typedef fields will be shown inline in -# the documentation of the scope in which they are defined (i.e. file, -# namespace, or group documentation), provided this scope is documented. If set -# to NO, structs, classes, and unions are shown on a separate page (for HTML and -# Man pages) or section (for LaTeX and RTF). -# The default value is: NO. - -INLINE_SIMPLE_STRUCTS = NO - -# When TYPEDEF_HIDES_STRUCT tag is enabled, a typedef of a struct, union, or -# enum is documented as struct, union, or enum with the name of the typedef. So -# typedef struct TypeS {} TypeT, will appear in the documentation as a struct -# with name TypeT. When disabled the typedef will appear as a member of a file, -# namespace, or class. And the struct will be named TypeS. This can typically be -# useful for C code in case the coding convention dictates that all compound -# types are typedef'ed and only the typedef is referenced, never the tag name. -# The default value is: NO. - -TYPEDEF_HIDES_STRUCT = NO - -# The size of the symbol lookup cache can be set using LOOKUP_CACHE_SIZE. This -# cache is used to resolve symbols given their name and scope. Since this can be -# an expensive process and often the same symbol appears multiple times in the -# code, doxygen keeps a cache of pre-resolved symbols. If the cache is too small -# doxygen will become slower. If the cache is too large, memory is wasted. The -# cache size is given by this formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range -# is 0..9, the default is 0, corresponding to a cache size of 2^16=65536 -# symbols. At the end of a run doxygen will report the cache usage and suggest -# the optimal cache size from a speed point of view. -# Minimum value: 0, maximum value: 9, default value: 0. - -LOOKUP_CACHE_SIZE = 0 - -# The NUM_PROC_THREADS specifies the number threads doxygen is allowed to use -# during processing. When set to 0 doxygen will based this on the number of -# cores available in the system. You can set it explicitly to a value larger -# than 0 to get more control over the balance between CPU load and processing -# speed. At this moment only the input processing can be done using multiple -# threads. Since this is still an experimental feature the default is set to 1, -# which effectively disables parallel processing. Please report any issues you -# encounter. Generating dot graphs in parallel is controlled by the -# DOT_NUM_THREADS setting. -# Minimum value: 0, maximum value: 32, default value: 1. - -NUM_PROC_THREADS = 1 - -#--------------------------------------------------------------------------- -# Build related configuration options -#--------------------------------------------------------------------------- - -# If the EXTRACT_ALL tag is set to YES, doxygen will assume all entities in -# documentation are documented, even if no documentation was available. Private -# class members and static file members will be hidden unless the -# EXTRACT_PRIVATE respectively EXTRACT_STATIC tags are set to YES. -# Note: This will also disable the warnings about undocumented members that are -# normally produced when WARNINGS is set to YES. -# The default value is: NO. - -EXTRACT_ALL = NO - -# If the EXTRACT_PRIVATE tag is set to YES, all private members of a class will -# be included in the documentation. -# The default value is: NO. - -EXTRACT_PRIVATE = NO - -# If the EXTRACT_PRIV_VIRTUAL tag is set to YES, documented private virtual -# methods of a class will be included in the documentation. -# The default value is: NO. - -EXTRACT_PRIV_VIRTUAL = NO - -# If the EXTRACT_PACKAGE tag is set to YES, all members with package or internal -# scope will be included in the documentation. -# The default value is: NO. - -EXTRACT_PACKAGE = NO - -# If the EXTRACT_STATIC tag is set to YES, all static members of a file will be -# included in the documentation. -# The default value is: NO. - -EXTRACT_STATIC = NO - -# If the EXTRACT_LOCAL_CLASSES tag is set to YES, classes (and structs) defined -# locally in source files will be included in the documentation. If set to NO, -# only classes defined in header files are included. Does not have any effect -# for Java sources. -# The default value is: YES. - -EXTRACT_LOCAL_CLASSES = YES - -# This flag is only useful for Objective-C code. If set to YES, local methods, -# which are defined in the implementation section but not in the interface are -# included in the documentation. If set to NO, only methods in the interface are -# included. -# The default value is: NO. - -EXTRACT_LOCAL_METHODS = NO - -# If this flag is set to YES, the members of anonymous namespaces will be -# extracted and appear in the documentation as a namespace called -# 'anonymous_namespace{file}', where file will be replaced with the base name of -# the file that contains the anonymous namespace. By default anonymous namespace -# are hidden. -# The default value is: NO. - -EXTRACT_ANON_NSPACES = NO - -# If this flag is set to YES, the name of an unnamed parameter in a declaration -# will be determined by the corresponding definition. By default unnamed -# parameters remain unnamed in the output. -# The default value is: YES. - -RESOLVE_UNNAMED_PARAMS = YES - -# If the HIDE_UNDOC_MEMBERS tag is set to YES, doxygen will hide all -# undocumented members inside documented classes or files. If set to NO these -# members will be included in the various overviews, but no documentation -# section is generated. This option has no effect if EXTRACT_ALL is enabled. -# The default value is: NO. - -HIDE_UNDOC_MEMBERS = NO - -# If the HIDE_UNDOC_CLASSES tag is set to YES, doxygen will hide all -# undocumented classes that are normally visible in the class hierarchy. If set -# to NO, these classes will be included in the various overviews. This option -# has no effect if EXTRACT_ALL is enabled. -# The default value is: NO. - -HIDE_UNDOC_CLASSES = NO - -# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, doxygen will hide all friend -# declarations. If set to NO, these declarations will be included in the -# documentation. -# The default value is: NO. - -HIDE_FRIEND_COMPOUNDS = NO - -# If the HIDE_IN_BODY_DOCS tag is set to YES, doxygen will hide any -# documentation blocks found inside the body of a function. If set to NO, these -# blocks will be appended to the function's detailed documentation block. -# The default value is: NO. - -HIDE_IN_BODY_DOCS = NO - -# The INTERNAL_DOCS tag determines if documentation that is typed after a -# \internal command is included. If the tag is set to NO then the documentation -# will be excluded. Set it to YES to include the internal documentation. -# The default value is: NO. - -INTERNAL_DOCS = NO - -# With the correct setting of option CASE_SENSE_NAMES doxygen will better be -# able to match the capabilities of the underlying filesystem. In case the -# filesystem is case sensitive (i.e. it supports files in the same directory -# whose names only differ in casing), the option must be set to YES to properly -# deal with such files in case they appear in the input. For filesystems that -# are not case sensitive the option should be be set to NO to properly deal with -# output files written for symbols that only differ in casing, such as for two -# classes, one named CLASS and the other named Class, and to also support -# references to files without having to specify the exact matching casing. On -# Windows (including Cygwin) and MacOS, users should typically set this option -# to NO, whereas on Linux or other Unix flavors it should typically be set to -# YES. -# The default value is: system dependent. - -CASE_SENSE_NAMES = NO - -# If the HIDE_SCOPE_NAMES tag is set to NO then doxygen will show members with -# their full class and namespace scopes in the documentation. If set to YES, the -# scope will be hidden. -# The default value is: NO. - -HIDE_SCOPE_NAMES = NO - -# If the HIDE_COMPOUND_REFERENCE tag is set to NO (default) then doxygen will -# append additional text to a page's title, such as Class Reference. If set to -# YES the compound reference will be hidden. -# The default value is: NO. - -HIDE_COMPOUND_REFERENCE= NO - -# If the SHOW_HEADERFILE tag is set to YES then the documentation for a class -# will show which file needs to be included to use the class. -# The default value is: YES. - -SHOW_HEADERFILE = YES - -# If the SHOW_INCLUDE_FILES tag is set to YES then doxygen will put a list of -# the files that are included by a file in the documentation of that file. -# The default value is: YES. - -SHOW_INCLUDE_FILES = YES - -# If the SHOW_GROUPED_MEMB_INC tag is set to YES then Doxygen will add for each -# grouped member an include statement to the documentation, telling the reader -# which file to include in order to use the member. -# The default value is: NO. - -SHOW_GROUPED_MEMB_INC = NO - -# If the FORCE_LOCAL_INCLUDES tag is set to YES then doxygen will list include -# files with double quotes in the documentation rather than with sharp brackets. -# The default value is: NO. - -FORCE_LOCAL_INCLUDES = NO - -# If the INLINE_INFO tag is set to YES then a tag [inline] is inserted in the -# documentation for inline members. -# The default value is: YES. - -INLINE_INFO = YES - -# If the SORT_MEMBER_DOCS tag is set to YES then doxygen will sort the -# (detailed) documentation of file and class members alphabetically by member -# name. If set to NO, the members will appear in declaration order. -# The default value is: YES. - -SORT_MEMBER_DOCS = YES - -# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the brief -# descriptions of file, namespace and class members alphabetically by member -# name. If set to NO, the members will appear in declaration order. Note that -# this will also influence the order of the classes in the class list. -# The default value is: NO. - -SORT_BRIEF_DOCS = NO - -# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen will sort the -# (brief and detailed) documentation of class members so that constructors and -# destructors are listed first. If set to NO the constructors will appear in the -# respective orders defined by SORT_BRIEF_DOCS and SORT_MEMBER_DOCS. -# Note: If SORT_BRIEF_DOCS is set to NO this option is ignored for sorting brief -# member documentation. -# Note: If SORT_MEMBER_DOCS is set to NO this option is ignored for sorting -# detailed member documentation. -# The default value is: NO. - -SORT_MEMBERS_CTORS_1ST = NO - -# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the hierarchy -# of group names into alphabetical order. If set to NO the group names will -# appear in their defined order. -# The default value is: NO. - -SORT_GROUP_NAMES = NO - -# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be sorted by -# fully-qualified names, including namespaces. If set to NO, the class list will -# be sorted only by class name, not including the namespace part. -# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. -# Note: This option applies only to the class list, not to the alphabetical -# list. -# The default value is: NO. - -SORT_BY_SCOPE_NAME = NO - -# If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to do proper -# type resolution of all parameters of a function it will reject a match between -# the prototype and the implementation of a member function even if there is -# only one candidate or it is obvious which candidate to choose by doing a -# simple string match. By disabling STRICT_PROTO_MATCHING doxygen will still -# accept a match between prototype and implementation in such cases. -# The default value is: NO. - -STRICT_PROTO_MATCHING = NO - -# The GENERATE_TODOLIST tag can be used to enable (YES) or disable (NO) the todo -# list. This list is created by putting \todo commands in the documentation. -# The default value is: YES. - -GENERATE_TODOLIST = YES - -# The GENERATE_TESTLIST tag can be used to enable (YES) or disable (NO) the test -# list. This list is created by putting \test commands in the documentation. -# The default value is: YES. - -GENERATE_TESTLIST = YES - -# The GENERATE_BUGLIST tag can be used to enable (YES) or disable (NO) the bug -# list. This list is created by putting \bug commands in the documentation. -# The default value is: YES. - -GENERATE_BUGLIST = YES - -# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or disable (NO) -# the deprecated list. This list is created by putting \deprecated commands in -# the documentation. -# The default value is: YES. - -GENERATE_DEPRECATEDLIST= YES - -# The ENABLED_SECTIONS tag can be used to enable conditional documentation -# sections, marked by \if ... \endif and \cond -# ... \endcond blocks. - -ENABLED_SECTIONS = - -# The MAX_INITIALIZER_LINES tag determines the maximum number of lines that the -# initial value of a variable or macro / define can have for it to appear in the -# documentation. If the initializer consists of more lines than specified here -# it will be hidden. Use a value of 0 to hide initializers completely. The -# appearance of the value of individual variables and macros / defines can be -# controlled using \showinitializer or \hideinitializer command in the -# documentation regardless of this setting. -# Minimum value: 0, maximum value: 10000, default value: 30. - -MAX_INITIALIZER_LINES = 30 - -# Set the SHOW_USED_FILES tag to NO to disable the list of files generated at -# the bottom of the documentation of classes and structs. If set to YES, the -# list will mention the files that were used to generate the documentation. -# The default value is: YES. - -SHOW_USED_FILES = YES - -# Set the SHOW_FILES tag to NO to disable the generation of the Files page. This -# will remove the Files entry from the Quick Index and from the Folder Tree View -# (if specified). -# The default value is: YES. - -SHOW_FILES = YES - -# Set the SHOW_NAMESPACES tag to NO to disable the generation of the Namespaces -# page. This will remove the Namespaces entry from the Quick Index and from the -# Folder Tree View (if specified). -# The default value is: YES. - -SHOW_NAMESPACES = YES - -# The FILE_VERSION_FILTER tag can be used to specify a program or script that -# doxygen should invoke to get the current version for each file (typically from -# the version control system). Doxygen will invoke the program by executing (via -# popen()) the command command input-file, where command is the value of the -# FILE_VERSION_FILTER tag, and input-file is the name of an input file provided -# by doxygen. Whatever the program writes to standard output is used as the file -# version. For an example see the documentation. - -FILE_VERSION_FILTER = - -# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed -# by doxygen. The layout file controls the global structure of the generated -# output files in an output format independent way. To create the layout file -# that represents doxygen's defaults, run doxygen with the -l option. You can -# optionally specify a file name after the option, if omitted DoxygenLayout.xml -# will be used as the name of the layout file. See also section "Changing the -# layout of pages" for information. -# -# Note that if you run doxygen from a directory containing a file called -# DoxygenLayout.xml, doxygen will parse it automatically even if the LAYOUT_FILE -# tag is left empty. - -LAYOUT_FILE = - -# The CITE_BIB_FILES tag can be used to specify one or more bib files containing -# the reference definitions. This must be a list of .bib files. The .bib -# extension is automatically appended if omitted. This requires the bibtex tool -# to be installed. See also https://en.wikipedia.org/wiki/BibTeX for more info. -# For LaTeX the style of the bibliography can be controlled using -# LATEX_BIB_STYLE. To use this feature you need bibtex and perl available in the -# search path. See also \cite for info how to create references. - -CITE_BIB_FILES = - -#--------------------------------------------------------------------------- -# Configuration options related to warning and progress messages -#--------------------------------------------------------------------------- - -# The QUIET tag can be used to turn on/off the messages that are generated to -# standard output by doxygen. If QUIET is set to YES this implies that the -# messages are off. -# The default value is: NO. - -QUIET = NO - -# The WARNINGS tag can be used to turn on/off the warning messages that are -# generated to standard error (stderr) by doxygen. If WARNINGS is set to YES -# this implies that the warnings are on. -# -# Tip: Turn warnings on while writing the documentation. -# The default value is: YES. - -WARNINGS = YES - -# If the WARN_IF_UNDOCUMENTED tag is set to YES then doxygen will generate -# warnings for undocumented members. If EXTRACT_ALL is set to YES then this flag -# will automatically be disabled. -# The default value is: YES. - -WARN_IF_UNDOCUMENTED = YES - -# If the WARN_IF_DOC_ERROR tag is set to YES, doxygen will generate warnings for -# potential errors in the documentation, such as documenting some parameters in -# a documented function twice, or documenting parameters that don't exist or -# using markup commands wrongly. -# The default value is: YES. - -WARN_IF_DOC_ERROR = YES - -# If WARN_IF_INCOMPLETE_DOC is set to YES, doxygen will warn about incomplete -# function parameter documentation. If set to NO, doxygen will accept that some -# parameters have no documentation without warning. -# The default value is: YES. - -WARN_IF_INCOMPLETE_DOC = YES - -# This WARN_NO_PARAMDOC option can be enabled to get warnings for functions that -# are documented, but have no documentation for their parameters or return -# value. If set to NO, doxygen will only warn about wrong parameter -# documentation, but not about the absence of documentation. If EXTRACT_ALL is -# set to YES then this flag will automatically be disabled. See also -# WARN_IF_INCOMPLETE_DOC -# The default value is: NO. - -WARN_NO_PARAMDOC = NO - -# If the WARN_AS_ERROR tag is set to YES then doxygen will immediately stop when -# a warning is encountered. If the WARN_AS_ERROR tag is set to FAIL_ON_WARNINGS -# then doxygen will continue running as if WARN_AS_ERROR tag is set to NO, but -# at the end of the doxygen process doxygen will return with a non-zero status. -# Possible values are: NO, YES and FAIL_ON_WARNINGS. -# The default value is: NO. - -WARN_AS_ERROR = NO - -# The WARN_FORMAT tag determines the format of the warning messages that doxygen -# can produce. The string should contain the $file, $line, and $text tags, which -# will be replaced by the file and line number from which the warning originated -# and the warning text. Optionally the format may contain $version, which will -# be replaced by the version of the file (if it could be obtained via -# FILE_VERSION_FILTER) -# The default value is: $file:$line: $text. - -WARN_FORMAT = "$file:$line: $text" - -# The WARN_LOGFILE tag can be used to specify a file to which warning and error -# messages should be written. If left blank the output is written to standard -# error (stderr). In case the file specified cannot be opened for writing the -# warning and error messages are written to standard error. When as file - is -# specified the warning and error messages are written to standard output -# (stdout). - -WARN_LOGFILE = - -#--------------------------------------------------------------------------- -# Configuration options related to the input files -#--------------------------------------------------------------------------- - -# The INPUT tag is used to specify the files and/or directories that contain -# documented source files. You may enter file names like myfile.cpp or -# directories like /usr/src/myproject. Separate the files or directories with -# spaces. See also FILE_PATTERNS and EXTENSION_MAPPING -# Note: If this tag is empty the current directory is searched. - -INPUT = src/rmb docs/additional/pancakerecipe.md docs/building.md docs/doxygen.h - -# This tag can be used to specify the character encoding of the source files -# that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses -# libiconv (or the iconv built into libc) for the transcoding. See the libiconv -# documentation (see: -# https://www.gnu.org/software/libiconv/) for the list of possible encodings. -# The default value is: UTF-8. - -INPUT_ENCODING = UTF-8 - -# If the value of the INPUT tag contains directories, you can use the -# FILE_PATTERNS tag to specify one or more wildcard patterns (like *.cpp and -# *.h) to filter out the source-files in the directories. -# -# Note that for custom extensions or not directly supported extensions you also -# need to set EXTENSION_MAPPING for the extension otherwise the files are not -# read by doxygen. -# -# Note the list of default checked file patterns might differ from the list of -# default file extension mappings. -# -# If left blank the following patterns are tested:*.c, *.cc, *.cxx, *.cpp, -# *.c++, *.java, *.ii, *.ixx, *.ipp, *.i++, *.inl, *.idl, *.ddl, *.odl, *.h, -# *.hh, *.hxx, *.hpp, *.h++, *.l, *.cs, *.d, *.php, *.php4, *.php5, *.phtml, -# *.inc, *.m, *.markdown, *.md, *.mm, *.dox (to be provided as doxygen C -# comment), *.py, *.pyw, *.f90, *.f95, *.f03, *.f08, *.f18, *.f, *.for, *.vhd, -# *.vhdl, *.ucf, *.qsf and *.ice. - -# FILE_PATTERNS = *.c \ -# *.cc \ -# *.cxx \ -# *.cpp \ -# *.c++ \ -FILE_PATTERNS = *.java \ - *.ii \ - *.ixx \ - *.ipp \ - *.i++ \ - *.inl \ - *.idl \ - *.ddl \ - *.odl \ - *.h \ - *.hh \ - *.hxx \ - *.hpp \ - *.h++ \ - *.l \ - *.cs \ - *.d \ - *.php \ - *.php4 \ - *.php5 \ - *.phtml \ - *.inc \ - *.m \ - *.markdown \ - *.md \ - *.mm \ - *.dox \ - *.py \ - *.pyw \ - *.f90 \ - *.f95 \ - *.f03 \ - *.f08 \ - *.f18 \ - *.f \ - *.for \ - *.vhd \ - *.vhdl \ - *.ucf \ - *.qsf \ - *.ice - -# The RECURSIVE tag can be used to specify whether or not subdirectories should -# be searched for input files as well. -# The default value is: NO. - -RECURSIVE = YES - -# The EXCLUDE tag can be used to specify files and/or directories that should be -# excluded from the INPUT source files. This way you can easily exclude a -# subdirectory from a directory tree whose root is specified with the INPUT tag. -# -# Note that relative paths are relative to the directory from which doxygen is -# run. - -EXCLUDE = - -# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or -# directories that are symbolic links (a Unix file system feature) are excluded -# from the input. -# The default value is: NO. - -EXCLUDE_SYMLINKS = NO - -# If the value of the INPUT tag contains directories, you can use the -# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude -# certain files from those directories. -# -# Note that the wildcards are matched against the file with absolute path, so to -# exclude all test directories for example use the pattern */test/* - -EXCLUDE_PATTERNS = - -# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names -# (namespaces, classes, functions, etc.) that should be excluded from the -# output. The symbol name can be a fully qualified name, a word, or if the -# wildcard * is used, a substring. Examples: ANamespace, AClass, -# ANamespace::AClass, ANamespace::*Test -# -# Note that the wildcards are matched against the file with absolute path, so to -# exclude all test directories use the pattern */test/* - -EXCLUDE_SYMBOLS = - -# The EXAMPLE_PATH tag can be used to specify one or more files or directories -# that contain example code fragments that are included (see the \include -# command). - -EXAMPLE_PATH = - -# If the value of the EXAMPLE_PATH tag contains directories, you can use the -# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp and -# *.h) to filter out the source-files in the directories. If left blank all -# files are included. - -EXAMPLE_PATTERNS = * - -# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be -# searched for input files to be used with the \include or \dontinclude commands -# irrespective of the value of the RECURSIVE tag. -# The default value is: NO. - -EXAMPLE_RECURSIVE = NO - -# The IMAGE_PATH tag can be used to specify one or more files or directories -# that contain images that are to be included in the documentation (see the -# \image command). - -IMAGE_PATH = - -# The INPUT_FILTER tag can be used to specify a program that doxygen should -# invoke to filter for each input file. Doxygen will invoke the filter program -# by executing (via popen()) the command: -# -# -# -# where is the value of the INPUT_FILTER tag, and is the -# name of an input file. Doxygen will then use the output that the filter -# program writes to standard output. If FILTER_PATTERNS is specified, this tag -# will be ignored. -# -# Note that the filter must not add or remove lines; it is applied before the -# code is scanned, but not when the output code is generated. If lines are added -# or removed, the anchors will not be placed correctly. -# -# Note that for custom extensions or not directly supported extensions you also -# need to set EXTENSION_MAPPING for the extension otherwise the files are not -# properly processed by doxygen. - -INPUT_FILTER = - -# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern -# basis. Doxygen will compare the file name with each pattern and apply the -# filter if there is a match. The filters are a list of the form: pattern=filter -# (like *.cpp=my_cpp_filter). See INPUT_FILTER for further information on how -# filters are used. If the FILTER_PATTERNS tag is empty or if none of the -# patterns match the file name, INPUT_FILTER is applied. -# -# Note that for custom extensions or not directly supported extensions you also -# need to set EXTENSION_MAPPING for the extension otherwise the files are not -# properly processed by doxygen. - -FILTER_PATTERNS = - -# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using -# INPUT_FILTER) will also be used to filter the input files that are used for -# producing the source files to browse (i.e. when SOURCE_BROWSER is set to YES). -# The default value is: NO. - -FILTER_SOURCE_FILES = NO - -# The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file -# pattern. A pattern will override the setting for FILTER_PATTERN (if any) and -# it is also possible to disable source filtering for a specific pattern using -# *.ext= (so without naming a filter). -# This tag requires that the tag FILTER_SOURCE_FILES is set to YES. - -FILTER_SOURCE_PATTERNS = - -# If the USE_MDFILE_AS_MAINPAGE tag refers to the name of a markdown file that -# is part of the input, its contents will be placed on the main page -# (index.html). This can be useful if you have a project on for instance GitHub -# and want to reuse the introduction page also for the doxygen output. - -INPUT += "README.md" -USE_MDFILE_AS_MAINPAGE = "README.md" - -#--------------------------------------------------------------------------- -# Configuration options related to source browsing -#--------------------------------------------------------------------------- - -# If the SOURCE_BROWSER tag is set to YES then a list of source files will be -# generated. Documented entities will be cross-referenced with these sources. -# -# Note: To get rid of all source code in the generated output, make sure that -# also VERBATIM_HEADERS is set to NO. -# The default value is: NO. - -SOURCE_BROWSER = NO - -# Setting the INLINE_SOURCES tag to YES will include the body of functions, -# classes and enums directly into the documentation. -# The default value is: NO. - -INLINE_SOURCES = NO - -# Setting the STRIP_CODE_COMMENTS tag to YES will instruct doxygen to hide any -# special comment blocks from generated source code fragments. Normal C, C++ and -# Fortran comments will always remain visible. -# The default value is: YES. - -STRIP_CODE_COMMENTS = YES - -# If the REFERENCED_BY_RELATION tag is set to YES then for each documented -# entity all documented functions referencing it will be listed. -# The default value is: NO. - -REFERENCED_BY_RELATION = NO - -# If the REFERENCES_RELATION tag is set to YES then for each documented function -# all documented entities called/used by that function will be listed. -# The default value is: NO. - -REFERENCES_RELATION = NO - -# If the REFERENCES_LINK_SOURCE tag is set to YES and SOURCE_BROWSER tag is set -# to YES then the hyperlinks from functions in REFERENCES_RELATION and -# REFERENCED_BY_RELATION lists will link to the source code. Otherwise they will -# link to the documentation. -# The default value is: YES. - -REFERENCES_LINK_SOURCE = YES - -# If SOURCE_TOOLTIPS is enabled (the default) then hovering a hyperlink in the -# source code will show a tooltip with additional information such as prototype, -# brief description and links to the definition and documentation. Since this -# will make the HTML file larger and loading of large files a bit slower, you -# can opt to disable this feature. -# The default value is: YES. -# This tag requires that the tag SOURCE_BROWSER is set to YES. - -SOURCE_TOOLTIPS = YES - -# If the USE_HTAGS tag is set to YES then the references to source code will -# point to the HTML generated by the htags(1) tool instead of doxygen built-in -# source browser. The htags tool is part of GNU's global source tagging system -# (see https://www.gnu.org/software/global/global.html). You will need version -# 4.8.6 or higher. -# -# To use it do the following: -# - Install the latest version of global -# - Enable SOURCE_BROWSER and USE_HTAGS in the configuration file -# - Make sure the INPUT points to the root of the source tree -# - Run doxygen as normal -# -# Doxygen will invoke htags (and that will in turn invoke gtags), so these -# tools must be available from the command line (i.e. in the search path). -# -# The result: instead of the source browser generated by doxygen, the links to -# source code will now point to the output of htags. -# The default value is: NO. -# This tag requires that the tag SOURCE_BROWSER is set to YES. - -USE_HTAGS = NO - -# If the VERBATIM_HEADERS tag is set the YES then doxygen will generate a -# verbatim copy of the header file for each class for which an include is -# specified. Set to NO to disable this. -# See also: Section \class. -# The default value is: YES. - -VERBATIM_HEADERS = YES - -#--------------------------------------------------------------------------- -# Configuration options related to the alphabetical class index -#--------------------------------------------------------------------------- - -# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index of all -# compounds will be generated. Enable this if the project contains a lot of -# classes, structs, unions or interfaces. -# The default value is: YES. - -ALPHABETICAL_INDEX = YES - -# In case all classes in a project start with a common prefix, all classes will -# be put under the same header in the alphabetical index. The IGNORE_PREFIX tag -# can be used to specify a prefix (or a list of prefixes) that should be ignored -# while generating the index headers. -# This tag requires that the tag ALPHABETICAL_INDEX is set to YES. - -IGNORE_PREFIX = - -#--------------------------------------------------------------------------- -# Configuration options related to the HTML output -#--------------------------------------------------------------------------- - -# If the GENERATE_HTML tag is set to YES, doxygen will generate HTML output -# The default value is: YES. - -GENERATE_HTML = YES - -# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. If a -# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of -# it. -# The default directory is: html. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_OUTPUT = docs/html - -# The HTML_FILE_EXTENSION tag can be used to specify the file extension for each -# generated HTML page (for example: .htm, .php, .asp). -# The default value is: .html. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_FILE_EXTENSION = .html - -# The HTML_HEADER tag can be used to specify a user-defined HTML header file for -# each generated HTML page. If the tag is left blank doxygen will generate a -# standard header. -# -# To get valid HTML the header file that includes any scripts and style sheets -# that doxygen needs, which is dependent on the configuration options used (e.g. -# the setting GENERATE_TREEVIEW). It is highly recommended to start with a -# default header using -# doxygen -w html new_header.html new_footer.html new_stylesheet.css -# YourConfigFile -# and then modify the file new_header.html. See also section "Doxygen usage" -# for information on how to generate the default header that doxygen normally -# uses. -# Note: The header is subject to change so you typically have to regenerate the -# default header when upgrading to a newer version of doxygen. For a description -# of the possible markers and block names see the documentation. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_HEADER = - -# The HTML_FOOTER tag can be used to specify a user-defined HTML footer for each -# generated HTML page. If the tag is left blank doxygen will generate a standard -# footer. See HTML_HEADER for more information on how to generate a default -# footer and what special commands can be used inside the footer. See also -# section "Doxygen usage" for information on how to generate the default footer -# that doxygen normally uses. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_FOOTER = - -# The HTML_STYLESHEET tag can be used to specify a user-defined cascading style -# sheet that is used by each HTML page. It can be used to fine-tune the look of -# the HTML output. If left blank doxygen will generate a default style sheet. -# See also section "Doxygen usage" for information on how to generate the style -# sheet that doxygen normally uses. -# Note: It is recommended to use HTML_EXTRA_STYLESHEET instead of this tag, as -# it is more robust and this tag (HTML_STYLESHEET) will in the future become -# obsolete. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_EXTRA_STYLESHEET = docs/doxygen-awesome.css - -# The HTML_EXTRA_FILES tag can be used to specify one or more extra images or -# other source files which should be copied to the HTML output directory. Note -# that these files will be copied to the base HTML output directory. Use the -# $relpath^ marker in the HTML_HEADER and/or HTML_FOOTER files to load these -# files. In the HTML_STYLESHEET file, use the file name only. Also note that the -# files will be copied as-is; there are no commands or markers available. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_EXTRA_FILES = - -# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. Doxygen -# will adjust the colors in the style sheet and background images according to -# this color. Hue is specified as an angle on a color-wheel, see -# https://en.wikipedia.org/wiki/Hue for more information. For instance the value -# 0 represents red, 60 is yellow, 120 is green, 180 is cyan, 240 is blue, 300 -# purple, and 360 is red again. -# Minimum value: 0, maximum value: 359, default value: 220. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_COLORSTYLE_HUE = 220 - -# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of the colors -# in the HTML output. For a value of 0 the output will use gray-scales only. A -# value of 255 will produce the most vivid colors. -# Minimum value: 0, maximum value: 255, default value: 100. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_COLORSTYLE_SAT = 100 - -# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to the -# luminance component of the colors in the HTML output. Values below 100 -# gradually make the output lighter, whereas values above 100 make the output -# darker. The value divided by 100 is the actual gamma applied, so 80 represents -# a gamma of 0.8, The value 220 represents a gamma of 2.2, and 100 does not -# change the gamma. -# Minimum value: 40, maximum value: 240, default value: 80. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_COLORSTYLE_GAMMA = 80 - -# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML -# page will contain the date and time when the page was generated. Setting this -# to YES can help to show when doxygen was last run and thus if the -# documentation is up to date. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_TIMESTAMP = NO - -# If the HTML_DYNAMIC_MENUS tag is set to YES then the generated HTML -# documentation will contain a main index with vertical navigation menus that -# are dynamically created via JavaScript. If disabled, the navigation index will -# consists of multiple levels of tabs that are statically embedded in every HTML -# page. Disable this option to support browsers that do not have JavaScript, -# like the Qt help browser. -# The default value is: YES. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_DYNAMIC_MENUS = YES - -# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML -# documentation will contain sections that can be hidden and shown after the -# page has loaded. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_DYNAMIC_SECTIONS = NO - -# With HTML_INDEX_NUM_ENTRIES one can control the preferred number of entries -# shown in the various tree structured indices initially; the user can expand -# and collapse entries dynamically later on. Doxygen will expand the tree to -# such a level that at most the specified number of entries are visible (unless -# a fully collapsed tree already exceeds this amount). So setting the number of -# entries 1 will produce a full collapsed tree by default. 0 is a special value -# representing an infinite number of entries and will result in a full expanded -# tree by default. -# Minimum value: 0, maximum value: 9999, default value: 100. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_INDEX_NUM_ENTRIES = 100 - -# If the GENERATE_DOCSET tag is set to YES, additional index files will be -# generated that can be used as input for Apple's Xcode 3 integrated development -# environment (see: -# https://developer.apple.com/xcode/), introduced with OSX 10.5 (Leopard). To -# create a documentation set, doxygen will generate a Makefile in the HTML -# output directory. Running make will produce the docset in that directory and -# running make install will install the docset in -# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find it at -# startup. See https://developer.apple.com/library/archive/featuredarticles/Doxy -# genXcode/_index.html for more information. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -GENERATE_DOCSET = NO - -# This tag determines the name of the docset feed. A documentation feed provides -# an umbrella under which multiple documentation sets from a single provider -# (such as a company or product suite) can be grouped. -# The default value is: Doxygen generated docs. -# This tag requires that the tag GENERATE_DOCSET is set to YES. - -DOCSET_FEEDNAME = "Doxygen generated docs" - -# This tag determines the URL of the docset feed. A documentation feed provides -# an umbrella under which multiple documentation sets from a single provider -# (such as a company or product suite) can be grouped. -# This tag requires that the tag GENERATE_DOCSET is set to YES. - -DOCSET_FEEDURL = - -# This tag specifies a string that should uniquely identify the documentation -# set bundle. This should be a reverse domain-name style string, e.g. -# com.mycompany.MyDocSet. Doxygen will append .docset to the name. -# The default value is: org.doxygen.Project. -# This tag requires that the tag GENERATE_DOCSET is set to YES. - -DOCSET_BUNDLE_ID = org.doxygen.Project - -# The DOCSET_PUBLISHER_ID tag specifies a string that should uniquely identify -# the documentation publisher. This should be a reverse domain-name style -# string, e.g. com.mycompany.MyDocSet.documentation. -# The default value is: org.doxygen.Publisher. -# This tag requires that the tag GENERATE_DOCSET is set to YES. - -DOCSET_PUBLISHER_ID = org.doxygen.Publisher - -# The DOCSET_PUBLISHER_NAME tag identifies the documentation publisher. -# The default value is: Publisher. -# This tag requires that the tag GENERATE_DOCSET is set to YES. - -DOCSET_PUBLISHER_NAME = Publisher - -# If the GENERATE_HTMLHELP tag is set to YES then doxygen generates three -# additional HTML index files: index.hhp, index.hhc, and index.hhk. The -# index.hhp is a project file that can be read by Microsoft's HTML Help Workshop -# on Windows. In the beginning of 2021 Microsoft took the original page, with -# a.o. the download links, offline the HTML help workshop was already many years -# in maintenance mode). You can download the HTML help workshop from the web -# archives at Installation executable (see: -# http://web.archive.org/web/20160201063255/http://download.microsoft.com/downlo -# ad/0/A/9/0A939EF6-E31C-430F-A3DF-DFAE7960D564/htmlhelp.exe). -# -# The HTML Help Workshop contains a compiler that can convert all HTML output -# generated by doxygen into a single compiled HTML file (.chm). Compiled HTML -# files are now used as the Windows 98 help format, and will replace the old -# Windows help format (.hlp) on all Windows platforms in the future. Compressed -# HTML files also contain an index, a table of contents, and you can search for -# words in the documentation. The HTML workshop also contains a viewer for -# compressed HTML files. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -GENERATE_HTMLHELP = NO - -# The CHM_FILE tag can be used to specify the file name of the resulting .chm -# file. You can add a path in front of the file if the result should not be -# written to the html output directory. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -CHM_FILE = - -# The HHC_LOCATION tag can be used to specify the location (absolute path -# including file name) of the HTML help compiler (hhc.exe). If non-empty, -# doxygen will try to run the HTML help compiler on the generated index.hhp. -# The file has to be specified with full path. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -HHC_LOCATION = - -# The GENERATE_CHI flag controls if a separate .chi index file is generated -# (YES) or that it should be included in the main .chm file (NO). -# The default value is: NO. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -GENERATE_CHI = NO - -# The CHM_INDEX_ENCODING is used to encode HtmlHelp index (hhk), content (hhc) -# and project file content. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -CHM_INDEX_ENCODING = - -# The BINARY_TOC flag controls whether a binary table of contents is generated -# (YES) or a normal table of contents (NO) in the .chm file. Furthermore it -# enables the Previous and Next buttons. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -BINARY_TOC = NO - -# The TOC_EXPAND flag can be set to YES to add extra items for group members to -# the table of contents of the HTML help documentation and to the tree view. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -TOC_EXPAND = NO - -# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and -# QHP_VIRTUAL_FOLDER are set, an additional index file will be generated that -# can be used as input for Qt's qhelpgenerator to generate a Qt Compressed Help -# (.qch) of the generated HTML documentation. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -GENERATE_QHP = NO - -# If the QHG_LOCATION tag is specified, the QCH_FILE tag can be used to specify -# the file name of the resulting .qch file. The path specified is relative to -# the HTML output folder. -# This tag requires that the tag GENERATE_QHP is set to YES. - -QCH_FILE = - -# The QHP_NAMESPACE tag specifies the namespace to use when generating Qt Help -# Project output. For more information please see Qt Help Project / Namespace -# (see: -# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#namespace). -# The default value is: org.doxygen.Project. -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHP_NAMESPACE = org.doxygen.Project - -# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating Qt -# Help Project output. For more information please see Qt Help Project / Virtual -# Folders (see: -# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#virtual-folders). -# The default value is: doc. -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHP_VIRTUAL_FOLDER = doc - -# If the QHP_CUST_FILTER_NAME tag is set, it specifies the name of a custom -# filter to add. For more information please see Qt Help Project / Custom -# Filters (see: -# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom-filters). -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHP_CUST_FILTER_NAME = - -# The QHP_CUST_FILTER_ATTRS tag specifies the list of the attributes of the -# custom filter to add. For more information please see Qt Help Project / Custom -# Filters (see: -# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom-filters). -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHP_CUST_FILTER_ATTRS = - -# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this -# project's filter section matches. Qt Help Project / Filter Attributes (see: -# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#filter-attributes). -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHP_SECT_FILTER_ATTRS = - -# The QHG_LOCATION tag can be used to specify the location (absolute path -# including file name) of Qt's qhelpgenerator. If non-empty doxygen will try to -# run qhelpgenerator on the generated .qhp file. -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHG_LOCATION = - -# If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files will be -# generated, together with the HTML files, they form an Eclipse help plugin. To -# install this plugin and make it available under the help contents menu in -# Eclipse, the contents of the directory containing the HTML and XML files needs -# to be copied into the plugins directory of eclipse. The name of the directory -# within the plugins directory should be the same as the ECLIPSE_DOC_ID value. -# After copying Eclipse needs to be restarted before the help appears. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -GENERATE_ECLIPSEHELP = NO - -# A unique identifier for the Eclipse help plugin. When installing the plugin -# the directory name containing the HTML and XML files should also have this -# name. Each documentation set should have its own identifier. -# The default value is: org.doxygen.Project. -# This tag requires that the tag GENERATE_ECLIPSEHELP is set to YES. - -ECLIPSE_DOC_ID = org.doxygen.Project - -# If you want full control over the layout of the generated HTML pages it might -# be necessary to disable the index and replace it with your own. The -# DISABLE_INDEX tag can be used to turn on/off the condensed index (tabs) at top -# of each HTML page. A value of NO enables the index and the value YES disables -# it. Since the tabs in the index contain the same information as the navigation -# tree, you can set this option to YES if you also set GENERATE_TREEVIEW to YES. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -DISABLE_INDEX = NO - -# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index -# structure should be generated to display hierarchical information. If the tag -# value is set to YES, a side panel will be generated containing a tree-like -# index structure (just like the one that is generated for HTML Help). For this -# to work a browser that supports JavaScript, DHTML, CSS and frames is required -# (i.e. any modern browser). Windows users are probably better off using the -# HTML help feature. Via custom style sheets (see HTML_EXTRA_STYLESHEET) one can -# further fine tune the look of the index (see "Fine-tuning the output"). As an -# example, the default style sheet generated by doxygen has an example that -# shows how to put an image at the root of the tree instead of the PROJECT_NAME. -# Since the tree basically has the same information as the tab index, you could -# consider setting DISABLE_INDEX to YES when enabling this option. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -GENERATE_TREEVIEW = YES - -# When both GENERATE_TREEVIEW and DISABLE_INDEX are set to YES, then the -# FULL_SIDEBAR option determines if the side bar is limited to only the treeview -# area (value NO) or if it should extend to the full height of the window (value -# YES). Setting this to YES gives a layout similar to -# https://docs.readthedocs.io with more room for contents, but less room for the -# project logo, title, and description. If either GENERATE_TREEVIEW or -# DISABLE_INDEX is set to NO, this option has no effect. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -FULL_SIDEBAR = NO - -# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values that -# doxygen will group on one line in the generated HTML documentation. -# -# Note that a value of 0 will completely suppress the enum values from appearing -# in the overview section. -# Minimum value: 0, maximum value: 20, default value: 4. -# This tag requires that the tag GENERATE_HTML is set to YES. - -ENUM_VALUES_PER_LINE = 4 - -# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be used -# to set the initial width (in pixels) of the frame in which the tree is shown. -# Minimum value: 0, maximum value: 1500, default value: 250. -# This tag requires that the tag GENERATE_HTML is set to YES. - -TREEVIEW_WIDTH = 250 - -# If the EXT_LINKS_IN_WINDOW option is set to YES, doxygen will open links to -# external symbols imported via tag files in a separate window. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -EXT_LINKS_IN_WINDOW = NO - -# If the OBFUSCATE_EMAILS tag is set to YES, doxygen will obfuscate email -# addresses. -# The default value is: YES. -# This tag requires that the tag GENERATE_HTML is set to YES. - -OBFUSCATE_EMAILS = YES - -# If the HTML_FORMULA_FORMAT option is set to svg, doxygen will use the pdf2svg -# tool (see https://github.com/dawbarton/pdf2svg) or inkscape (see -# https://inkscape.org) to generate formulas as SVG images instead of PNGs for -# the HTML output. These images will generally look nicer at scaled resolutions. -# Possible values are: png (the default) and svg (looks nicer but requires the -# pdf2svg or inkscape tool). -# The default value is: png. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_FORMULA_FORMAT = png - -# Use this tag to change the font size of LaTeX formulas included as images in -# the HTML documentation. When you change the font size after a successful -# doxygen run you need to manually remove any form_*.png images from the HTML -# output directory to force them to be regenerated. -# Minimum value: 8, maximum value: 50, default value: 10. -# This tag requires that the tag GENERATE_HTML is set to YES. - -FORMULA_FONTSIZE = 10 - -# Use the FORMULA_TRANSPARENT tag to determine whether or not the images -# generated for formulas are transparent PNGs. Transparent PNGs are not -# supported properly for IE 6.0, but are supported on all modern browsers. -# -# Note that when changing this option you need to delete any form_*.png files in -# the HTML output directory before the changes have effect. -# The default value is: YES. -# This tag requires that the tag GENERATE_HTML is set to YES. - -FORMULA_TRANSPARENT = YES - -# The FORMULA_MACROFILE can contain LaTeX \newcommand and \renewcommand commands -# to create new LaTeX commands to be used in formulas as building blocks. See -# the section "Including formulas" for details. - -FORMULA_MACROFILE = - -# Enable the USE_MATHJAX option to render LaTeX formulas using MathJax (see -# https://www.mathjax.org) which uses client side JavaScript for the rendering -# instead of using pre-rendered bitmaps. Use this if you do not have LaTeX -# installed or if you want to formulas look prettier in the HTML output. When -# enabled you may also need to install MathJax separately and configure the path -# to it using the MATHJAX_RELPATH option. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -USE_MATHJAX = YES - -# With MATHJAX_VERSION it is possible to specify the MathJax version to be used. -# Note that the different versions of MathJax have different requirements with -# regards to the different settings, so it is possible that also other MathJax -# settings have to be changed when switching between the different MathJax -# versions. -# Possible values are: MathJax_2 and MathJax_3. -# The default value is: MathJax_2. -# This tag requires that the tag USE_MATHJAX is set to YES. - -MATHJAX_VERSION = MathJax_3 - -# When MathJax is enabled you can set the default output format to be used for -# the MathJax output. For more details about the output format see MathJax -# version 2 (see: -# http://docs.mathjax.org/en/v2.7-latest/output.html) and MathJax version 3 -# (see: -# http://docs.mathjax.org/en/latest/web/components/output.html). -# Possible values are: HTML-CSS (which is slower, but has the best -# compatibility. This is the name for Mathjax version 2, for MathJax version 3 -# this will be translated into chtml), NativeMML (i.e. MathML. Only supported -# for NathJax 2. For MathJax version 3 chtml will be used instead.), chtml (This -# is the name for Mathjax version 3, for MathJax version 2 this will be -# translated into HTML-CSS) and SVG. -# The default value is: HTML-CSS. -# This tag requires that the tag USE_MATHJAX is set to YES. - -MATHJAX_FORMAT = HTML-CSS - -# When MathJax is enabled you need to specify the location relative to the HTML -# output directory using the MATHJAX_RELPATH option. The destination directory -# should contain the MathJax.js script. For instance, if the mathjax directory -# is located at the same level as the HTML output directory, then -# MATHJAX_RELPATH should be ../mathjax. The default value points to the MathJax -# Content Delivery Network so you can quickly see the result without installing -# MathJax. However, it is strongly recommended to install a local copy of -# MathJax from https://www.mathjax.org before deployment. The default value is: -# - in case of MathJax version 2: https://cdn.jsdelivr.net/npm/mathjax@2 -# - in case of MathJax version 3: https://cdn.jsdelivr.net/npm/mathjax@3 -# This tag requires that the tag USE_MATHJAX is set to YES. - -MATHJAX_RELPATH = - -# The MATHJAX_EXTENSIONS tag can be used to specify one or more MathJax -# extension names that should be enabled during MathJax rendering. For example -# for MathJax version 2 (see https://docs.mathjax.org/en/v2.7-latest/tex.html -# #tex-and-latex-extensions): -# MATHJAX_EXTENSIONS = TeX/AMSmath TeX/AMSsymbols -# For example for MathJax version 3 (see -# http://docs.mathjax.org/en/latest/input/tex/extensions/index.html): -# MATHJAX_EXTENSIONS = ams -# This tag requires that the tag USE_MATHJAX is set to YES. - -MATHJAX_EXTENSIONS = - -# The MATHJAX_CODEFILE tag can be used to specify a file with javascript pieces -# of code that will be used on startup of the MathJax code. See the MathJax site -# (see: -# http://docs.mathjax.org/en/v2.7-latest/output.html) for more details. For an -# example see the documentation. -# This tag requires that the tag USE_MATHJAX is set to YES. - -MATHJAX_CODEFILE = - -# When the SEARCHENGINE tag is enabled doxygen will generate a search box for -# the HTML output. The underlying search engine uses javascript and DHTML and -# should work on any modern browser. Note that when using HTML help -# (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets (GENERATE_DOCSET) -# there is already a search function so this one should typically be disabled. -# For large projects the javascript based search engine can be slow, then -# enabling SERVER_BASED_SEARCH may provide a better solution. It is possible to -# search using the keyboard; to jump to the search box use + S -# (what the is depends on the OS and browser, but it is typically -# , /