From 17d2885ab2150c1dfb7e676483a695f50bdecc7b Mon Sep 17 00:00:00 2001 From: okcroboticsteam Date: Thu, 12 Jan 2023 17:26:11 -0600 Subject: [PATCH 01/28] added hardware files --- src/main/include/hardware/actuatorInterface | 51 ++++++++ src/main/include/hardware/hardwareInterface | 51 ++++++++ .../include/hardware/hardwareInterface.cpp | 117 ++++++++++++++++++ src/main/include/hardware/sensorInterface | 25 ++++ 4 files changed, 244 insertions(+) create mode 100644 src/main/include/hardware/actuatorInterface create mode 100644 src/main/include/hardware/hardwareInterface create mode 100644 src/main/include/hardware/hardwareInterface.cpp create mode 100644 src/main/include/hardware/sensorInterface diff --git a/src/main/include/hardware/actuatorInterface b/src/main/include/hardware/actuatorInterface new file mode 100644 index 0000000..c456ed3 --- /dev/null +++ b/src/main/include/hardware/actuatorInterface @@ -0,0 +1,51 @@ +#pragma once + +#include +#include +#include + + +// CTRE namespace +namespace ctre_can = ctre::phoenix::motorcontrol::can; + +// Brushless Motor +#define BRUSHLESS rev::CANSparkMax::MotorType::kBrushless + +// Coast +#define COAST rev::CANSparkMax::IdleMode::kCoast + +// CAN IDs +#define LEFT_MOTOR_1 1 +#define LEFT_MOTOR_2 2 +#define LEFT_MOTOR_3 3 +#define RIGHT_MOTOR_1 4 +#define RIGHT_MOTOR_2 5 +#define RIGHT_MOTOR_3 6 + +#define INDEXER_MOTOR 7 +#define INTAKE_POSITION_MOTOR 10 +#define INTAKE_MOTOR 11 + +#define SHOOTER_MOTOR 8 +#define TRIGGER_MOTOR 9 + +typedef struct actuator_interface_t { + // Left drivetrain motors + std::unique_ptr left_motor_1; + std::unique_ptr left_motor_2; + std::unique_ptr left_motor_3; + + // Right drivetrain motors + std::unique_ptr right_motor_1; + std::unique_ptr right_motor_2; + std::unique_ptr right_motor_3; + + // intake motors + std::unique_ptr intake_position_motor; + std::unique_ptr intake_motor; + std::unique_ptr indexer_motor; + + // Shooter motors + std::unique_ptr shooter_motor; + std::unique_ptr trigger_motor; +} ActuatorInterface; \ No newline at end of file diff --git a/src/main/include/hardware/hardwareInterface b/src/main/include/hardware/hardwareInterface new file mode 100644 index 0000000..c456ed3 --- /dev/null +++ b/src/main/include/hardware/hardwareInterface @@ -0,0 +1,51 @@ +#pragma once + +#include +#include +#include + + +// CTRE namespace +namespace ctre_can = ctre::phoenix::motorcontrol::can; + +// Brushless Motor +#define BRUSHLESS rev::CANSparkMax::MotorType::kBrushless + +// Coast +#define COAST rev::CANSparkMax::IdleMode::kCoast + +// CAN IDs +#define LEFT_MOTOR_1 1 +#define LEFT_MOTOR_2 2 +#define LEFT_MOTOR_3 3 +#define RIGHT_MOTOR_1 4 +#define RIGHT_MOTOR_2 5 +#define RIGHT_MOTOR_3 6 + +#define INDEXER_MOTOR 7 +#define INTAKE_POSITION_MOTOR 10 +#define INTAKE_MOTOR 11 + +#define SHOOTER_MOTOR 8 +#define TRIGGER_MOTOR 9 + +typedef struct actuator_interface_t { + // Left drivetrain motors + std::unique_ptr left_motor_1; + std::unique_ptr left_motor_2; + std::unique_ptr left_motor_3; + + // Right drivetrain motors + std::unique_ptr right_motor_1; + std::unique_ptr right_motor_2; + std::unique_ptr right_motor_3; + + // intake motors + std::unique_ptr intake_position_motor; + std::unique_ptr intake_motor; + std::unique_ptr indexer_motor; + + // Shooter motors + std::unique_ptr shooter_motor; + std::unique_ptr trigger_motor; +} ActuatorInterface; \ No newline at end of file diff --git a/src/main/include/hardware/hardwareInterface.cpp b/src/main/include/hardware/hardwareInterface.cpp new file mode 100644 index 0000000..d1830dd --- /dev/null +++ b/src/main/include/hardware/hardwareInterface.cpp @@ -0,0 +1,117 @@ + + + +#include "hardware/HardwareInterface.h" + +bool SetupDrivetrainInterface( + std::unique_ptr &hardware, + std::shared_ptr *interface) { + OKC_CHECK(interface != nullptr); + OKC_CHECK(hardware->actuators != nullptr); + OKC_CHECK(hardware->sensors != nullptr); + + // Get actuators interface for drivetrain. + std::unique_ptr &actuators = hardware->actuators; + std::unique_ptr &sensors = hardware->sensors; + + // Build motor control groups and differential drive. + frc::MotorControllerGroup left_motors{*actuators->left_motor_1, + *actuators->left_motor_2, + *actuators->left_motor_3}; + + frc::MotorControllerGroup right_motors{*actuators->right_motor_1, + *actuators->right_motor_2, + *actuators->right_motor_3}; + // motors face opposite directions so +1 for left side is opposite +1 for + // right side, this fixes that + right_motors.SetInverted(true); + + // Ensure the differential drivetrain is un-initialized. + OKC_CHECK(hardware->diff_drive == nullptr); + + // Create the differential drive. + hardware->diff_drive = + std::make_unique(left_motors, right_motors); + + // Protect against nullptr actuators/sensors + OKC_CHECK(actuators->left_motor_1 != nullptr); + OKC_CHECK(actuators->left_motor_2 != nullptr); + OKC_CHECK(actuators->left_motor_3 != nullptr); + OKC_CHECK(actuators->right_motor_1 != nullptr); + OKC_CHECK(actuators->right_motor_2 != nullptr); + OKC_CHECK(actuators->right_motor_3 != nullptr); + OKC_CHECK(hardware->diff_drive != nullptr); + OKC_CHECK(sensors->ahrs != nullptr); + + // Set up drivetrain interface. + DrivetrainHardwareInterface drivetrain_interface = { + actuators->left_motor_1.get(), actuators->left_motor_2.get(), + actuators->left_motor_3.get(), actuators->right_motor_1.get(), + actuators->right_motor_2.get(), actuators->right_motor_3.get(), + hardware->diff_drive.get(), hardware->sensors->ahrs.get()}; + + // Set the output interface + *interface = + std::make_shared(drivetrain_interface); + + return true; +} + +bool SetupIntakeInterface(std::unique_ptr &hardware, + std::shared_ptr *interface) { + OKC_CHECK(interface != nullptr); + OKC_CHECK(hardware->actuators != nullptr); + OKC_CHECK(hardware->sensors != nullptr); + + // Get actuators interface for intake. + std::unique_ptr &actuators = hardware->actuators; + std::unique_ptr &sensors = hardware->sensors; + + // Protect against nullptr actuators/sensors + OKC_CHECK(actuators->intake_position_motor != nullptr); + OKC_CHECK(actuators->intake_motor != nullptr); + OKC_CHECK(actuators->indexer_motor != nullptr); + OKC_CHECK(sensors->retracted_limit_switch != nullptr); + OKC_CHECK(sensors->deploy_limit_switch != nullptr); + + // Set up intake interface. + IntakeHardwareInterface intake_interface = { + actuators->intake_position_motor.get(), + actuators->intake_motor.get(), + actuators->indexer_motor.get(), + + sensors->retracted_limit_switch.get(), + sensors->deploy_limit_switch.get(), + }; + + // Set the output interface + *interface = std::make_shared(intake_interface); + + return true; +} + +bool SetupShooterInterface( + std::unique_ptr &hardware, + std::shared_ptr *interface) { + OKC_CHECK(interface != nullptr); + OKC_CHECK(hardware->actuators != nullptr); + OKC_CHECK(hardware->sensors != nullptr); + + // Get actuators and sensors interfaces for shooter. + std::unique_ptr &actuators = hardware->actuators; + std::unique_ptr &sensors = hardware->sensors; + + // Protect against nullptr actuators/sensors + OKC_CHECK(actuators->shooter_motor != nullptr); + OKC_CHECK(actuators->trigger_motor != nullptr); + OKC_CHECK(sensors->ball_detector != nullptr); + + ShooterHardwareInterface shooter_interface = { + actuators->shooter_motor.get(), actuators->trigger_motor.get(), + sensors->ball_detector.get()}; + + // Set the output interface + *interface = std::make_shared(shooter_interface); + + return true; +} diff --git a/src/main/include/hardware/sensorInterface b/src/main/include/hardware/sensorInterface new file mode 100644 index 0000000..070cea3 --- /dev/null +++ b/src/main/include/hardware/sensorInterface @@ -0,0 +1,25 @@ +#pragma once + +#include + +#include "AHRS.h" +#include +#include + +// == sensor ports == +#define DEPLOY_LIMIT_SWITCH 2 +#define RETRACTED_LIMIT_SWITCH 3 + +#define BALL_DETECTOR 9 + +typedef struct sensors_t { + // navX IMU + std::unique_ptr ahrs; + + // intake limit switches + std::unique_ptr deploy_limit_switch; + std::unique_ptr retracted_limit_switch; + + // Shooter ball detector + std::unique_ptr ball_detector; +} SensorInterface; \ No newline at end of file From b8d2f6e5a34f8c0e5fa63075359696308d787683 Mon Sep 17 00:00:00 2001 From: okcroboticsteam Date: Thu, 12 Jan 2023 17:44:02 -0600 Subject: [PATCH 02/28] changed names of motors --- .vscode/settings.json | 75 ++++++++++- src/main/cpp/hardware/hardwareInterface.cpp | 5 + ...{actuatorInterface => actuatorInterface.h} | 24 ++-- src/main/include/hardware/hardwareInterface | 51 -------- .../include/hardware/hardwareInterface.cpp | 117 ------------------ src/main/include/hardware/hardwareInterface.h | 64 ++++++++++ .../{sensorInterface => sensorInterface.h} | 0 7 files changed, 156 insertions(+), 180 deletions(-) create mode 100644 src/main/cpp/hardware/hardwareInterface.cpp rename src/main/include/hardware/{actuatorInterface => actuatorInterface.h} (57%) delete mode 100644 src/main/include/hardware/hardwareInterface delete mode 100644 src/main/include/hardware/hardwareInterface.cpp create mode 100644 src/main/include/hardware/hardwareInterface.h rename src/main/include/hardware/{sensorInterface => sensorInterface.h} (100%) diff --git a/.vscode/settings.json b/.vscode/settings.json index 5e795ff..1899fd1 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -14,5 +14,78 @@ "**/.factorypath": true, "**/*~": true }, - "C_Cpp.default.configurationProvider": "vscode-wpilib" + "C_Cpp.default.configurationProvider": "vscode-wpilib", + "files.associations": { + "array": "cpp", + "atomic": "cpp", + "bit": "cpp", + "*.tcc": "cpp", + "bitset": "cpp", + "cctype": "cpp", + "cfenv": "cpp", + "chrono": "cpp", + "clocale": "cpp", + "cmath": "cpp", + "codecvt": "cpp", + "compare": "cpp", + "complex": "cpp", + "concepts": "cpp", + "condition_variable": "cpp", + "cstdarg": "cpp", + "cstddef": "cpp", + "cstdint": "cpp", + "cstdio": "cpp", + "cstdlib": "cpp", + "cstring": "cpp", + "ctime": "cpp", + "cwchar": "cpp", + "cwctype": "cpp", + "deque": "cpp", + "list": "cpp", + "map": "cpp", + "set": "cpp", + "string": "cpp", + "unordered_map": "cpp", + "unordered_set": "cpp", + "vector": "cpp", + "exception": "cpp", + "algorithm": "cpp", + "functional": "cpp", + "iterator": "cpp", + "memory": "cpp", + "memory_resource": "cpp", + "numeric": "cpp", + "optional": "cpp", + "random": "cpp", + "ratio": "cpp", + "regex": "cpp", + "string_view": "cpp", + "system_error": "cpp", + "tuple": "cpp", + "type_traits": "cpp", + "utility": "cpp", + "fstream": "cpp", + "future": "cpp", + "initializer_list": "cpp", + "iomanip": "cpp", + "iosfwd": "cpp", + "iostream": "cpp", + "istream": "cpp", + "limits": "cpp", + "mutex": "cpp", + "new": "cpp", + "numbers": "cpp", + "ostream": "cpp", + "semaphore": "cpp", + "span": "cpp", + "sstream": "cpp", + "stdexcept": "cpp", + "stop_token": "cpp", + "streambuf": "cpp", + "thread": "cpp", + "cinttypes": "cpp", + "typeindex": "cpp", + "typeinfo": "cpp", + "variant": "cpp" + } } diff --git a/src/main/cpp/hardware/hardwareInterface.cpp b/src/main/cpp/hardware/hardwareInterface.cpp new file mode 100644 index 0000000..41790db --- /dev/null +++ b/src/main/cpp/hardware/hardwareInterface.cpp @@ -0,0 +1,5 @@ + + + +#include "hardware/HardwareInterface.h" + diff --git a/src/main/include/hardware/actuatorInterface b/src/main/include/hardware/actuatorInterface.h similarity index 57% rename from src/main/include/hardware/actuatorInterface rename to src/main/include/hardware/actuatorInterface.h index c456ed3..d7c0524 100644 --- a/src/main/include/hardware/actuatorInterface +++ b/src/main/include/hardware/actuatorInterface.h @@ -31,19 +31,21 @@ namespace ctre_can = ctre::phoenix::motorcontrol::can; typedef struct actuator_interface_t { // Left drivetrain motors - std::unique_ptr left_motor_1; - std::unique_ptr left_motor_2; - std::unique_ptr left_motor_3; + std::unique_ptr left_front_drive; + std::unique_ptr left_back_drive; + std::unique_ptr left_front_steer; + std::unique_ptr left_back_steer; // Right drivetrain motors - std::unique_ptr right_motor_1; - std::unique_ptr right_motor_2; - std::unique_ptr right_motor_3; - - // intake motors - std::unique_ptr intake_position_motor; - std::unique_ptr intake_motor; - std::unique_ptr indexer_motor; + std::unique_ptr right_front_drive; + std::unique_ptr right_back_drive; + std::unique_ptr right_front_steer; + std::unique_ptr right_back_steer; + + // arm motors + std::unique_ptr arm_lift_motor; + std::unique_ptr arm_up_motor; + std::unique_ptr arm_extend_motor; // Shooter motors std::unique_ptr shooter_motor; diff --git a/src/main/include/hardware/hardwareInterface b/src/main/include/hardware/hardwareInterface deleted file mode 100644 index c456ed3..0000000 --- a/src/main/include/hardware/hardwareInterface +++ /dev/null @@ -1,51 +0,0 @@ -#pragma once - -#include -#include -#include - - -// CTRE namespace -namespace ctre_can = ctre::phoenix::motorcontrol::can; - -// Brushless Motor -#define BRUSHLESS rev::CANSparkMax::MotorType::kBrushless - -// Coast -#define COAST rev::CANSparkMax::IdleMode::kCoast - -// CAN IDs -#define LEFT_MOTOR_1 1 -#define LEFT_MOTOR_2 2 -#define LEFT_MOTOR_3 3 -#define RIGHT_MOTOR_1 4 -#define RIGHT_MOTOR_2 5 -#define RIGHT_MOTOR_3 6 - -#define INDEXER_MOTOR 7 -#define INTAKE_POSITION_MOTOR 10 -#define INTAKE_MOTOR 11 - -#define SHOOTER_MOTOR 8 -#define TRIGGER_MOTOR 9 - -typedef struct actuator_interface_t { - // Left drivetrain motors - std::unique_ptr left_motor_1; - std::unique_ptr left_motor_2; - std::unique_ptr left_motor_3; - - // Right drivetrain motors - std::unique_ptr right_motor_1; - std::unique_ptr right_motor_2; - std::unique_ptr right_motor_3; - - // intake motors - std::unique_ptr intake_position_motor; - std::unique_ptr intake_motor; - std::unique_ptr indexer_motor; - - // Shooter motors - std::unique_ptr shooter_motor; - std::unique_ptr trigger_motor; -} ActuatorInterface; \ No newline at end of file diff --git a/src/main/include/hardware/hardwareInterface.cpp b/src/main/include/hardware/hardwareInterface.cpp deleted file mode 100644 index d1830dd..0000000 --- a/src/main/include/hardware/hardwareInterface.cpp +++ /dev/null @@ -1,117 +0,0 @@ - - - -#include "hardware/HardwareInterface.h" - -bool SetupDrivetrainInterface( - std::unique_ptr &hardware, - std::shared_ptr *interface) { - OKC_CHECK(interface != nullptr); - OKC_CHECK(hardware->actuators != nullptr); - OKC_CHECK(hardware->sensors != nullptr); - - // Get actuators interface for drivetrain. - std::unique_ptr &actuators = hardware->actuators; - std::unique_ptr &sensors = hardware->sensors; - - // Build motor control groups and differential drive. - frc::MotorControllerGroup left_motors{*actuators->left_motor_1, - *actuators->left_motor_2, - *actuators->left_motor_3}; - - frc::MotorControllerGroup right_motors{*actuators->right_motor_1, - *actuators->right_motor_2, - *actuators->right_motor_3}; - // motors face opposite directions so +1 for left side is opposite +1 for - // right side, this fixes that - right_motors.SetInverted(true); - - // Ensure the differential drivetrain is un-initialized. - OKC_CHECK(hardware->diff_drive == nullptr); - - // Create the differential drive. - hardware->diff_drive = - std::make_unique(left_motors, right_motors); - - // Protect against nullptr actuators/sensors - OKC_CHECK(actuators->left_motor_1 != nullptr); - OKC_CHECK(actuators->left_motor_2 != nullptr); - OKC_CHECK(actuators->left_motor_3 != nullptr); - OKC_CHECK(actuators->right_motor_1 != nullptr); - OKC_CHECK(actuators->right_motor_2 != nullptr); - OKC_CHECK(actuators->right_motor_3 != nullptr); - OKC_CHECK(hardware->diff_drive != nullptr); - OKC_CHECK(sensors->ahrs != nullptr); - - // Set up drivetrain interface. - DrivetrainHardwareInterface drivetrain_interface = { - actuators->left_motor_1.get(), actuators->left_motor_2.get(), - actuators->left_motor_3.get(), actuators->right_motor_1.get(), - actuators->right_motor_2.get(), actuators->right_motor_3.get(), - hardware->diff_drive.get(), hardware->sensors->ahrs.get()}; - - // Set the output interface - *interface = - std::make_shared(drivetrain_interface); - - return true; -} - -bool SetupIntakeInterface(std::unique_ptr &hardware, - std::shared_ptr *interface) { - OKC_CHECK(interface != nullptr); - OKC_CHECK(hardware->actuators != nullptr); - OKC_CHECK(hardware->sensors != nullptr); - - // Get actuators interface for intake. - std::unique_ptr &actuators = hardware->actuators; - std::unique_ptr &sensors = hardware->sensors; - - // Protect against nullptr actuators/sensors - OKC_CHECK(actuators->intake_position_motor != nullptr); - OKC_CHECK(actuators->intake_motor != nullptr); - OKC_CHECK(actuators->indexer_motor != nullptr); - OKC_CHECK(sensors->retracted_limit_switch != nullptr); - OKC_CHECK(sensors->deploy_limit_switch != nullptr); - - // Set up intake interface. - IntakeHardwareInterface intake_interface = { - actuators->intake_position_motor.get(), - actuators->intake_motor.get(), - actuators->indexer_motor.get(), - - sensors->retracted_limit_switch.get(), - sensors->deploy_limit_switch.get(), - }; - - // Set the output interface - *interface = std::make_shared(intake_interface); - - return true; -} - -bool SetupShooterInterface( - std::unique_ptr &hardware, - std::shared_ptr *interface) { - OKC_CHECK(interface != nullptr); - OKC_CHECK(hardware->actuators != nullptr); - OKC_CHECK(hardware->sensors != nullptr); - - // Get actuators and sensors interfaces for shooter. - std::unique_ptr &actuators = hardware->actuators; - std::unique_ptr &sensors = hardware->sensors; - - // Protect against nullptr actuators/sensors - OKC_CHECK(actuators->shooter_motor != nullptr); - OKC_CHECK(actuators->trigger_motor != nullptr); - OKC_CHECK(sensors->ball_detector != nullptr); - - ShooterHardwareInterface shooter_interface = { - actuators->shooter_motor.get(), actuators->trigger_motor.get(), - sensors->ball_detector.get()}; - - // Set the output interface - *interface = std::make_shared(shooter_interface); - - return true; -} diff --git a/src/main/include/hardware/hardwareInterface.h b/src/main/include/hardware/hardwareInterface.h new file mode 100644 index 0000000..5df20cf --- /dev/null +++ b/src/main/include/hardware/hardwareInterface.h @@ -0,0 +1,64 @@ +#pragma once + +#include +#include + +#include "hardware/ActuatorInterface.h" +#include "hardware/SensorInterface.h" + +// Subsystem I/O +#include "io/DrivetrainIO.h" +#include "io/IntakeIO.h" +#include "io/ShooterIO.h" + +typedef struct hardware_t { + // Actuators + std::unique_ptr actuators; + + // Drivetrain specific hardware abstractions. + std::unique_ptr diff_drive; + + // Sensors + std::unique_ptr sensors; + +} HardwareInterface; + +// Subsystem hardware setup functions + +/** + * @brief Link the Drivetrain to the hardware interfaces. + * + * @param interface + * @return true + * @return false + */ +bool SetupSwervedriveInterface( + std::unique_ptr &hardware, + std::shared_ptr *interface); + +/** + * @brief Link the Intake to the hardware interfaces. + * + * @param interface + * @return true + * @return false + */ +bool SetupArmInterface(std::unique_ptr &hardware, + std::shared_ptr *interface); + +/** + * @brief Link the Shooter to the hardware interfaces. + * + * @param interface + * @return true + * @return false + */ +bool SetupClawInterface( + std::unique_ptr &hardware, + std::shared_ptr *interface); + + bool SetupVisionTrackingInterface( + std::unique_ptr &hardware, + std::shared_ptr *interface); + + diff --git a/src/main/include/hardware/sensorInterface b/src/main/include/hardware/sensorInterface.h similarity index 100% rename from src/main/include/hardware/sensorInterface rename to src/main/include/hardware/sensorInterface.h From b64846a65afb158fd610683b4cba810bce1a0c86 Mon Sep 17 00:00:00 2001 From: okcroboticsteam Date: Thu, 12 Jan 2023 18:33:49 -0600 Subject: [PATCH 03/28] defined --- src/main/cpp/subsystems/arm.cpp | 15 +++++++++++++++ src/main/include/hardware/actuatorInterface.h | 5 ----- src/main/include/subsystems/arm.h | 15 +++++++++++++++ 3 files changed, 30 insertions(+), 5 deletions(-) create mode 100644 src/main/cpp/subsystems/arm.cpp create mode 100644 src/main/include/subsystems/arm.h diff --git a/src/main/cpp/subsystems/arm.cpp b/src/main/cpp/subsystems/arm.cpp new file mode 100644 index 0000000..7ff9bd8 --- /dev/null +++ b/src/main/cpp/subsystems/arm.cpp @@ -0,0 +1,15 @@ +bool Arm::init(){ + return true; +} + +bool Arm::SetDegrees(double degrees){ + return true; +} + +bool Arm::SetExtend(double inches){ + return true; +} + +bool Arm::Function(int number){ + return true; +} \ No newline at end of file diff --git a/src/main/include/hardware/actuatorInterface.h b/src/main/include/hardware/actuatorInterface.h index d7c0524..b20b793 100644 --- a/src/main/include/hardware/actuatorInterface.h +++ b/src/main/include/hardware/actuatorInterface.h @@ -1,6 +1,5 @@ #pragma once -#include #include #include @@ -46,8 +45,4 @@ typedef struct actuator_interface_t { std::unique_ptr arm_lift_motor; std::unique_ptr arm_up_motor; std::unique_ptr arm_extend_motor; - - // Shooter motors - std::unique_ptr shooter_motor; - std::unique_ptr trigger_motor; } ActuatorInterface; \ No newline at end of file diff --git a/src/main/include/subsystems/arm.h b/src/main/include/subsystems/arm.h new file mode 100644 index 0000000..be60029 --- /dev/null +++ b/src/main/include/subsystems/arm.h @@ -0,0 +1,15 @@ + + +class Arm : public frc2::SubsystemBase { +public: +Arm(ArmSoftwareInterface *interface) + : interface_(interface), Arm_pid(1.0, 0.0, 0.0) {} + ~Arm() {} + + bool Function(int number); + bool SetDegrees(double degrees); + bool SetExtend(double inches); + bool init(); +private: + ArmSoftwareInterface *const interface; +}; \ No newline at end of file From d0d54e7d1caaa12078d51576180cb4a160fac5a0 Mon Sep 17 00:00:00 2001 From: okcroboticsteam Date: Thu, 12 Jan 2023 19:48:49 -0600 Subject: [PATCH 04/28] labeled buttons --- src/main/include/RobotContainer.h | 46 +++++++++++++++++++++++++++++++ 1 file changed, 46 insertions(+) diff --git a/src/main/include/RobotContainer.h b/src/main/include/RobotContainer.h index 2988968..11ea9e7 100644 --- a/src/main/include/RobotContainer.h +++ b/src/main/include/RobotContainer.h @@ -28,4 +28,50 @@ class RobotContainer { ExampleCommand m_autonomousCommand; void ConfigureButtonBindings(); + + std::shared_ptr gamepad1_; + std::shared_ptr gamepad2_; + + std::shared_ptr driver_a_button_; + std::shared_ptr driver_b_button_; + std::shared_ptr driver_back_button_; + std::shared_ptr driver_left_bumper_; + std::shared_ptr driver_right_bumper_; + + std::shared_ptr manip_a_button_; + std::shared_ptr manip_b_button_; + std::shared_ptr manip_back_button_; + std::shared_ptr manip_start_button_; + std::shared_ptr manip_left_stick_button_; + std::shared_ptr manip_right_stick_button; + + std::shared_ptr manip_trigger_button_; + std::shared_ptr manip_left_button_; + std::shared_ptr manip_bottom_right_button_; + std::shared_ptr manip_top_right_button_; + std::shared_ptr manip_botton_left_button_; + std::shared_ptr manip_top_left_button_; + + std::shared_ptr manip_seven_button_; + std::shared_ptr manip_eight_button_; + std::shared_ptr manip_nine_button_; + std::shared_ptr manip_ten_button_; + std::shared_ptr manip_eleven_button_; + std::shared_ptr manip_twelve_button_; + + std::shared_ptr manip_A_button_; + std::shared_ptr manip_B_button_; + std::shared_ptr manip_X_button_; + std::shared_ptr manip_Y_button_; + std::shared_ptr manip_RB_button_; + std::shared_ptr manip_LB_button_; + std::shared_ptr manip_RT_button_; + std::shared_ptr manip_LT_button_; + std::shared_ptr manip_back_button_; + std::shared_ptr manip_start_button_; + std::shared_ptr manip_mode_button_; + +}; }; + + From 2a914ec4b45c085026ed58bed1190f79f2065042 Mon Sep 17 00:00:00 2001 From: okcroboticsteam Date: Sat, 14 Jan 2023 11:24:48 -0600 Subject: [PATCH 05/28] arm sw, hw, cpp, and IO --- src/main/cpp/IO/armIO.cpp | 98 ++++++++++++++++ src/main/include/hardware/hardwareInterface.h | 2 +- src/main/include/io/DriveTrain.io.h | 109 ++++++++++++++++++ src/main/include/io/armIO.h | 57 +++++++++ 4 files changed, 265 insertions(+), 1 deletion(-) create mode 100644 src/main/cpp/IO/armIO.cpp create mode 100644 src/main/include/io/DriveTrain.io.h create mode 100644 src/main/include/io/armIO.h diff --git a/src/main/cpp/IO/armIO.cpp b/src/main/cpp/IO/armIO.cpp new file mode 100644 index 0000000..e01cec1 --- /dev/null +++ b/src/main/cpp/IO/armIO.cpp @@ -0,0 +1,98 @@ + +#include "io/ArmIO.h" + +void ArmIO::Periodic() { + // Process all the inputs and outputs to/from high level software. + VOKC_CALL(ProcessIO()); +} + +void ArmIO::SimulationPeriodic() { + // SimulationPeriodic +} + +bool ArmIO::ProcessIO() { + OKC_CHECK(sw_interface_ != nullptr); + OKC_CHECK(hw_interface_ != nullptr); + + // Set the software outputs + // If the intake configuration needs to be updated, update it. + if (sw_interface_->update_config) { + OKC_CALL(UpdateArmConfig(sw_interface_->arm_config)); + + // Lower the update flag + sw_interface_->update_config = false; + } + + // If the encoder should be reset, reset it + if (sw_interface_->reset_encoders) { + OKC_CALL(ResetEncoders()); + + // Lower the encoder reset flag + sw_interface_->reset_encoders = false; + } + + // if the encoder should be set to a specific value + if (sw_interface_->set_encoder_to_val) { + OKC_CALL(SetEncoder(sw_interface_->encoder_val_to_set)) + + sw_interface_->set_encoder_to_val = false; + } + + + // Get the hardware sensor values. + // limit switches + sw_interface_->deployed_limit_switch_val = hw_interface_->deploy_limit_switch->Get(); //??? + sw_interface_->retracted_limit_switch_val = hw_interface_->retracted_limit_switch->Get(); //??? + + // intake position encoder + sw_interface_->arm_position_encoder_val = + hw_interface_->arm_position_motor->GetEncoder().GetPosition(); + + return true; +} + +bool ArmIO::UpdateArmConfig(ArmConfig &config) { + OKC_CHECK(hw_interface_ != nullptr); + + // Get the configuration + double open_loop_ramp = config.open_loop_ramp_rate; + //double max_output_deploy = config.max_output_deploy; + //double max_output_retract = config.max_output_retract; + double max_indexer_current = config.max_indexer_current; + + // Apply the configuration + // Open Loop Ramp Rate + hw_interface_->arm_motor->SetOpenLoopRampRate(open_loop_ramp); + hw_interface_->indexer_motor->SetOpenLoopRampRate(open_loop_ramp); + + // Java code has this commented out as well, I'm assuming because it was meesing something up. + // well, the intake works (probably, been a while since it's been actually plugged in) without this, + // so leaving commented out for now + // hw_interface_->intake_position_motor->SetOpenLoopRampRate(open_loop_ramp); + + // current limiting, so the neo 550 on the indexer doesn't stall and smoke + hw_interface_->indexer_motor->SetSmartCurrentLimit(max_indexer_current); + + return true; +} + +bool ArmIO::ResetEncoders() { + OKC_CHECK(hw_interface_ != nullptr); + + hw_interface_->arm_position_motor->GetEncoder().SetPosition(0.0); + + // we currently don't use the encoder for these other two motors, so we don't need to reset them + // yet. yet. + // hw_interface_->intake_motor->GetEncoder().SetPosition(0.0); + // hw_interface_->indexer_motor->GetEncoder().SetPosition(0.0); + + return true; +} + +bool ArmIO::SetEncoder(double &val) { + OKC_CHECK(hw_interface_ != nullptr); + + hw_interface_->arm_position_motor->GetEncoder().SetPosition(val); + + return true; +} \ No newline at end of file diff --git a/src/main/include/hardware/hardwareInterface.h b/src/main/include/hardware/hardwareInterface.h index 5df20cf..e990a22 100644 --- a/src/main/include/hardware/hardwareInterface.h +++ b/src/main/include/hardware/hardwareInterface.h @@ -44,7 +44,7 @@ bool SetupSwervedriveInterface( * @return false */ bool SetupArmInterface(std::unique_ptr &hardware, - std::shared_ptr *interface); + std::shared_ptr *interface); /** * @brief Link the Shooter to the hardware interfaces. diff --git a/src/main/include/io/DriveTrain.io.h b/src/main/include/io/DriveTrain.io.h new file mode 100644 index 0000000..519599e --- /dev/null +++ b/src/main/include/io/DriveTrain.io.h @@ -0,0 +1,109 @@ +#pragma once + +#include + +#include +#include +#include +#include + +#include "AHRS.h" +#include "Utils.h" + +enum DriveMode { + ARCADE = 0, + TANK = 1, + CURVATURE = 2 +}; + +typedef struct drivetrain_config_t { + double max_output; + double open_loop_ramp_rate; +} DrivetrainConfig; + +typedef struct drivetrain_hardware_interface_t { + // Left motors + rev::CANSparkMax *const left_motor_1; + rev::CANSparkMax *const left_motor_2; + rev::CANSparkMax *const left_motor_3; + + // Right motors + rev::CANSparkMax *const right_motor_1; + rev::CANSparkMax *const right_motor_2; + rev::CANSparkMax *const right_motor_3; + + // Drivetrain + frc::DifferentialDrive *const diff_drive; + + // AHRS + AHRS *const ahrs; + +} DrivetrainHardwareInterface; + +typedef struct drivetrain_software_interface_t { + // SW INPUTS + + // IMU yaw angle + double imu_yaw; + + // Encoders + double left_encoder_avg; + double right_encoder_avg; + + // SW OUTPUTS + + // Configure drivetrain variables + DrivetrainConfig drive_config; + bool update_config; + + // Tank or arcade drive selector. + DriveMode drive_mode; + + // Input squaring + bool square_inputs; + + // Arcade drive inputs + double arcade_power; + double arcade_turn; + + // Tank drive inputs + double tank_left; + double tank_right; + + // Curvature drive inputs + // Note: use arcade drive inputs except for turn_in_place flag. + bool turn_in_place; + + // Reset flags + bool reset_encoders; + bool reset_gyro; + +} DrivetrainSoftwareInterface; + +class DrivetrainIO : public frc2::SubsystemBase { +public: + DrivetrainIO(DrivetrainHardwareInterface *hw_interface, + DrivetrainSoftwareInterface *sw_interface) + : hw_interface_(hw_interface), sw_interface_(sw_interface) {} + + /** + * Will be called periodically whenever the CommandScheduler runs. + */ + void Periodic() override; + + /** + * Will be called periodically whenever the CommandScheduler runs during + * simulation. + */ + void SimulationPeriodic() override; + + bool ProcessIO(); + +private: + bool UpdateDriveConfig(DrivetrainConfig &config); + bool ResetEncoders(); + + DrivetrainHardwareInterface *const hw_interface_; + DrivetrainSoftwareInterface *const sw_interface_; +}; +Footer diff --git a/src/main/include/io/armIO.h b/src/main/include/io/armIO.h new file mode 100644 index 0000000..0ddfad8 --- /dev/null +++ b/src/main/include/io/armIO.h @@ -0,0 +1,57 @@ +#pragma once + +#include + +#include +#include +#include +#include + +#include "Utils.h" + + +typedef struct Arm_config_t { + +} ArmConfig; + +typedef struct arm_hardware_interface_t { + std::unique_ptr arm_lift_motor; + std::unique_ptr arm_up_motor; + std::unique_ptr arm_extend_motor; +} ArmHardwareInterface; + +typedef struct arm_software_interface_t { + + // actuator outputs + double arm_lift_power; + double arm_up_power; + double arm_extend_power; +} ArmSoftwareInterface; + +class ArmIO : public frc2::SubsystemBase { +public: + ArmIO(ArmHardwareInterface *hw_interface, + ArmSoftwareInterface *sw_interface) + : hw_interface_(hw_interface), sw_interface_(sw_interface) {} + + /** + * Will be called periodically whenever the CommandScheduler runs. + */ + void Periodic() override; + + /** + * Will be called periodically whenever the CommandScheduler runs during + * simulation. + */ + void SimulationPeriodic() override; + + bool ProcessIO(); + +private: + bool UpdateArmConfig(ArmConfig &config); + bool ResetEncoders(); + bool SetEncoder(double &val); + + ArmHardwareInterface *const hw_interface_; + ArmSoftwareInterface *const sw_interface_; +}; \ No newline at end of file From ce32b482b6acd4bc5b41c03f70bdbff0e6fbe237 Mon Sep 17 00:00:00 2001 From: AbbeySieg Date: Sat, 14 Jan 2023 14:20:31 -0600 Subject: [PATCH 06/28] changed file names --- gradlew | 0 src/main/cpp/IO/{armIO.cpp => ArmIO.cpp} | 0 src/main/cpp/subsystems/{arm.cpp => Arm.cpp} | 0 src/main/include/io/{armIO.h => ArmIO.h} | 0 src/main/include/io/DriveTrain.io.h | 109 ------------------- src/main/include/subsystems/{arm.h => Arm.h} | 0 6 files changed, 109 deletions(-) mode change 100644 => 100755 gradlew rename src/main/cpp/IO/{armIO.cpp => ArmIO.cpp} (100%) rename src/main/cpp/subsystems/{arm.cpp => Arm.cpp} (100%) rename src/main/include/io/{armIO.h => ArmIO.h} (100%) delete mode 100644 src/main/include/io/DriveTrain.io.h rename src/main/include/subsystems/{arm.h => Arm.h} (100%) diff --git a/gradlew b/gradlew old mode 100644 new mode 100755 diff --git a/src/main/cpp/IO/armIO.cpp b/src/main/cpp/IO/ArmIO.cpp similarity index 100% rename from src/main/cpp/IO/armIO.cpp rename to src/main/cpp/IO/ArmIO.cpp diff --git a/src/main/cpp/subsystems/arm.cpp b/src/main/cpp/subsystems/Arm.cpp similarity index 100% rename from src/main/cpp/subsystems/arm.cpp rename to src/main/cpp/subsystems/Arm.cpp diff --git a/src/main/include/io/armIO.h b/src/main/include/io/ArmIO.h similarity index 100% rename from src/main/include/io/armIO.h rename to src/main/include/io/ArmIO.h diff --git a/src/main/include/io/DriveTrain.io.h b/src/main/include/io/DriveTrain.io.h deleted file mode 100644 index 519599e..0000000 --- a/src/main/include/io/DriveTrain.io.h +++ /dev/null @@ -1,109 +0,0 @@ -#pragma once - -#include - -#include -#include -#include -#include - -#include "AHRS.h" -#include "Utils.h" - -enum DriveMode { - ARCADE = 0, - TANK = 1, - CURVATURE = 2 -}; - -typedef struct drivetrain_config_t { - double max_output; - double open_loop_ramp_rate; -} DrivetrainConfig; - -typedef struct drivetrain_hardware_interface_t { - // Left motors - rev::CANSparkMax *const left_motor_1; - rev::CANSparkMax *const left_motor_2; - rev::CANSparkMax *const left_motor_3; - - // Right motors - rev::CANSparkMax *const right_motor_1; - rev::CANSparkMax *const right_motor_2; - rev::CANSparkMax *const right_motor_3; - - // Drivetrain - frc::DifferentialDrive *const diff_drive; - - // AHRS - AHRS *const ahrs; - -} DrivetrainHardwareInterface; - -typedef struct drivetrain_software_interface_t { - // SW INPUTS - - // IMU yaw angle - double imu_yaw; - - // Encoders - double left_encoder_avg; - double right_encoder_avg; - - // SW OUTPUTS - - // Configure drivetrain variables - DrivetrainConfig drive_config; - bool update_config; - - // Tank or arcade drive selector. - DriveMode drive_mode; - - // Input squaring - bool square_inputs; - - // Arcade drive inputs - double arcade_power; - double arcade_turn; - - // Tank drive inputs - double tank_left; - double tank_right; - - // Curvature drive inputs - // Note: use arcade drive inputs except for turn_in_place flag. - bool turn_in_place; - - // Reset flags - bool reset_encoders; - bool reset_gyro; - -} DrivetrainSoftwareInterface; - -class DrivetrainIO : public frc2::SubsystemBase { -public: - DrivetrainIO(DrivetrainHardwareInterface *hw_interface, - DrivetrainSoftwareInterface *sw_interface) - : hw_interface_(hw_interface), sw_interface_(sw_interface) {} - - /** - * Will be called periodically whenever the CommandScheduler runs. - */ - void Periodic() override; - - /** - * Will be called periodically whenever the CommandScheduler runs during - * simulation. - */ - void SimulationPeriodic() override; - - bool ProcessIO(); - -private: - bool UpdateDriveConfig(DrivetrainConfig &config); - bool ResetEncoders(); - - DrivetrainHardwareInterface *const hw_interface_; - DrivetrainSoftwareInterface *const sw_interface_; -}; -Footer diff --git a/src/main/include/subsystems/arm.h b/src/main/include/subsystems/Arm.h similarity index 100% rename from src/main/include/subsystems/arm.h rename to src/main/include/subsystems/Arm.h From dcc6c2d7c107a54845f913d29415c18c93e5f53c Mon Sep 17 00:00:00 2001 From: AbbeySieg Date: Sat, 14 Jan 2023 14:42:29 -0600 Subject: [PATCH 07/28] renamed more files --- .../cpp/hardware/{hardwareInterface.cpp => HardwareInterface.cpp} | 0 src/main/include/{io => IO}/ArmIO.h | 0 .../include/hardware/{actuatorInterface.h => ActuatorInterface.h} | 0 .../include/hardware/{hardwareInterface.h => HardwareInterface.h} | 0 .../include/hardware/{sensorInterface.h => SensorInterface.h} | 0 5 files changed, 0 insertions(+), 0 deletions(-) rename src/main/cpp/hardware/{hardwareInterface.cpp => HardwareInterface.cpp} (100%) rename src/main/include/{io => IO}/ArmIO.h (100%) rename src/main/include/hardware/{actuatorInterface.h => ActuatorInterface.h} (100%) rename src/main/include/hardware/{hardwareInterface.h => HardwareInterface.h} (100%) rename src/main/include/hardware/{sensorInterface.h => SensorInterface.h} (100%) diff --git a/src/main/cpp/hardware/hardwareInterface.cpp b/src/main/cpp/hardware/HardwareInterface.cpp similarity index 100% rename from src/main/cpp/hardware/hardwareInterface.cpp rename to src/main/cpp/hardware/HardwareInterface.cpp diff --git a/src/main/include/io/ArmIO.h b/src/main/include/IO/ArmIO.h similarity index 100% rename from src/main/include/io/ArmIO.h rename to src/main/include/IO/ArmIO.h diff --git a/src/main/include/hardware/actuatorInterface.h b/src/main/include/hardware/ActuatorInterface.h similarity index 100% rename from src/main/include/hardware/actuatorInterface.h rename to src/main/include/hardware/ActuatorInterface.h diff --git a/src/main/include/hardware/hardwareInterface.h b/src/main/include/hardware/HardwareInterface.h similarity index 100% rename from src/main/include/hardware/hardwareInterface.h rename to src/main/include/hardware/HardwareInterface.h diff --git a/src/main/include/hardware/sensorInterface.h b/src/main/include/hardware/SensorInterface.h similarity index 100% rename from src/main/include/hardware/sensorInterface.h rename to src/main/include/hardware/SensorInterface.h From e2777664c3fe5589a898246b6a8c39b51f7579bc Mon Sep 17 00:00:00 2001 From: AbbeySieg Date: Sat, 14 Jan 2023 14:53:00 -0600 Subject: [PATCH 08/28] added swerve drive to branch --- src/main/cpp/IO/SwerveDriveIO.cpp | 167 ++++++++++++++++++++++++++++++ src/main/cpp/IO/SwerveDriveIO.h | 137 ++++++++++++++++++++++++ 2 files changed, 304 insertions(+) create mode 100644 src/main/cpp/IO/SwerveDriveIO.cpp create mode 100644 src/main/cpp/IO/SwerveDriveIO.h diff --git a/src/main/cpp/IO/SwerveDriveIO.cpp b/src/main/cpp/IO/SwerveDriveIO.cpp new file mode 100644 index 0000000..231d41c --- /dev/null +++ b/src/main/cpp/IO/SwerveDriveIO.cpp @@ -0,0 +1,167 @@ +#include "io/SwerveDriveIO.h" +#include "Utils.h" + +void SwerveDriveIO::Periodic() { + // Process all the inputs and outputs to/from high level software. + VOKC_CALL(ProcessIO()); +} + +void SwerveDriveIO::SimulationPeriodic() { + // SimulationPeriodic +} + +bool SwerveDriveIO::ProcessIO() { + OKC_CHECK(sw_interface_ != nullptr); + OKC_CHECK(hw_interface_ != nullptr); + + // Set the software outputs + // If the swerve drive configuration needs to be updated, update it. + if (sw_interface_->update_config) { + OKC_CALL(UpdateDriveConfig(sw_interface_->drive_config)); + + // Lower the update flag + sw_interface_->update_config = false; + } + + // If the encoders should be reset, reset them + if (sw_interface_->reset_drive_encoders) { + OKC_CALL(ResetDriveEncoders()); + + // Lower the encoder reset flag + sw_interface_->reset_drive_encoders = false; + } + + if (sw_interface_->reset_steer_encoders) { + OKC_CALL(ResetSteerEncoders()); + + // Lower the encoder reset flag + sw_interface_->reset_steer_encoders = false; + } + + // If the navX should be reset, reset it. + if (sw_interface_->reset_gyro) { + hw_interface_->ahrs->Reset(); + + // Lower the navX reset flag + sw_interface_->reset_gyro = false; + } + + OKC_CHECK(hw_interface_->left_front_drive_motor != nullptr); + OKC_CHECK(hw_interface_->left_back_drive_motor != nullptr); + OKC_CHECK(hw_interface_->right_front_drive_motor != nullptr); + OKC_CHECK(hw_interface_->right_back_drive_motor != nullptr); + + // Set the drive outputs. + // hw_interface_->left_front_drive_motor->Set(TeamOKC::Clamp(-this->sw_interface_->drive_config.max_output_drive, this->sw_interface_->drive_config.max_output_drive, &this->sw_interface_->left_front_drive_motor_output)); + // hw_interface_->left_back_drive_motor->Set(TeamOKC::Clamp(-this->sw_interface_->drive_config.max_output_drive, this->sw_interface_->drive_config.max_output_drive, &this->sw_interface_->left_back_drive_motor_output)); + // hw_interface_->right_front_drive_motor->Set(TeamOKC::Clamp(-this->sw_interface_->drive_config.max_output_drive, this->sw_interface_->drive_config.max_output_drive, &this->sw_interface_->right_front_drive_motor_output)); + // hw_interface_->right_back_drive_motor->Set(TeamOKC::Clamp(-this->sw_interface_->drive_config.max_output_drive, this->sw_interface_->drive_config.max_output_drive, &this->sw_interface_->right_back_drive_motor_output)); + hw_interface_->left_front_drive_motor->Set(this->sw_interface_->left_front_drive_motor_output); + hw_interface_->left_back_drive_motor->Set(this->sw_interface_->left_back_drive_motor_output); + hw_interface_->right_front_drive_motor->Set(this->sw_interface_->right_front_drive_motor_output); + hw_interface_->right_back_drive_motor->Set(this->sw_interface_->right_back_drive_motor_output); + + // set the steer outputs. + // hw_interface_->left_front_steer_motor->Set(TeamOKC::Clamp(-this->sw_interface_->drive_config.max_output_steer, this->sw_interface_->drive_config.max_output_steer, &this->sw_interface_->left_front_steer_motor_output)); + // hw_interface_->left_back_steer_motor->Set(TeamOKC::Clamp(-this->sw_interface_->drive_config.max_output_steer, this->sw_interface_->drive_config.max_output_steer, &this->sw_interface_->left_back_steer_motor_output)); + // hw_interface_->right_front_steer_motor->Set(TeamOKC::Clamp(-this->sw_interface_->drive_config.max_output_steer, this->sw_interface_->drive_config.max_output_steer, &this->sw_interface_->right_front_steer_motor_output)); + // hw_interface_->right_back_steer_motor->Set(TeamOKC::Clamp(-this->sw_interface_->drive_config.max_output_steer, this->sw_interface_->drive_config.max_output_steer, &this->sw_interface_->right_back_steer_motor_output)); + hw_interface_->left_front_steer_motor->Set(this->sw_interface_->left_front_steer_motor_output); + hw_interface_->left_back_steer_motor->Set(this->sw_interface_->left_back_steer_motor_output); + hw_interface_->right_front_steer_motor->Set(this->sw_interface_->right_front_steer_motor_output); + hw_interface_->right_back_steer_motor->Set(this->sw_interface_->right_back_steer_motor_output); + + // Get the hardware sensor values. + // navX IMU: + sw_interface_->imu_yaw = hw_interface_->ahrs->GetAngle(); + + // Encoders + // position + // drive + sw_interface_->left_front_drive_motor_enc = hw_interface_->left_front_drive_encoder->GetPosition(); + sw_interface_->left_back_drive_motor_enc = hw_interface_->left_back_drive_encoder->GetPosition(); + sw_interface_->right_front_drive_motor_enc = hw_interface_->right_front_drive_encoder->GetPosition(); + sw_interface_->right_back_drive_motor_enc = hw_interface_->right_back_drive_encoder->GetPosition(); + + // steer + sw_interface_->left_front_steer_motor_enc = hw_interface_->left_front_steer_encoder->GetAbsolutePosition(); + sw_interface_->left_back_steer_motor_enc = hw_interface_->left_back_steer_encoder->GetAbsolutePosition(); + sw_interface_->right_front_steer_motor_enc = hw_interface_->right_front_steer_encoder->GetAbsolutePosition(); + sw_interface_->right_back_steer_motor_enc = hw_interface_->right_back_steer_encoder->GetAbsolutePosition(); + + // velocity + // drive + sw_interface_->left_front_drive_enc_vel = hw_interface_->left_front_drive_encoder->GetVelocity(); + sw_interface_->left_back_drive_enc_vel = hw_interface_->left_back_drive_encoder->GetVelocity(); + sw_interface_->right_front_drive_enc_vel = hw_interface_->right_front_drive_encoder->GetVelocity(); + sw_interface_->right_back_drive_enc_vel = hw_interface_->right_back_drive_encoder->GetVelocity(); + + // steer + sw_interface_->left_front_steer_enc_vel = hw_interface_->left_front_steer_vel_encoder->GetVelocity(); + sw_interface_->left_back_steer_enc_vel = hw_interface_->left_back_steer_vel_encoder->GetVelocity(); + sw_interface_->right_front_steer_enc_vel = hw_interface_->right_front_steer_vel_encoder->GetVelocity(); + sw_interface_->right_back_steer_enc_vel = hw_interface_->right_back_steer_vel_encoder->GetVelocity(); + + return true; +} + +bool SwerveDriveIO::UpdateDriveConfig(SwerveDriveConfig &config) { + OKC_CHECK(hw_interface_ != nullptr); + + OKC_CHECK(hw_interface_->left_front_drive_motor != nullptr); + OKC_CHECK(hw_interface_->left_back_drive_motor != nullptr); + OKC_CHECK(hw_interface_->right_front_drive_motor != nullptr); + OKC_CHECK(hw_interface_->right_back_drive_motor != nullptr); + + // Get the configuration + double open_loop_ramp_drive = config.open_loop_ramp_rate_drive; + double open_loop_ramp_steer = config.open_loop_ramp_rate_steer; + double max_output_drive = config.max_output_drive; + double max_output_steer = config.max_output_steer; + + // Apply the configuration + // Open Loop Ramp Rate + hw_interface_->left_front_drive_motor->SetOpenLoopRampRate(open_loop_ramp_drive); + hw_interface_->left_back_drive_motor->SetOpenLoopRampRate(open_loop_ramp_drive); + hw_interface_->right_front_drive_motor->SetOpenLoopRampRate(open_loop_ramp_drive); + hw_interface_->right_back_drive_motor->SetOpenLoopRampRate(open_loop_ramp_drive); + + hw_interface_->left_front_steer_motor->SetOpenLoopRampRate(open_loop_ramp_steer); + hw_interface_->left_back_steer_motor->SetOpenLoopRampRate(open_loop_ramp_steer); + hw_interface_->right_front_steer_motor->SetOpenLoopRampRate(open_loop_ramp_steer); + hw_interface_->right_back_steer_motor->SetOpenLoopRampRate(open_loop_ramp_steer); + + return true; +} + +bool SwerveDriveIO::ResetDriveEncoders() { + OKC_CHECK(hw_interface_ != nullptr); + + OKC_CHECK(hw_interface_->left_front_drive_encoder != nullptr); + OKC_CHECK(hw_interface_->left_back_drive_encoder != nullptr); + OKC_CHECK(hw_interface_->right_front_drive_encoder != nullptr); + OKC_CHECK(hw_interface_->right_back_drive_encoder != nullptr); + + OKC_CHECK(hw_interface_->left_front_drive_motor != nullptr); + OKC_CHECK(hw_interface_->left_back_drive_motor != nullptr); + OKC_CHECK(hw_interface_->right_front_drive_motor != nullptr); + OKC_CHECK(hw_interface_->right_back_drive_motor != nullptr); + + // internal encoders + hw_interface_->left_front_drive_encoder->SetPosition(0); + hw_interface_->left_back_drive_encoder->SetPosition(0); + hw_interface_->right_front_drive_encoder->SetPosition(0); + hw_interface_->right_back_drive_encoder->SetPosition(0); + + return true; +} + +bool SwerveDriveIO::ResetSteerEncoders() { + OKC_CHECK(hw_interface_ != nullptr); + + //TODO + + return true; +} + + diff --git a/src/main/cpp/IO/SwerveDriveIO.h b/src/main/cpp/IO/SwerveDriveIO.h new file mode 100644 index 0000000..14eb055 --- /dev/null +++ b/src/main/cpp/IO/SwerveDriveIO.h @@ -0,0 +1,137 @@ +#pragma once + +#include + +#include +#include + +#include "AHRS.h" +#include "Utils.h" +#include "frc/AnalogEncoder.h" + +typedef struct swerve_drive_config_t { + double max_output_drive; + double open_loop_ramp_rate_drive; + + double max_output_steer; + double open_loop_ramp_rate_steer; +} SwerveDriveConfig; + +typedef struct swerve_drive_hardware_interface_t { + // motors + rev::CANSparkMax *const left_front_drive_motor; + rev::CANSparkMax *const left_back_drive_motor; + + rev::CANSparkMax *const right_front_drive_motor; + rev::CANSparkMax *const right_back_drive_motor; + + rev::CANSparkMax *const left_front_steer_motor; + rev::CANSparkMax *const left_back_steer_motor; + + rev::CANSparkMax *const right_front_steer_motor; + rev::CANSparkMax *const right_back_steer_motor; + + // AHRS + AHRS *const ahrs; + + // drive encoders + rev::SparkMaxRelativeEncoder *const left_front_drive_encoder; + rev::SparkMaxRelativeEncoder *const left_back_drive_encoder; + rev::SparkMaxRelativeEncoder *const right_front_drive_encoder; + rev::SparkMaxRelativeEncoder *const right_back_drive_encoder; + + // Steer encoders + frc::AnalogEncoder *const left_front_steer_encoder; + frc::AnalogEncoder *const left_back_steer_encoder; + frc::AnalogEncoder *const right_front_steer_encoder; + frc::AnalogEncoder *const right_back_steer_encoder; + + // other steer encoders + rev::SparkMaxRelativeEncoder *const left_front_steer_vel_encoder; + rev::SparkMaxRelativeEncoder *const left_back_steer_vel_encoder; + rev::SparkMaxRelativeEncoder *const right_front_steer_vel_encoder; + rev::SparkMaxRelativeEncoder *const right_back_steer_vel_encoder; +} SwerveDriveHardwareInterface; + +typedef struct swerve_drive_software_interface_t { + // SW INPUTS + // IMU yaw angle + double imu_yaw; + + // Encoders + double left_front_drive_motor_enc; + double left_back_drive_motor_enc; + double right_front_drive_motor_enc; + double right_back_drive_motor_enc; + + double left_front_steer_motor_enc; + double left_back_steer_motor_enc; + double right_front_steer_motor_enc; + double right_back_steer_motor_enc; + + // encoder velocities + double left_front_drive_enc_vel; + double left_back_drive_enc_vel; + double right_front_drive_enc_vel; + double right_back_drive_enc_vel; + + double left_front_steer_enc_vel; + double left_back_steer_enc_vel; + double right_front_steer_enc_vel; + double right_back_steer_enc_vel; + + // SW OUTPUTS + // Configure swerve drive variables + SwerveDriveConfig drive_config; + bool update_config; + + // Input squaring + bool square_inputs; + + // motor outputs + double left_front_drive_motor_output; + double left_back_drive_motor_output; + + double right_front_drive_motor_output; + double right_back_drive_motor_output; + + double left_front_steer_motor_output; + double left_back_steer_motor_output; + + double right_front_steer_motor_output; + double right_back_steer_motor_output; + + // Reset flags + bool reset_drive_encoders; + bool reset_steer_encoders; + bool reset_gyro; + +} SwerveDriveSoftwareInterface; + +class SwerveDriveIO : public frc2::SubsystemBase { +public: + SwerveDriveIO(SwerveDriveHardwareInterface *hw_interface, + SwerveDriveSoftwareInterface *sw_interface) + : hw_interface_(hw_interface), sw_interface_(sw_interface) {} + + /** + * Will be called periodically whenever the CommandScheduler runs. + */ + void Periodic() override; + + /** + * Will be called periodically whenever the CommandScheduler runs during + * simulation. + */ + void SimulationPeriodic() override; + + bool ProcessIO(); + +private: + bool UpdateDriveConfig(SwerveDriveConfig &config); + bool ResetDriveEncoders(); + bool ResetSteerEncoders(); + + SwerveDriveHardwareInterface *const hw_interface_; + SwerveDriveSoftwareInterface *const sw_interface_; +}; From 72adfe6d5698618ffd46dbf239f527241a0b7b8c Mon Sep 17 00:00:00 2001 From: okcroboticsteam Date: Mon, 16 Jan 2023 16:13:33 -0600 Subject: [PATCH 09/28] changed hw, actua, and sen names --- .../{actuatorInterface.h => Actuators.h} | 0 .../{hardwareInterface.h => Hardware.h} | 0 .../hardware/{sensorInterface.h => Sensors.h} | 0 src/main/include/io/DriveTrain.io.h | 109 ------------------ 4 files changed, 109 deletions(-) rename src/main/include/hardware/{actuatorInterface.h => Actuators.h} (100%) rename src/main/include/hardware/{hardwareInterface.h => Hardware.h} (100%) rename src/main/include/hardware/{sensorInterface.h => Sensors.h} (100%) delete mode 100644 src/main/include/io/DriveTrain.io.h diff --git a/src/main/include/hardware/actuatorInterface.h b/src/main/include/hardware/Actuators.h similarity index 100% rename from src/main/include/hardware/actuatorInterface.h rename to src/main/include/hardware/Actuators.h diff --git a/src/main/include/hardware/hardwareInterface.h b/src/main/include/hardware/Hardware.h similarity index 100% rename from src/main/include/hardware/hardwareInterface.h rename to src/main/include/hardware/Hardware.h diff --git a/src/main/include/hardware/sensorInterface.h b/src/main/include/hardware/Sensors.h similarity index 100% rename from src/main/include/hardware/sensorInterface.h rename to src/main/include/hardware/Sensors.h diff --git a/src/main/include/io/DriveTrain.io.h b/src/main/include/io/DriveTrain.io.h deleted file mode 100644 index 519599e..0000000 --- a/src/main/include/io/DriveTrain.io.h +++ /dev/null @@ -1,109 +0,0 @@ -#pragma once - -#include - -#include -#include -#include -#include - -#include "AHRS.h" -#include "Utils.h" - -enum DriveMode { - ARCADE = 0, - TANK = 1, - CURVATURE = 2 -}; - -typedef struct drivetrain_config_t { - double max_output; - double open_loop_ramp_rate; -} DrivetrainConfig; - -typedef struct drivetrain_hardware_interface_t { - // Left motors - rev::CANSparkMax *const left_motor_1; - rev::CANSparkMax *const left_motor_2; - rev::CANSparkMax *const left_motor_3; - - // Right motors - rev::CANSparkMax *const right_motor_1; - rev::CANSparkMax *const right_motor_2; - rev::CANSparkMax *const right_motor_3; - - // Drivetrain - frc::DifferentialDrive *const diff_drive; - - // AHRS - AHRS *const ahrs; - -} DrivetrainHardwareInterface; - -typedef struct drivetrain_software_interface_t { - // SW INPUTS - - // IMU yaw angle - double imu_yaw; - - // Encoders - double left_encoder_avg; - double right_encoder_avg; - - // SW OUTPUTS - - // Configure drivetrain variables - DrivetrainConfig drive_config; - bool update_config; - - // Tank or arcade drive selector. - DriveMode drive_mode; - - // Input squaring - bool square_inputs; - - // Arcade drive inputs - double arcade_power; - double arcade_turn; - - // Tank drive inputs - double tank_left; - double tank_right; - - // Curvature drive inputs - // Note: use arcade drive inputs except for turn_in_place flag. - bool turn_in_place; - - // Reset flags - bool reset_encoders; - bool reset_gyro; - -} DrivetrainSoftwareInterface; - -class DrivetrainIO : public frc2::SubsystemBase { -public: - DrivetrainIO(DrivetrainHardwareInterface *hw_interface, - DrivetrainSoftwareInterface *sw_interface) - : hw_interface_(hw_interface), sw_interface_(sw_interface) {} - - /** - * Will be called periodically whenever the CommandScheduler runs. - */ - void Periodic() override; - - /** - * Will be called periodically whenever the CommandScheduler runs during - * simulation. - */ - void SimulationPeriodic() override; - - bool ProcessIO(); - -private: - bool UpdateDriveConfig(DrivetrainConfig &config); - bool ResetEncoders(); - - DrivetrainHardwareInterface *const hw_interface_; - DrivetrainSoftwareInterface *const sw_interface_; -}; -Footer From e9bf87291ba7a17b99a57d859ed9260b4c261a85 Mon Sep 17 00:00:00 2001 From: okcroboticsteam Date: Mon, 16 Jan 2023 16:24:59 -0600 Subject: [PATCH 10/28] it's being weird --- src/main/include/hardware/ActuatorInterface.h | 48 -------------- src/main/include/hardware/HardwareInterface.h | 64 ------------------- src/main/include/hardware/SensorInterface.h | 25 -------- 3 files changed, 137 deletions(-) delete mode 100644 src/main/include/hardware/ActuatorInterface.h delete mode 100644 src/main/include/hardware/HardwareInterface.h delete mode 100644 src/main/include/hardware/SensorInterface.h diff --git a/src/main/include/hardware/ActuatorInterface.h b/src/main/include/hardware/ActuatorInterface.h deleted file mode 100644 index b20b793..0000000 --- a/src/main/include/hardware/ActuatorInterface.h +++ /dev/null @@ -1,48 +0,0 @@ -#pragma once - -#include -#include - - -// CTRE namespace -namespace ctre_can = ctre::phoenix::motorcontrol::can; - -// Brushless Motor -#define BRUSHLESS rev::CANSparkMax::MotorType::kBrushless - -// Coast -#define COAST rev::CANSparkMax::IdleMode::kCoast - -// CAN IDs -#define LEFT_MOTOR_1 1 -#define LEFT_MOTOR_2 2 -#define LEFT_MOTOR_3 3 -#define RIGHT_MOTOR_1 4 -#define RIGHT_MOTOR_2 5 -#define RIGHT_MOTOR_3 6 - -#define INDEXER_MOTOR 7 -#define INTAKE_POSITION_MOTOR 10 -#define INTAKE_MOTOR 11 - -#define SHOOTER_MOTOR 8 -#define TRIGGER_MOTOR 9 - -typedef struct actuator_interface_t { - // Left drivetrain motors - std::unique_ptr left_front_drive; - std::unique_ptr left_back_drive; - std::unique_ptr left_front_steer; - std::unique_ptr left_back_steer; - - // Right drivetrain motors - std::unique_ptr right_front_drive; - std::unique_ptr right_back_drive; - std::unique_ptr right_front_steer; - std::unique_ptr right_back_steer; - - // arm motors - std::unique_ptr arm_lift_motor; - std::unique_ptr arm_up_motor; - std::unique_ptr arm_extend_motor; -} ActuatorInterface; \ No newline at end of file diff --git a/src/main/include/hardware/HardwareInterface.h b/src/main/include/hardware/HardwareInterface.h deleted file mode 100644 index e990a22..0000000 --- a/src/main/include/hardware/HardwareInterface.h +++ /dev/null @@ -1,64 +0,0 @@ -#pragma once - -#include -#include - -#include "hardware/ActuatorInterface.h" -#include "hardware/SensorInterface.h" - -// Subsystem I/O -#include "io/DrivetrainIO.h" -#include "io/IntakeIO.h" -#include "io/ShooterIO.h" - -typedef struct hardware_t { - // Actuators - std::unique_ptr actuators; - - // Drivetrain specific hardware abstractions. - std::unique_ptr diff_drive; - - // Sensors - std::unique_ptr sensors; - -} HardwareInterface; - -// Subsystem hardware setup functions - -/** - * @brief Link the Drivetrain to the hardware interfaces. - * - * @param interface - * @return true - * @return false - */ -bool SetupSwervedriveInterface( - std::unique_ptr &hardware, - std::shared_ptr *interface); - -/** - * @brief Link the Intake to the hardware interfaces. - * - * @param interface - * @return true - * @return false - */ -bool SetupArmInterface(std::unique_ptr &hardware, - std::shared_ptr *interface); - -/** - * @brief Link the Shooter to the hardware interfaces. - * - * @param interface - * @return true - * @return false - */ -bool SetupClawInterface( - std::unique_ptr &hardware, - std::shared_ptr *interface); - - bool SetupVisionTrackingInterface( - std::unique_ptr &hardware, - std::shared_ptr *interface); - - diff --git a/src/main/include/hardware/SensorInterface.h b/src/main/include/hardware/SensorInterface.h deleted file mode 100644 index 070cea3..0000000 --- a/src/main/include/hardware/SensorInterface.h +++ /dev/null @@ -1,25 +0,0 @@ -#pragma once - -#include - -#include "AHRS.h" -#include -#include - -// == sensor ports == -#define DEPLOY_LIMIT_SWITCH 2 -#define RETRACTED_LIMIT_SWITCH 3 - -#define BALL_DETECTOR 9 - -typedef struct sensors_t { - // navX IMU - std::unique_ptr ahrs; - - // intake limit switches - std::unique_ptr deploy_limit_switch; - std::unique_ptr retracted_limit_switch; - - // Shooter ball detector - std::unique_ptr ball_detector; -} SensorInterface; \ No newline at end of file From db16ef780e6583ebc6fb8815ac0d363c6c3742c3 Mon Sep 17 00:00:00 2001 From: Karun Singh Date: Sat, 21 Jan 2023 13:14:22 -0600 Subject: [PATCH 11/28] test commit --- src/main/include/hardware/Actuators.h | 4 ++++ src/main/include/subsystems/claw.h | 27 +++++++++++++++++++++++++++ 2 files changed, 31 insertions(+) create mode 100644 src/main/include/subsystems/claw.h diff --git a/src/main/include/hardware/Actuators.h b/src/main/include/hardware/Actuators.h index b20b793..d567d5f 100644 --- a/src/main/include/hardware/Actuators.h +++ b/src/main/include/hardware/Actuators.h @@ -45,4 +45,8 @@ typedef struct actuator_interface_t { std::unique_ptr arm_lift_motor; std::unique_ptr arm_up_motor; std::unique_ptr arm_extend_motor; + + // Claw things + std::unique_ptr claw_motor; + std::unique_ptr claw_IR_sensor; } ActuatorInterface; \ No newline at end of file diff --git a/src/main/include/subsystems/claw.h b/src/main/include/subsystems/claw.h new file mode 100644 index 0000000..a805151 --- /dev/null +++ b/src/main/include/subsystems/claw.h @@ -0,0 +1,27 @@ +// 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 + +class ExampleSubsystem : public frc2::SubsystemBase { + public: + ExampleSubsystem(); + + /** + * Will be called periodically whenever the CommandScheduler runs. + */ + void Periodic() override; + + /** + * Will be called periodically whenever the CommandScheduler runs during + * simulation. + */ + void SimulationPeriodic() override; + + private: + // Components (e.g. motor controllers and sensors) should generally be + // declared private and exposed only through public methods. +}; From 91016a4c222e01708c5376ebecafcae90dc5beae Mon Sep 17 00:00:00 2001 From: Karun Singh Date: Sat, 21 Jan 2023 13:30:07 -0600 Subject: [PATCH 12/28] functions added I think --- src/main/cpp/subsystems/claw.cpp | 20 ++++++++++++++++++++ src/main/include/subsystems/claw.h | 3 +++ 2 files changed, 23 insertions(+) create mode 100644 src/main/cpp/subsystems/claw.cpp diff --git a/src/main/cpp/subsystems/claw.cpp b/src/main/cpp/subsystems/claw.cpp new file mode 100644 index 0000000..a6dde86 --- /dev/null +++ b/src/main/cpp/subsystems/claw.cpp @@ -0,0 +1,20 @@ +#pragma once + +#include +#include "subsystems/claw.h" + +bool Claw::init() { + Claw_pid = std::make_shared(); + return true; +} + +bool Claw::SetPosition(double inches){ +this->Claw_pid->SetSetpoint (inches); + + return true; +} + + void Arm::Periodic(){ + this->interface_->claw_lift_power = this->Claw_pid->Calculate(this->interface_->claw_encoder); + + } diff --git a/src/main/include/subsystems/claw.h b/src/main/include/subsystems/claw.h index a805151..f8dd37b 100644 --- a/src/main/include/subsystems/claw.h +++ b/src/main/include/subsystems/claw.h @@ -21,6 +21,9 @@ class ExampleSubsystem : public frc2::SubsystemBase { */ void SimulationPeriodic() override; + bool init(); + bool SetPosition(double inches); + private: // Components (e.g. motor controllers and sensors) should generally be // declared private and exposed only through public methods. From c15cb656c009cc713f5a1d80074841e5558f53b3 Mon Sep 17 00:00:00 2001 From: Karun Singh Date: Sat, 21 Jan 2023 13:39:03 -0600 Subject: [PATCH 13/28] last changes for 1-21-23, added parameter,util --- src/main/cpp/Paramaters.cpp | 33 ++++++++++++++++ src/main/cpp/Utils.cpp | 21 ++++++++++ src/main/cpp/subsystems/claw.cpp | 3 ++ src/main/include/Parameters.h | 28 ++++++++++++++ src/main/include/Utils.h | 61 ++++++++++++++++++++++++++++++ src/main/include/subsystems/claw.h | 1 + 6 files changed, 147 insertions(+) create mode 100644 src/main/cpp/Paramaters.cpp create mode 100644 src/main/cpp/Utils.cpp create mode 100644 src/main/include/Parameters.h create mode 100644 src/main/include/Utils.h diff --git a/src/main/cpp/Paramaters.cpp b/src/main/cpp/Paramaters.cpp new file mode 100644 index 0000000..c61d064 --- /dev/null +++ b/src/main/cpp/Paramaters.cpp @@ -0,0 +1,33 @@ +#include "Parameters.h" + +namespace RobotParams { + toml::table parameters; + + // Save parameter file location. + std::string param_file = + frc::filesystem::GetDeployDirectory() + "/parameters.toml"; + + bool LoadParameters(const std::string &path) { + // Load the parameters from a file. + try { + parameters = toml::parse_file(path.c_str()); + } catch (const toml::parse_error &err) { + std::cerr << "Parsing failed:\n" << err << "\n"; + return false; + } + + return true; + } + + bool SaveParameters(const std::string &path) { + // Output the parameters table to the file. + std::ofstream file; + file.open(path, std::ofstream::out | std::ofstream::trunc); + file << parameters << std::flush; + file.close(); + + return true; + } + +} // namespace RobotParams + diff --git a/src/main/cpp/Utils.cpp b/src/main/cpp/Utils.cpp new file mode 100644 index 0000000..67db360 --- /dev/null +++ b/src/main/cpp/Utils.cpp @@ -0,0 +1,21 @@ +#include "Utils.h" + +namespace TeamOKC { + // TODO: make this a templated function. + bool Clamp(const double &lower, const double &upper, double *value) { + OKC_CHECK(value != nullptr); + + // Ensure value is not lower than the minimum or higher than the + // maximum. If it is out of the bounds, set it to the boundary value it + // violates. + if (*value < lower) { + *value = lower; + } else if (*value > upper) { + *value = upper; + } else { + // Nothing to do here, value is within the range. + } + + return true; + } +} // namespace TeamOKC \ No newline at end of file diff --git a/src/main/cpp/subsystems/claw.cpp b/src/main/cpp/subsystems/claw.cpp index a6dde86..3cf5692 100644 --- a/src/main/cpp/subsystems/claw.cpp +++ b/src/main/cpp/subsystems/claw.cpp @@ -18,3 +18,6 @@ this->Claw_pid->SetSetpoint (inches); this->interface_->claw_lift_power = this->Claw_pid->Calculate(this->interface_->claw_encoder); } +bool Claw::Reset(){ + //nothing +} \ No newline at end of file diff --git a/src/main/include/Parameters.h b/src/main/include/Parameters.h new file mode 100644 index 0000000..03b9f21 --- /dev/null +++ b/src/main/include/Parameters.h @@ -0,0 +1,28 @@ + +#pragma once + +#include +#include + +#include + +#include "Utils.h" +#include "third_party/toml.hpp" + +namespace RobotParams { + extern toml::table parameters; + extern std::string param_file; + + bool LoadParameters(const std::string &path); + bool SaveParameters(const std::string &path); + + template + T GetParam(const std::string_view &path, T default_val) { + return parameters.at_path(path).value_or(default_val); + } + + template bool SetParam(const std::string_view &path, T value) { + parameters.insert_or_assign(path, value); + return true; + } +} // namespace RobotParams \ No newline at end of file diff --git a/src/main/include/Utils.h b/src/main/include/Utils.h new file mode 100644 index 0000000..89f53c0 --- /dev/null +++ b/src/main/include/Utils.h @@ -0,0 +1,61 @@ + +#pragma once + +#include + +// Despite what VS Code highlighting might suggest, this uses __FUNCTION__ when +// compiliing using Visual Studio on Windows, and otherwise uses +// __PRETTY_FUNCTION__ +#if !defined(__PRETTY_FUNCTION__) && !defined(__GNUC__) +#define __SHOW_LINE_INFO__ __FUNCTION__ +#else +#define __SHOW_LINE_INFO__ __PRETTY_FUNCTION__ +#endif + +#define OKC_CALL(res) \ + if (!(res)) { \ + std::cerr << "OKC_CHECK FAIL [" << __FILE__ << ":" << __LINE__ \ + << "] - " << __SHOW_LINE_INFO__ << std::endl; \ + return false; \ + } + +#define OKC_CHECK(check) \ + if (!(check)) { \ + std::cerr << "OKC_CHECK FAIL [" << __FILE__ << ":" << __LINE__ \ + << "] - " << __SHOW_LINE_INFO__ << std::endl; \ + return false; \ + } + +#define OKC_CHECK_MSG(check, msg) \ + if (!(check)) { \ + std::cerr << "OKC_CHECK FAIL [" << __FILE__ << ":" << __LINE__ \ + << "] - " << __SHOW_LINE_INFO__ << ": " << msg << std::endl; \ + return false; \ + } + +#define VOKC_CALL(res) \ + if (!(res)) { \ + std::cerr << "OKC_CHECK FAIL [" << __FILE__ << ":" << __LINE__ \ + << "] - " << __SHOW_LINE_INFO__ << std::endl; \ + return; \ + } + +#define VOKC_CHECK(check) \ + if (!(check)) { \ + std::cerr << "OKC_CHECK FAIL [" << __FILE__ << ":" << __LINE__ \ + << "] - " << __SHOW_LINE_INFO__ << std::endl; \ + return; \ + } + +#define VOKC_CHECK_MSG(check, msg) \ + if (!(check)) { \ + std::cerr << "OKC_CHECK FAIL [" << __FILE__ << ":" << __LINE__ \ + << "] - " << __SHOW_LINE_INFO__ << ": " << msg << std::endl; \ + return; \ + } + +namespace TeamOKC { + + bool Clamp(const double &lower, const double &upper, double *value); + +} \ No newline at end of file diff --git a/src/main/include/subsystems/claw.h b/src/main/include/subsystems/claw.h index f8dd37b..503ad38 100644 --- a/src/main/include/subsystems/claw.h +++ b/src/main/include/subsystems/claw.h @@ -23,6 +23,7 @@ class ExampleSubsystem : public frc2::SubsystemBase { bool init(); bool SetPosition(double inches); + bool Reset(); private: // Components (e.g. motor controllers and sensors) should generally be From b7b9314409a387728471770d745ca528a87b243b Mon Sep 17 00:00:00 2001 From: X-EX3-X Date: Sat, 28 Jan 2023 10:16:33 -0600 Subject: [PATCH 14/28] I update the hardware and software interfaces --- src/main/include/io/clawIO.h | 52 ++++++++++++++++++++++++++++++++++++ 1 file changed, 52 insertions(+) create mode 100644 src/main/include/io/clawIO.h diff --git a/src/main/include/io/clawIO.h b/src/main/include/io/clawIO.h new file mode 100644 index 0000000..925c957 --- /dev/null +++ b/src/main/include/io/clawIO.h @@ -0,0 +1,52 @@ +#pragma once + +#include + +#include +#include +#include +#include + +#include "Utils.h" + + +typedef struct claw_config_t { + +} ClawConfig; + +typedef struct claw_hardware_interface_t { + rev::CANSparkMax *const claw_open_and_close_motor; + rev:SparkMaxRelativeEncoder *const claw_open_and_close_encoder; +} ClawHardwareInterface; + +typedef struct claw_software_interface_t { + + // actuator outputs + double claw_open_and_close_power; + double encoder_reading; + bool reset_claw_open_and_close; +} ClawSoftwareInterface; + +class ClawIO : public frc2::SubsystemBase { +public: + ClawIO(ClawHardwareInterface *hw_interface, + ClawSoftwareInterface *sw_interface) + : hw_interface_(hw_interface), sw_interface_(sw_interface) {} + + /** + * Will be called periodically whenever the CommandScheduler runs. + */ + void Periodic() override; + + /** + * Will be called periodically whenever the CommandScheduler runs during + * simulation. + */ + void SimulationPeriodic() override; + + bool ProcessIO(); + +private: + ClawHardwareInterface *const hw_interface_; + ClawSoftwareInterface *const sw_interface_; +}; \ No newline at end of file From 8e06a1e2cf36f9f650b46889a992a27581675d7e Mon Sep 17 00:00:00 2001 From: X-EX3-X Date: Sat, 28 Jan 2023 10:36:35 -0600 Subject: [PATCH 15/28] I changed the software and hardware interfaces and I defined functions in the subsystems --- src/main/cpp/IO/ClawIO.cpp | 29 +++++++++++++++++++++++ src/main/cpp/subsystems/Claw.cpp | 15 ++++++++++++ src/main/include/hardware/Actuators.h | 5 ++++ src/main/include/subsystems/claw.h | 33 +++++++++++++++++++++++++++ 4 files changed, 82 insertions(+) create mode 100644 src/main/cpp/IO/ClawIO.cpp create mode 100644 src/main/cpp/subsystems/Claw.cpp create mode 100644 src/main/include/subsystems/claw.h diff --git a/src/main/cpp/IO/ClawIO.cpp b/src/main/cpp/IO/ClawIO.cpp new file mode 100644 index 0000000..d727fa2 --- /dev/null +++ b/src/main/cpp/IO/ClawIO.cpp @@ -0,0 +1,29 @@ + +#include "io/clawIO.h" + +void clawIO::Periodic() { + // Process all the inputs and outputs to/from high level software. + VOKC_CALL(ProcessIO()); +} + +void ClawIO::SimulationPeriodic() { + // SimulationPeriodic +} + +bool ClawIO::ProcessIO() { + OKC_CHECK(sw_interface_ != nullptr); + OKC_CHECK(hw_interface_ != nullptr); + + // Set the software outputs + // If the encoder should be reset, reset it + if (sw_interface_->reset_encoders) { + hw_interface_.claw_open_and_close_encoder.SetPosition (0); + // Lower the encoder reset flag + sw_interface_->reset_claw_open_and_close = false; + } + hw_interface_.claw_open_and_close_motor.Set (sw_interface_.claw_open_and_close_power); + sw_interface_.encoder_reading = hw_interface_->claw_open_and_close_encoder->GetPosition(); + + return true; +} + diff --git a/src/main/cpp/subsystems/Claw.cpp b/src/main/cpp/subsystems/Claw.cpp new file mode 100644 index 0000000..138f736 --- /dev/null +++ b/src/main/cpp/subsystems/Claw.cpp @@ -0,0 +1,15 @@ +#include "subsytems/claw.h" + +bool Claw::Init(){ + return true; +} + +bool Claw::ResetPositionEncoder(){ + return true; +} +bool Claw::ResetPositionPID(){ + return true; +} +bool Claw::SetPosition(){ + return true; +} \ No newline at end of file diff --git a/src/main/include/hardware/Actuators.h b/src/main/include/hardware/Actuators.h index b20b793..42507c0 100644 --- a/src/main/include/hardware/Actuators.h +++ b/src/main/include/hardware/Actuators.h @@ -45,4 +45,9 @@ typedef struct actuator_interface_t { std::unique_ptr arm_lift_motor; std::unique_ptr arm_up_motor; std::unique_ptr arm_extend_motor; + + // claw + std::unique_ptr claw_servo; + std::unique_ptr IR_sensor; + } ActuatorInterface; \ No newline at end of file diff --git a/src/main/include/subsystems/claw.h b/src/main/include/subsystems/claw.h new file mode 100644 index 0000000..691f749 --- /dev/null +++ b/src/main/include/subsystems/claw.h @@ -0,0 +1,33 @@ +#pragma once + +#include + +class ClawSubsystem : public frc2::SubsystemBase { + public: + ClawSubsystem(); + + bool Init(); + + bool ResetPositionEncoder(); + bool ResetPositionPID(); + + bool SetPosition(); + + /** + * Will be called periodically whenever the CommandScheduler runs. + */ + void Periodic() override; + + /** + * Will be called periodically whenever the CommandScheduler runs during + * simulation. + */ + void SimulationPeriodic() override; + + private: + // Components (e.g. motor controllers and sensors) should generally be + // declared private and exposed only through public methods. + +}; + + \ No newline at end of file From d43dd10784a72c11997caf0eac6c75eefcaf5f8d Mon Sep 17 00:00:00 2001 From: X-EX3-X Date: Sat, 28 Jan 2023 10:41:31 -0600 Subject: [PATCH 16/28] fleshed out claw subsystem --- src/main/cpp/subsystems/claw.cpp | 24 ++++++++---------------- 1 file changed, 8 insertions(+), 16 deletions(-) diff --git a/src/main/cpp/subsystems/claw.cpp b/src/main/cpp/subsystems/claw.cpp index 3cf5692..138f736 100644 --- a/src/main/cpp/subsystems/claw.cpp +++ b/src/main/cpp/subsystems/claw.cpp @@ -1,23 +1,15 @@ -#pragma once +#include "subsytems/claw.h" -#include -#include "subsystems/claw.h" - -bool Claw::init() { - Claw_pid = std::make_shared(); +bool Claw::Init(){ return true; } -bool Claw::SetPosition(double inches){ -this->Claw_pid->SetSetpoint (inches); - +bool Claw::ResetPositionEncoder(){ return true; } - - void Arm::Periodic(){ - this->interface_->claw_lift_power = this->Claw_pid->Calculate(this->interface_->claw_encoder); - - } -bool Claw::Reset(){ - //nothing +bool Claw::ResetPositionPID(){ + return true; +} +bool Claw::SetPosition(){ + return true; } \ No newline at end of file From f8333d7b87e9e6c195f8591453394f47dfce966b Mon Sep 17 00:00:00 2001 From: X-EX3-X Date: Sat, 28 Jan 2023 11:50:27 -0600 Subject: [PATCH 17/28] IT WORKSSSS EVERYTHING WORKSSSSSSSSSSSSSSS --- build.gradle | 2 +- src/main/cpp/IO/ClawIO.cpp | 12 +- src/main/cpp/IO/SwerveDriveIO.cpp | 167 - src/main/cpp/IO/SwerveDriveIO.h | 137 - src/main/cpp/IO/armIO.cpp | 98 - src/main/cpp/hardware/hardwareInterface.cpp | 5 - src/main/cpp/subsystems/arm.cpp | 15 - src/main/cpp/subsystems/claw.cpp | 8 +- src/main/include/RobotContainer.h | 6 +- src/main/include/hardware/Actuators.h | 6 +- src/main/include/io/armIO.h | 57 - src/main/include/io/clawIO.h | 2 +- src/main/include/subsystems/arm.h | 15 - src/main/include/subsystems/claw.h | 9 +- src/main/include/third_party/toml.hpp | 17257 ++++++++++++++++++ vendordeps/REVLib.json | 73 + 16 files changed, 17353 insertions(+), 516 deletions(-) delete mode 100644 src/main/cpp/IO/SwerveDriveIO.cpp delete mode 100644 src/main/cpp/IO/SwerveDriveIO.h delete mode 100644 src/main/cpp/IO/armIO.cpp delete mode 100644 src/main/cpp/hardware/hardwareInterface.cpp delete mode 100644 src/main/cpp/subsystems/arm.cpp delete mode 100644 src/main/include/io/armIO.h delete mode 100644 src/main/include/subsystems/arm.h create mode 100644 src/main/include/third_party/toml.hpp create mode 100644 vendordeps/REVLib.json diff --git a/build.gradle b/build.gradle index 2451599..313fab4 100644 --- a/build.gradle +++ b/build.gradle @@ -1,7 +1,7 @@ plugins { id "cpp" id "google-test-test-suite" - id "edu.wpi.first.GradleRIO" version "2023.1.1" + id "edu.wpi.first.GradleRIO" version "2023.2.1" } // Define my targets (RoboRIO) and artifacts (deployable files) diff --git a/src/main/cpp/IO/ClawIO.cpp b/src/main/cpp/IO/ClawIO.cpp index d727fa2..cf64601 100644 --- a/src/main/cpp/IO/ClawIO.cpp +++ b/src/main/cpp/IO/ClawIO.cpp @@ -1,7 +1,7 @@ -#include "io/clawIO.h" +#include "io/ClawIO.h" -void clawIO::Periodic() { +void ClawIO::Periodic() { // Process all the inputs and outputs to/from high level software. VOKC_CALL(ProcessIO()); } @@ -16,13 +16,13 @@ bool ClawIO::ProcessIO() { // Set the software outputs // If the encoder should be reset, reset it - if (sw_interface_->reset_encoders) { - hw_interface_.claw_open_and_close_encoder.SetPosition (0); + if (sw_interface_->reset_claw_open_and_close) { + hw_interface_->claw_open_and_close_encoder->SetPosition (0); // Lower the encoder reset flag sw_interface_->reset_claw_open_and_close = false; } - hw_interface_.claw_open_and_close_motor.Set (sw_interface_.claw_open_and_close_power); - sw_interface_.encoder_reading = hw_interface_->claw_open_and_close_encoder->GetPosition(); + hw_interface_->claw_open_and_close_motor->Set (sw_interface_->claw_open_and_close_power); + sw_interface_->encoder_reading = hw_interface_->claw_open_and_close_encoder->GetPosition(); return true; } diff --git a/src/main/cpp/IO/SwerveDriveIO.cpp b/src/main/cpp/IO/SwerveDriveIO.cpp deleted file mode 100644 index 231d41c..0000000 --- a/src/main/cpp/IO/SwerveDriveIO.cpp +++ /dev/null @@ -1,167 +0,0 @@ -#include "io/SwerveDriveIO.h" -#include "Utils.h" - -void SwerveDriveIO::Periodic() { - // Process all the inputs and outputs to/from high level software. - VOKC_CALL(ProcessIO()); -} - -void SwerveDriveIO::SimulationPeriodic() { - // SimulationPeriodic -} - -bool SwerveDriveIO::ProcessIO() { - OKC_CHECK(sw_interface_ != nullptr); - OKC_CHECK(hw_interface_ != nullptr); - - // Set the software outputs - // If the swerve drive configuration needs to be updated, update it. - if (sw_interface_->update_config) { - OKC_CALL(UpdateDriveConfig(sw_interface_->drive_config)); - - // Lower the update flag - sw_interface_->update_config = false; - } - - // If the encoders should be reset, reset them - if (sw_interface_->reset_drive_encoders) { - OKC_CALL(ResetDriveEncoders()); - - // Lower the encoder reset flag - sw_interface_->reset_drive_encoders = false; - } - - if (sw_interface_->reset_steer_encoders) { - OKC_CALL(ResetSteerEncoders()); - - // Lower the encoder reset flag - sw_interface_->reset_steer_encoders = false; - } - - // If the navX should be reset, reset it. - if (sw_interface_->reset_gyro) { - hw_interface_->ahrs->Reset(); - - // Lower the navX reset flag - sw_interface_->reset_gyro = false; - } - - OKC_CHECK(hw_interface_->left_front_drive_motor != nullptr); - OKC_CHECK(hw_interface_->left_back_drive_motor != nullptr); - OKC_CHECK(hw_interface_->right_front_drive_motor != nullptr); - OKC_CHECK(hw_interface_->right_back_drive_motor != nullptr); - - // Set the drive outputs. - // hw_interface_->left_front_drive_motor->Set(TeamOKC::Clamp(-this->sw_interface_->drive_config.max_output_drive, this->sw_interface_->drive_config.max_output_drive, &this->sw_interface_->left_front_drive_motor_output)); - // hw_interface_->left_back_drive_motor->Set(TeamOKC::Clamp(-this->sw_interface_->drive_config.max_output_drive, this->sw_interface_->drive_config.max_output_drive, &this->sw_interface_->left_back_drive_motor_output)); - // hw_interface_->right_front_drive_motor->Set(TeamOKC::Clamp(-this->sw_interface_->drive_config.max_output_drive, this->sw_interface_->drive_config.max_output_drive, &this->sw_interface_->right_front_drive_motor_output)); - // hw_interface_->right_back_drive_motor->Set(TeamOKC::Clamp(-this->sw_interface_->drive_config.max_output_drive, this->sw_interface_->drive_config.max_output_drive, &this->sw_interface_->right_back_drive_motor_output)); - hw_interface_->left_front_drive_motor->Set(this->sw_interface_->left_front_drive_motor_output); - hw_interface_->left_back_drive_motor->Set(this->sw_interface_->left_back_drive_motor_output); - hw_interface_->right_front_drive_motor->Set(this->sw_interface_->right_front_drive_motor_output); - hw_interface_->right_back_drive_motor->Set(this->sw_interface_->right_back_drive_motor_output); - - // set the steer outputs. - // hw_interface_->left_front_steer_motor->Set(TeamOKC::Clamp(-this->sw_interface_->drive_config.max_output_steer, this->sw_interface_->drive_config.max_output_steer, &this->sw_interface_->left_front_steer_motor_output)); - // hw_interface_->left_back_steer_motor->Set(TeamOKC::Clamp(-this->sw_interface_->drive_config.max_output_steer, this->sw_interface_->drive_config.max_output_steer, &this->sw_interface_->left_back_steer_motor_output)); - // hw_interface_->right_front_steer_motor->Set(TeamOKC::Clamp(-this->sw_interface_->drive_config.max_output_steer, this->sw_interface_->drive_config.max_output_steer, &this->sw_interface_->right_front_steer_motor_output)); - // hw_interface_->right_back_steer_motor->Set(TeamOKC::Clamp(-this->sw_interface_->drive_config.max_output_steer, this->sw_interface_->drive_config.max_output_steer, &this->sw_interface_->right_back_steer_motor_output)); - hw_interface_->left_front_steer_motor->Set(this->sw_interface_->left_front_steer_motor_output); - hw_interface_->left_back_steer_motor->Set(this->sw_interface_->left_back_steer_motor_output); - hw_interface_->right_front_steer_motor->Set(this->sw_interface_->right_front_steer_motor_output); - hw_interface_->right_back_steer_motor->Set(this->sw_interface_->right_back_steer_motor_output); - - // Get the hardware sensor values. - // navX IMU: - sw_interface_->imu_yaw = hw_interface_->ahrs->GetAngle(); - - // Encoders - // position - // drive - sw_interface_->left_front_drive_motor_enc = hw_interface_->left_front_drive_encoder->GetPosition(); - sw_interface_->left_back_drive_motor_enc = hw_interface_->left_back_drive_encoder->GetPosition(); - sw_interface_->right_front_drive_motor_enc = hw_interface_->right_front_drive_encoder->GetPosition(); - sw_interface_->right_back_drive_motor_enc = hw_interface_->right_back_drive_encoder->GetPosition(); - - // steer - sw_interface_->left_front_steer_motor_enc = hw_interface_->left_front_steer_encoder->GetAbsolutePosition(); - sw_interface_->left_back_steer_motor_enc = hw_interface_->left_back_steer_encoder->GetAbsolutePosition(); - sw_interface_->right_front_steer_motor_enc = hw_interface_->right_front_steer_encoder->GetAbsolutePosition(); - sw_interface_->right_back_steer_motor_enc = hw_interface_->right_back_steer_encoder->GetAbsolutePosition(); - - // velocity - // drive - sw_interface_->left_front_drive_enc_vel = hw_interface_->left_front_drive_encoder->GetVelocity(); - sw_interface_->left_back_drive_enc_vel = hw_interface_->left_back_drive_encoder->GetVelocity(); - sw_interface_->right_front_drive_enc_vel = hw_interface_->right_front_drive_encoder->GetVelocity(); - sw_interface_->right_back_drive_enc_vel = hw_interface_->right_back_drive_encoder->GetVelocity(); - - // steer - sw_interface_->left_front_steer_enc_vel = hw_interface_->left_front_steer_vel_encoder->GetVelocity(); - sw_interface_->left_back_steer_enc_vel = hw_interface_->left_back_steer_vel_encoder->GetVelocity(); - sw_interface_->right_front_steer_enc_vel = hw_interface_->right_front_steer_vel_encoder->GetVelocity(); - sw_interface_->right_back_steer_enc_vel = hw_interface_->right_back_steer_vel_encoder->GetVelocity(); - - return true; -} - -bool SwerveDriveIO::UpdateDriveConfig(SwerveDriveConfig &config) { - OKC_CHECK(hw_interface_ != nullptr); - - OKC_CHECK(hw_interface_->left_front_drive_motor != nullptr); - OKC_CHECK(hw_interface_->left_back_drive_motor != nullptr); - OKC_CHECK(hw_interface_->right_front_drive_motor != nullptr); - OKC_CHECK(hw_interface_->right_back_drive_motor != nullptr); - - // Get the configuration - double open_loop_ramp_drive = config.open_loop_ramp_rate_drive; - double open_loop_ramp_steer = config.open_loop_ramp_rate_steer; - double max_output_drive = config.max_output_drive; - double max_output_steer = config.max_output_steer; - - // Apply the configuration - // Open Loop Ramp Rate - hw_interface_->left_front_drive_motor->SetOpenLoopRampRate(open_loop_ramp_drive); - hw_interface_->left_back_drive_motor->SetOpenLoopRampRate(open_loop_ramp_drive); - hw_interface_->right_front_drive_motor->SetOpenLoopRampRate(open_loop_ramp_drive); - hw_interface_->right_back_drive_motor->SetOpenLoopRampRate(open_loop_ramp_drive); - - hw_interface_->left_front_steer_motor->SetOpenLoopRampRate(open_loop_ramp_steer); - hw_interface_->left_back_steer_motor->SetOpenLoopRampRate(open_loop_ramp_steer); - hw_interface_->right_front_steer_motor->SetOpenLoopRampRate(open_loop_ramp_steer); - hw_interface_->right_back_steer_motor->SetOpenLoopRampRate(open_loop_ramp_steer); - - return true; -} - -bool SwerveDriveIO::ResetDriveEncoders() { - OKC_CHECK(hw_interface_ != nullptr); - - OKC_CHECK(hw_interface_->left_front_drive_encoder != nullptr); - OKC_CHECK(hw_interface_->left_back_drive_encoder != nullptr); - OKC_CHECK(hw_interface_->right_front_drive_encoder != nullptr); - OKC_CHECK(hw_interface_->right_back_drive_encoder != nullptr); - - OKC_CHECK(hw_interface_->left_front_drive_motor != nullptr); - OKC_CHECK(hw_interface_->left_back_drive_motor != nullptr); - OKC_CHECK(hw_interface_->right_front_drive_motor != nullptr); - OKC_CHECK(hw_interface_->right_back_drive_motor != nullptr); - - // internal encoders - hw_interface_->left_front_drive_encoder->SetPosition(0); - hw_interface_->left_back_drive_encoder->SetPosition(0); - hw_interface_->right_front_drive_encoder->SetPosition(0); - hw_interface_->right_back_drive_encoder->SetPosition(0); - - return true; -} - -bool SwerveDriveIO::ResetSteerEncoders() { - OKC_CHECK(hw_interface_ != nullptr); - - //TODO - - return true; -} - - diff --git a/src/main/cpp/IO/SwerveDriveIO.h b/src/main/cpp/IO/SwerveDriveIO.h deleted file mode 100644 index 14eb055..0000000 --- a/src/main/cpp/IO/SwerveDriveIO.h +++ /dev/null @@ -1,137 +0,0 @@ -#pragma once - -#include - -#include -#include - -#include "AHRS.h" -#include "Utils.h" -#include "frc/AnalogEncoder.h" - -typedef struct swerve_drive_config_t { - double max_output_drive; - double open_loop_ramp_rate_drive; - - double max_output_steer; - double open_loop_ramp_rate_steer; -} SwerveDriveConfig; - -typedef struct swerve_drive_hardware_interface_t { - // motors - rev::CANSparkMax *const left_front_drive_motor; - rev::CANSparkMax *const left_back_drive_motor; - - rev::CANSparkMax *const right_front_drive_motor; - rev::CANSparkMax *const right_back_drive_motor; - - rev::CANSparkMax *const left_front_steer_motor; - rev::CANSparkMax *const left_back_steer_motor; - - rev::CANSparkMax *const right_front_steer_motor; - rev::CANSparkMax *const right_back_steer_motor; - - // AHRS - AHRS *const ahrs; - - // drive encoders - rev::SparkMaxRelativeEncoder *const left_front_drive_encoder; - rev::SparkMaxRelativeEncoder *const left_back_drive_encoder; - rev::SparkMaxRelativeEncoder *const right_front_drive_encoder; - rev::SparkMaxRelativeEncoder *const right_back_drive_encoder; - - // Steer encoders - frc::AnalogEncoder *const left_front_steer_encoder; - frc::AnalogEncoder *const left_back_steer_encoder; - frc::AnalogEncoder *const right_front_steer_encoder; - frc::AnalogEncoder *const right_back_steer_encoder; - - // other steer encoders - rev::SparkMaxRelativeEncoder *const left_front_steer_vel_encoder; - rev::SparkMaxRelativeEncoder *const left_back_steer_vel_encoder; - rev::SparkMaxRelativeEncoder *const right_front_steer_vel_encoder; - rev::SparkMaxRelativeEncoder *const right_back_steer_vel_encoder; -} SwerveDriveHardwareInterface; - -typedef struct swerve_drive_software_interface_t { - // SW INPUTS - // IMU yaw angle - double imu_yaw; - - // Encoders - double left_front_drive_motor_enc; - double left_back_drive_motor_enc; - double right_front_drive_motor_enc; - double right_back_drive_motor_enc; - - double left_front_steer_motor_enc; - double left_back_steer_motor_enc; - double right_front_steer_motor_enc; - double right_back_steer_motor_enc; - - // encoder velocities - double left_front_drive_enc_vel; - double left_back_drive_enc_vel; - double right_front_drive_enc_vel; - double right_back_drive_enc_vel; - - double left_front_steer_enc_vel; - double left_back_steer_enc_vel; - double right_front_steer_enc_vel; - double right_back_steer_enc_vel; - - // SW OUTPUTS - // Configure swerve drive variables - SwerveDriveConfig drive_config; - bool update_config; - - // Input squaring - bool square_inputs; - - // motor outputs - double left_front_drive_motor_output; - double left_back_drive_motor_output; - - double right_front_drive_motor_output; - double right_back_drive_motor_output; - - double left_front_steer_motor_output; - double left_back_steer_motor_output; - - double right_front_steer_motor_output; - double right_back_steer_motor_output; - - // Reset flags - bool reset_drive_encoders; - bool reset_steer_encoders; - bool reset_gyro; - -} SwerveDriveSoftwareInterface; - -class SwerveDriveIO : public frc2::SubsystemBase { -public: - SwerveDriveIO(SwerveDriveHardwareInterface *hw_interface, - SwerveDriveSoftwareInterface *sw_interface) - : hw_interface_(hw_interface), sw_interface_(sw_interface) {} - - /** - * Will be called periodically whenever the CommandScheduler runs. - */ - void Periodic() override; - - /** - * Will be called periodically whenever the CommandScheduler runs during - * simulation. - */ - void SimulationPeriodic() override; - - bool ProcessIO(); - -private: - bool UpdateDriveConfig(SwerveDriveConfig &config); - bool ResetDriveEncoders(); - bool ResetSteerEncoders(); - - SwerveDriveHardwareInterface *const hw_interface_; - SwerveDriveSoftwareInterface *const sw_interface_; -}; diff --git a/src/main/cpp/IO/armIO.cpp b/src/main/cpp/IO/armIO.cpp deleted file mode 100644 index e01cec1..0000000 --- a/src/main/cpp/IO/armIO.cpp +++ /dev/null @@ -1,98 +0,0 @@ - -#include "io/ArmIO.h" - -void ArmIO::Periodic() { - // Process all the inputs and outputs to/from high level software. - VOKC_CALL(ProcessIO()); -} - -void ArmIO::SimulationPeriodic() { - // SimulationPeriodic -} - -bool ArmIO::ProcessIO() { - OKC_CHECK(sw_interface_ != nullptr); - OKC_CHECK(hw_interface_ != nullptr); - - // Set the software outputs - // If the intake configuration needs to be updated, update it. - if (sw_interface_->update_config) { - OKC_CALL(UpdateArmConfig(sw_interface_->arm_config)); - - // Lower the update flag - sw_interface_->update_config = false; - } - - // If the encoder should be reset, reset it - if (sw_interface_->reset_encoders) { - OKC_CALL(ResetEncoders()); - - // Lower the encoder reset flag - sw_interface_->reset_encoders = false; - } - - // if the encoder should be set to a specific value - if (sw_interface_->set_encoder_to_val) { - OKC_CALL(SetEncoder(sw_interface_->encoder_val_to_set)) - - sw_interface_->set_encoder_to_val = false; - } - - - // Get the hardware sensor values. - // limit switches - sw_interface_->deployed_limit_switch_val = hw_interface_->deploy_limit_switch->Get(); //??? - sw_interface_->retracted_limit_switch_val = hw_interface_->retracted_limit_switch->Get(); //??? - - // intake position encoder - sw_interface_->arm_position_encoder_val = - hw_interface_->arm_position_motor->GetEncoder().GetPosition(); - - return true; -} - -bool ArmIO::UpdateArmConfig(ArmConfig &config) { - OKC_CHECK(hw_interface_ != nullptr); - - // Get the configuration - double open_loop_ramp = config.open_loop_ramp_rate; - //double max_output_deploy = config.max_output_deploy; - //double max_output_retract = config.max_output_retract; - double max_indexer_current = config.max_indexer_current; - - // Apply the configuration - // Open Loop Ramp Rate - hw_interface_->arm_motor->SetOpenLoopRampRate(open_loop_ramp); - hw_interface_->indexer_motor->SetOpenLoopRampRate(open_loop_ramp); - - // Java code has this commented out as well, I'm assuming because it was meesing something up. - // well, the intake works (probably, been a while since it's been actually plugged in) without this, - // so leaving commented out for now - // hw_interface_->intake_position_motor->SetOpenLoopRampRate(open_loop_ramp); - - // current limiting, so the neo 550 on the indexer doesn't stall and smoke - hw_interface_->indexer_motor->SetSmartCurrentLimit(max_indexer_current); - - return true; -} - -bool ArmIO::ResetEncoders() { - OKC_CHECK(hw_interface_ != nullptr); - - hw_interface_->arm_position_motor->GetEncoder().SetPosition(0.0); - - // we currently don't use the encoder for these other two motors, so we don't need to reset them - // yet. yet. - // hw_interface_->intake_motor->GetEncoder().SetPosition(0.0); - // hw_interface_->indexer_motor->GetEncoder().SetPosition(0.0); - - return true; -} - -bool ArmIO::SetEncoder(double &val) { - OKC_CHECK(hw_interface_ != nullptr); - - hw_interface_->arm_position_motor->GetEncoder().SetPosition(val); - - return true; -} \ No newline at end of file diff --git a/src/main/cpp/hardware/hardwareInterface.cpp b/src/main/cpp/hardware/hardwareInterface.cpp deleted file mode 100644 index 41790db..0000000 --- a/src/main/cpp/hardware/hardwareInterface.cpp +++ /dev/null @@ -1,5 +0,0 @@ - - - -#include "hardware/HardwareInterface.h" - diff --git a/src/main/cpp/subsystems/arm.cpp b/src/main/cpp/subsystems/arm.cpp deleted file mode 100644 index 7ff9bd8..0000000 --- a/src/main/cpp/subsystems/arm.cpp +++ /dev/null @@ -1,15 +0,0 @@ -bool Arm::init(){ - return true; -} - -bool Arm::SetDegrees(double degrees){ - return true; -} - -bool Arm::SetExtend(double inches){ - return true; -} - -bool Arm::Function(int number){ - return true; -} \ No newline at end of file diff --git a/src/main/cpp/subsystems/claw.cpp b/src/main/cpp/subsystems/claw.cpp index 138f736..2cbccb2 100644 --- a/src/main/cpp/subsystems/claw.cpp +++ b/src/main/cpp/subsystems/claw.cpp @@ -1,4 +1,4 @@ -#include "subsytems/claw.h" +#include "subsystems/Claw.h" bool Claw::Init(){ return true; @@ -11,5 +11,11 @@ bool Claw::ResetPositionPID(){ return true; } bool Claw::SetPosition(){ + // SetPosition (30); //cone + // SetPosition (0); //close + // SetPosition (50);//cube + return true; +} +bool Claw::Reset(){ return true; } \ No newline at end of file diff --git a/src/main/include/RobotContainer.h b/src/main/include/RobotContainer.h index 7c82aab..0c1a961 100644 --- a/src/main/include/RobotContainer.h +++ b/src/main/include/RobotContainer.h @@ -6,7 +6,8 @@ #include - +#include "frc/Joystick.h" +#include "frc2/command/button/JoystickButton.h" /** * This class is where the bulk of the robot should be declared. Since @@ -38,8 +39,6 @@ class RobotContainer { std::shared_ptr manip_a_button_; std::shared_ptr manip_b_button_; - std::shared_ptr manip_back_button_; - std::shared_ptr manip_start_button_; std::shared_ptr manip_left_stick_button_; std::shared_ptr manip_right_stick_button; @@ -70,6 +69,5 @@ class RobotContainer { std::shared_ptr manip_mode_button_; }; -}; diff --git a/src/main/include/hardware/Actuators.h b/src/main/include/hardware/Actuators.h index d567d5f..2b2ee88 100644 --- a/src/main/include/hardware/Actuators.h +++ b/src/main/include/hardware/Actuators.h @@ -2,11 +2,9 @@ #include #include +#include "frc/DigitalInput.h" -// CTRE namespace -namespace ctre_can = ctre::phoenix::motorcontrol::can; - // Brushless Motor #define BRUSHLESS rev::CANSparkMax::MotorType::kBrushless @@ -48,5 +46,5 @@ typedef struct actuator_interface_t { // Claw things std::unique_ptr claw_motor; - std::unique_ptr claw_IR_sensor; + std::unique_ptr claw_IR_sensor; } ActuatorInterface; \ No newline at end of file diff --git a/src/main/include/io/armIO.h b/src/main/include/io/armIO.h deleted file mode 100644 index 0ddfad8..0000000 --- a/src/main/include/io/armIO.h +++ /dev/null @@ -1,57 +0,0 @@ -#pragma once - -#include - -#include -#include -#include -#include - -#include "Utils.h" - - -typedef struct Arm_config_t { - -} ArmConfig; - -typedef struct arm_hardware_interface_t { - std::unique_ptr arm_lift_motor; - std::unique_ptr arm_up_motor; - std::unique_ptr arm_extend_motor; -} ArmHardwareInterface; - -typedef struct arm_software_interface_t { - - // actuator outputs - double arm_lift_power; - double arm_up_power; - double arm_extend_power; -} ArmSoftwareInterface; - -class ArmIO : public frc2::SubsystemBase { -public: - ArmIO(ArmHardwareInterface *hw_interface, - ArmSoftwareInterface *sw_interface) - : hw_interface_(hw_interface), sw_interface_(sw_interface) {} - - /** - * Will be called periodically whenever the CommandScheduler runs. - */ - void Periodic() override; - - /** - * Will be called periodically whenever the CommandScheduler runs during - * simulation. - */ - void SimulationPeriodic() override; - - bool ProcessIO(); - -private: - bool UpdateArmConfig(ArmConfig &config); - bool ResetEncoders(); - bool SetEncoder(double &val); - - ArmHardwareInterface *const hw_interface_; - ArmSoftwareInterface *const sw_interface_; -}; \ No newline at end of file diff --git a/src/main/include/io/clawIO.h b/src/main/include/io/clawIO.h index 925c957..1879426 100644 --- a/src/main/include/io/clawIO.h +++ b/src/main/include/io/clawIO.h @@ -16,7 +16,7 @@ typedef struct claw_config_t { typedef struct claw_hardware_interface_t { rev::CANSparkMax *const claw_open_and_close_motor; - rev:SparkMaxRelativeEncoder *const claw_open_and_close_encoder; + rev::SparkMaxRelativeEncoder *const claw_open_and_close_encoder; } ClawHardwareInterface; typedef struct claw_software_interface_t { diff --git a/src/main/include/subsystems/arm.h b/src/main/include/subsystems/arm.h deleted file mode 100644 index be60029..0000000 --- a/src/main/include/subsystems/arm.h +++ /dev/null @@ -1,15 +0,0 @@ - - -class Arm : public frc2::SubsystemBase { -public: -Arm(ArmSoftwareInterface *interface) - : interface_(interface), Arm_pid(1.0, 0.0, 0.0) {} - ~Arm() {} - - bool Function(int number); - bool SetDegrees(double degrees); - bool SetExtend(double inches); - bool init(); -private: - ArmSoftwareInterface *const interface; -}; \ No newline at end of file diff --git a/src/main/include/subsystems/claw.h b/src/main/include/subsystems/claw.h index 27ef144..67191ac 100644 --- a/src/main/include/subsystems/claw.h +++ b/src/main/include/subsystems/claw.h @@ -1,17 +1,15 @@ -<<<<<<< HEAD -======= // 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. ->>>>>>> c15cb656c009cc713f5a1d80074841e5558f53b3 #pragma once #include -class ClawSubsystem : public frc2::SubsystemBase { +class Claw : public frc2::SubsystemBase { public: - ClawSubsystem(); + Claw(); + ~Claw(); bool Init(); @@ -19,6 +17,7 @@ class ClawSubsystem : public frc2::SubsystemBase { bool ResetPositionPID(); bool SetPosition(); + bool Reset(); /** * Will be called periodically whenever the CommandScheduler runs. diff --git a/src/main/include/third_party/toml.hpp b/src/main/include/third_party/toml.hpp new file mode 100644 index 0000000..5e4c7f8 --- /dev/null +++ b/src/main/include/third_party/toml.hpp @@ -0,0 +1,17257 @@ +//---------------------------------------------------------------------------------------------------------------------- +// +// toml++ v3.2.0 +// https://github.com/marzer/tomlplusplus +// SPDX-License-Identifier: MIT +// +//---------------------------------------------------------------------------------------------------------------------- +// +// - THIS FILE WAS ASSEMBLED FROM MULTIPLE HEADER FILES BY A SCRIPT - PLEASE DON'T EDIT IT DIRECTLY - +// +// If you wish to submit a contribution to toml++, hooray and thanks! Before you crack on, please be aware that this +// file was assembled from a number of smaller files by a python script, and code contributions should not be made +// against it directly. You should instead make your changes in the relevant source file(s). The file names of the files +// that contributed to this header can be found at the beginnings and ends of the corresponding sections of this file. +// +//---------------------------------------------------------------------------------------------------------------------- +// +// TOML Language Specifications: +// latest: https://github.com/toml-lang/toml/blob/master/README.md +// v1.0.0: https://toml.io/en/v1.0.0 +// v0.5.0: https://toml.io/en/v0.5.0 +// changelog: https://github.com/toml-lang/toml/blob/master/CHANGELOG.md +// +//---------------------------------------------------------------------------------------------------------------------- +// +// MIT License +// +// Copyright (c) Mark Gillard +// +// 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. +// +//---------------------------------------------------------------------------------------------------------------------- +#ifndef TOMLPLUSPLUS_H +#define TOMLPLUSPLUS_H + +#define INCLUDE_TOMLPLUSPLUS_H // old guard name used pre-v3 + +//******** impl/preprocessor.h *************************************************************************************** + +#ifndef __cplusplus +#error toml++ is a C++ library. +#endif +#ifdef _MSVC_LANG +#define TOML_CPP _MSVC_LANG +#else +#define TOML_CPP __cplusplus +#endif +#if TOML_CPP >= 202002L +#undef TOML_CPP +#define TOML_CPP 20 +#elif TOML_CPP >= 201703L +#undef TOML_CPP +#define TOML_CPP 17 +#else +#if TOML_CPP < 201103L +#error toml++ requires C++17 or higher. For a pre-C++11 TOML library see https://github.com/ToruNiina/Boost.toml +#elif TOML_CPP < 201703L +#error toml++ requires C++17 or higher. For a C++11 TOML library see https://github.com/ToruNiina/toml11 +#endif +#endif + +#ifdef __clang__ +#define TOML_CLANG __clang_major__ +#else +#define TOML_CLANG 0 +#endif +#ifdef __INTEL_COMPILER +#define TOML_ICC __INTEL_COMPILER +#ifdef __ICL +#define TOML_ICC_CL TOML_ICC +#else +#define TOML_ICC_CL 0 +#endif +#else +#define TOML_ICC 0 +#define TOML_ICC_CL 0 +#endif +#if defined(_MSC_VER) && !TOML_CLANG && !TOML_ICC +#define TOML_MSVC _MSC_VER +#else +#define TOML_MSVC 0 +#endif +#if defined(__GNUC__) && !TOML_CLANG && !TOML_ICC +#define TOML_GCC __GNUC__ +#else +#define TOML_GCC 0 +#endif +#if defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__NT__) || defined(__CYGWIN__) +#define TOML_WINDOWS 1 +#else +#define TOML_WINDOWS 0 +#endif +#if defined(DOXYGEN) || defined(__DOXYGEN__) || defined(__POXY__) || defined(__poxy__) +#define TOML_DOXYGEN 1 +#else +#define TOML_DOXYGEN 0 +#endif +#ifdef __INTELLISENSE__ +#define TOML_INTELLISENSE 1 +#else +#define TOML_INTELLISENSE 0 +#endif + +// IA64 +#if defined(__ia64__) || defined(__ia64) || defined(_IA64) || defined(__IA64__) || defined(_M_IA64) +#define TOML_ARCH_ITANIUM 1 +#else +#define TOML_ARCH_ITANIUM 0 +#endif + +// AMD64 +#if defined(__amd64__) || defined(__amd64) || defined(__x86_64__) || defined(__x86_64) || defined(_M_AMD64) +#define TOML_ARCH_AMD64 1 +#else +#define TOML_ARCH_AMD64 0 +#endif + +// 32-bit x86 +#if defined(__i386__) || defined(_M_IX86) +#define TOML_ARCH_X86 1 +#else +#define TOML_ARCH_X86 0 +#endif + +// ARM +#if defined(__aarch64__) || defined(__ARM_ARCH_ISA_A64) || defined(_M_ARM64) || defined(__ARM_64BIT_STATE) \ + || defined(_M_ARM64EC) +#define TOML_ARCH_ARM32 0 +#define TOML_ARCH_ARM64 1 +#define TOML_ARCH_ARM 1 +#elif defined(__arm__) || defined(_M_ARM) || defined(__ARM_32BIT_STATE) +#define TOML_ARCH_ARM32 1 +#define TOML_ARCH_ARM64 0 +#define TOML_ARCH_ARM 1 +#else +#define TOML_ARCH_ARM32 0 +#define TOML_ARCH_ARM64 0 +#define TOML_ARCH_ARM 0 +#endif + +// TOML_HAS_INCLUDE +#ifdef __has_include +#define TOML_HAS_INCLUDE(header) __has_include(header) +#else +#define TOML_HAS_INCLUDE(header) 0 +#endif + +#ifdef __has_builtin +#define TOML_HAS_BUILTIN(name) __has_builtin(name) +#else +#define TOML_HAS_BUILTIN(name) 0 +#endif + +// TOML_HAS_FEATURE +#ifdef __has_feature +#define TOML_HAS_FEATURE(name) __has_feature(name) +#else +#define TOML_HAS_FEATURE(name) 0 +#endif + +// TOML_HAS_ATTR +#ifdef __has_attribute +#define TOML_HAS_ATTR(attr) __has_attribute(attr) +#else +#define TOML_HAS_ATTR(attr) 0 +#endif + +// TOML_HAS_CPP_ATTR +#ifdef __has_cpp_attribute +#define TOML_HAS_CPP_ATTR(attr) __has_cpp_attribute(attr) +#else +#define TOML_HAS_CPP_ATTR(attr) 0 +#endif + +// TOML_COMPILER_HAS_EXCEPTIONS +#if defined(__EXCEPTIONS) || defined(_CPPUNWIND) || defined(__cpp_exceptions) +#define TOML_COMPILER_HAS_EXCEPTIONS 1 +#else +#define TOML_COMPILER_HAS_EXCEPTIONS 0 +#endif + +// TOML_COMPILER_HAS_RTTI +#if defined(_CPPRTTI) || defined(__GXX_RTTI) || TOML_HAS_FEATURE(cxx_rtti) +#define TOML_COMPILER_HAS_RTTI 1 +#else +#define TOML_COMPILER_HAS_RTTI 0 +#endif + +// TOML_ATTR (gnu attributes) +#if TOML_CLANG || TOML_GCC || defined(__GNUC__) +#define TOML_ATTR(...) __attribute__((__VA_ARGS__)) +#else +#define TOML_ATTR(...) +#endif + +// TOML_DECLSPEC (msvc attributes) +#ifdef _MSC_VER +#define TOML_DECLSPEC(...) __declspec(__VA_ARGS__) +#else +#define TOML_DECLSPEC(...) +#endif + +// TOML_CONCAT +#define TOML_CONCAT_1(x, y) x##y +#define TOML_CONCAT(x, y) TOML_CONCAT_1(x, y) + +// TOML_MAKE_STRING +#define TOML_MAKE_STRING_1(s) #s +#define TOML_MAKE_STRING(s) TOML_MAKE_STRING_1(s) + +// TOML_PRAGMA_XXXX (compiler-specific pragmas) +#if TOML_CLANG +#define TOML_PRAGMA_CLANG(decl) _Pragma(TOML_MAKE_STRING(clang decl)) +#else +#define TOML_PRAGMA_CLANG(decl) +#endif +#if TOML_CLANG >= 9 +#define TOML_PRAGMA_CLANG_GE_9(decl) TOML_PRAGMA_CLANG(decl) +#else +#define TOML_PRAGMA_CLANG_GE_9(decl) +#endif +#if TOML_CLANG >= 10 +#define TOML_PRAGMA_CLANG_GE_10(decl) TOML_PRAGMA_CLANG(decl) +#else +#define TOML_PRAGMA_CLANG_GE_10(decl) +#endif +#if TOML_CLANG >= 11 +#define TOML_PRAGMA_CLANG_GE_11(decl) TOML_PRAGMA_CLANG(decl) +#else +#define TOML_PRAGMA_CLANG_GE_11(decl) +#endif +#if TOML_GCC +#define TOML_PRAGMA_GCC(decl) _Pragma(TOML_MAKE_STRING(GCC decl)) +#else +#define TOML_PRAGMA_GCC(decl) +#endif +#if TOML_MSVC +#define TOML_PRAGMA_MSVC(...) __pragma(__VA_ARGS__) +#else +#define TOML_PRAGMA_MSVC(...) +#endif +#if TOML_ICC +#define TOML_PRAGMA_ICC(...) __pragma(__VA_ARGS__) +#else +#define TOML_PRAGMA_ICC(...) +#endif + +// TOML_ALWAYS_INLINE +#ifdef _MSC_VER +#define TOML_ALWAYS_INLINE __forceinline +#elif TOML_GCC || TOML_CLANG || TOML_HAS_ATTR(__always_inline__) +#define TOML_ALWAYS_INLINE \ + TOML_ATTR(__always_inline__) \ + inline +#else +#define TOML_ALWAYS_INLINE inline +#endif + +// TOML_NEVER_INLINE +#ifdef _MSC_VER +#define TOML_NEVER_INLINE TOML_DECLSPEC(noinline) +#elif TOML_GCC || TOML_CLANG || TOML_HAS_ATTR(__noinline__) +#define TOML_NEVER_INLINE TOML_ATTR(__noinline__) +#else +#define TOML_NEVER_INLINE +#endif + +// MSVC attributes +#define TOML_ABSTRACT_INTERFACE TOML_DECLSPEC(novtable) +#define TOML_EMPTY_BASES TOML_DECLSPEC(empty_bases) + +// TOML_TRIVIAL_ABI +#if TOML_CLANG || TOML_HAS_ATTR(__trivial_abi__) +#define TOML_TRIVIAL_ABI TOML_ATTR(__trivial_abi__) +#else +#define TOML_TRIVIAL_ABI +#endif + +// TOML_NODISCARD +#if TOML_CPP >= 17 && TOML_HAS_CPP_ATTR(nodiscard) >= 201603 +#define TOML_NODISCARD [[nodiscard]] +#elif TOML_CLANG || TOML_GCC || TOML_HAS_ATTR(__warn_unused_result__) +#define TOML_NODISCARD TOML_ATTR(__warn_unused_result__) +#else +#define TOML_NODISCARD +#endif + +// TOML_NODISCARD_CTOR +#if TOML_CPP >= 17 && TOML_HAS_CPP_ATTR(nodiscard) >= 201907 +#define TOML_NODISCARD_CTOR [[nodiscard]] +#else +#define TOML_NODISCARD_CTOR +#endif + +// pure + const +// clang-format off +#ifdef NDEBUG + #define TOML_PURE TOML_DECLSPEC(noalias) TOML_ATTR(__pure__) + #define TOML_CONST TOML_DECLSPEC(noalias) TOML_ATTR(__const__) + #define TOML_PURE_GETTER TOML_NODISCARD TOML_PURE + #define TOML_CONST_GETTER TOML_NODISCARD TOML_CONST + #define TOML_PURE_INLINE_GETTER TOML_NODISCARD TOML_ALWAYS_INLINE TOML_PURE + #define TOML_CONST_INLINE_GETTER TOML_NODISCARD TOML_ALWAYS_INLINE TOML_CONST +#else + #define TOML_PURE + #define TOML_CONST + #define TOML_PURE_GETTER TOML_NODISCARD + #define TOML_CONST_GETTER TOML_NODISCARD + #define TOML_PURE_INLINE_GETTER TOML_NODISCARD TOML_ALWAYS_INLINE + #define TOML_CONST_INLINE_GETTER TOML_NODISCARD TOML_ALWAYS_INLINE +#endif +// clang-format on + +// TOML_ASSUME +#ifdef _MSC_VER +#define TOML_ASSUME(...) __assume(__VA_ARGS__) +#elif TOML_ICC || TOML_CLANG || TOML_HAS_BUILTIN(__builtin_assume) +#define TOML_ASSUME(...) __builtin_assume(__VA_ARGS__) +#else +#define TOML_ASSUME(...) static_assert(true) +#endif + +// TOML_UNREACHABLE +#ifdef _MSC_VER +#define TOML_UNREACHABLE __assume(0) +#elif TOML_ICC || TOML_CLANG || TOML_GCC || TOML_HAS_BUILTIN(__builtin_unreachable) +#define TOML_UNREACHABLE __builtin_unreachable() +#else +#define TOML_UNREACHABLE static_assert(true) +#endif + +// TOML_LIKELY +#if TOML_CPP >= 20 && TOML_HAS_CPP_ATTR(likely) >= 201803 +#define TOML_LIKELY(...) (__VA_ARGS__) [[likely]] +#define TOML_LIKELY_CASE [[likely]] +#elif TOML_GCC || TOML_CLANG || TOML_HAS_BUILTIN(__builtin_expect) +#define TOML_LIKELY(...) (__builtin_expect(!!(__VA_ARGS__), 1)) +#else +#define TOML_LIKELY(...) (__VA_ARGS__) +#endif +#ifndef TOML_LIKELY_CASE +#define TOML_LIKELY_CASE +#endif + +// TOML_UNLIKELY +#if TOML_CPP >= 20 && TOML_HAS_CPP_ATTR(unlikely) >= 201803 +#define TOML_UNLIKELY(...) (__VA_ARGS__) [[unlikely]] +#define TOML_UNLIKELY_CASE [[unlikely]] +#elif TOML_GCC || TOML_CLANG || TOML_HAS_BUILTIN(__builtin_expect) +#define TOML_UNLIKELY(...) (__builtin_expect(!!(__VA_ARGS__), 0)) +#else +#define TOML_UNLIKELY(...) (__VA_ARGS__) +#endif +#ifndef TOML_UNLIKELY_CASE +#define TOML_UNLIKELY_CASE +#endif + +// TOML_FLAGS_ENUM +#if TOML_CLANG || TOML_HAS_ATTR(flag_enum) +#define TOML_FLAGS_ENUM __attribute__((flag_enum)) +#else +#define TOML_FLAGS_ENUM +#endif + +// TOML_OPEN_ENUM + TOML_CLOSED_ENUM +#if TOML_CLANG || TOML_HAS_ATTR(enum_extensibility) +#define TOML_OPEN_ENUM __attribute__((enum_extensibility(open))) +#define TOML_CLOSED_ENUM __attribute__((enum_extensibility(closed))) +#else +#define TOML_OPEN_ENUM +#define TOML_CLOSED_ENUM +#endif + +// TOML_OPEN_FLAGS_ENUM + TOML_CLOSED_FLAGS_ENUM +#define TOML_OPEN_FLAGS_ENUM TOML_OPEN_ENUM TOML_FLAGS_ENUM +#define TOML_CLOSED_FLAGS_ENUM TOML_CLOSED_ENUM TOML_FLAGS_ENUM + +// TOML_MAKE_FLAGS +#define TOML_MAKE_FLAGS_2(T, op, linkage) \ + TOML_CONST_INLINE_GETTER \ + linkage constexpr T operator op(T lhs, T rhs) noexcept \ + { \ + using under = std::underlying_type_t; \ + return static_cast(static_cast(lhs) op static_cast(rhs)); \ + } \ + \ + linkage constexpr T& operator TOML_CONCAT(op, =)(T & lhs, T rhs) noexcept \ + { \ + return lhs = (lhs op rhs); \ + } \ + \ + static_assert(true) +#define TOML_MAKE_FLAGS_1(T, linkage) \ + static_assert(std::is_enum_v); \ + \ + TOML_MAKE_FLAGS_2(T, &, linkage); \ + TOML_MAKE_FLAGS_2(T, |, linkage); \ + TOML_MAKE_FLAGS_2(T, ^, linkage); \ + \ + TOML_CONST_INLINE_GETTER \ + linkage constexpr T operator~(T val) noexcept \ + { \ + using under = std::underlying_type_t; \ + return static_cast(~static_cast(val)); \ + } \ + \ + TOML_CONST_INLINE_GETTER \ + linkage constexpr bool operator!(T val) noexcept \ + { \ + using under = std::underlying_type_t; \ + return !static_cast(val); \ + } \ + \ + static_assert(true) +#define TOML_MAKE_FLAGS(T) TOML_MAKE_FLAGS_1(T, ) + +#define TOML_UNUSED(...) static_cast(__VA_ARGS__) + +#define TOML_DELETE_DEFAULTS(T) \ + T(const T&) = delete; \ + T(T&&) = delete; \ + T& operator=(const T&) = delete; \ + T& operator=(T&&) = delete + +#define TOML_ASYMMETRICAL_EQUALITY_OPS(LHS, RHS, ...) \ + __VA_ARGS__ TOML_NODISCARD \ + friend bool operator==(RHS rhs, LHS lhs) noexcept \ + { \ + return lhs == rhs; \ + } \ + __VA_ARGS__ TOML_NODISCARD \ + friend bool operator!=(LHS lhs, RHS rhs) noexcept \ + { \ + return !(lhs == rhs); \ + } \ + __VA_ARGS__ TOML_NODISCARD \ + friend bool operator!=(RHS rhs, LHS lhs) noexcept \ + { \ + return !(lhs == rhs); \ + } \ + static_assert(true) + +#define TOML_EVAL_BOOL_1(T, F) T +#define TOML_EVAL_BOOL_0(T, F) F + +#if !defined(__POXY__) && !defined(POXY_IMPLEMENTATION_DETAIL) +#define POXY_IMPLEMENTATION_DETAIL(...) __VA_ARGS__ +#endif + +// COMPILER-SPECIFIC WARNING MANAGEMENT + +#if TOML_CLANG + +#define TOML_PUSH_WARNINGS \ + TOML_PRAGMA_CLANG(diagnostic push) \ + static_assert(true) + +#define TOML_DISABLE_SWITCH_WARNINGS \ + TOML_PRAGMA_CLANG(diagnostic ignored "-Wswitch") \ + static_assert(true) + +#define TOML_DISABLE_ARITHMETIC_WARNINGS \ + TOML_PRAGMA_CLANG(diagnostic ignored "-Wfloat-equal") \ + TOML_PRAGMA_CLANG(diagnostic ignored "-Wdouble-promotion") \ + TOML_PRAGMA_CLANG(diagnostic ignored "-Wchar-subscripts") \ + TOML_PRAGMA_CLANG(diagnostic ignored "-Wshift-sign-overflow") \ + static_assert(true) + +#define TOML_DISABLE_SPAM_WARNINGS \ + TOML_PRAGMA_CLANG_GE_9(diagnostic ignored "-Wctad-maybe-unsupported") \ + TOML_PRAGMA_CLANG_GE_10(diagnostic ignored "-Wzero-as-null-pointer-constant") \ + TOML_PRAGMA_CLANG_GE_11(diagnostic ignored "-Wsuggest-destructor-override") \ + TOML_PRAGMA_CLANG(diagnostic ignored "-Wweak-vtables") \ + TOML_PRAGMA_CLANG(diagnostic ignored "-Wweak-template-vtables") \ + TOML_PRAGMA_CLANG(diagnostic ignored "-Wdouble-promotion") \ + TOML_PRAGMA_CLANG(diagnostic ignored "-Wchar-subscripts") \ + TOML_PRAGMA_CLANG(diagnostic ignored "-Wmissing-field-initializers") \ + TOML_PRAGMA_CLANG(diagnostic ignored "-Wpadded") \ + static_assert(true) + +#define TOML_POP_WARNINGS \ + TOML_PRAGMA_CLANG(diagnostic pop) \ + static_assert(true) + +#define TOML_DISABLE_WARNINGS \ + TOML_PRAGMA_CLANG(diagnostic push) \ + TOML_PRAGMA_CLANG(diagnostic ignored "-Weverything") \ + static_assert(true, "") + +#define TOML_ENABLE_WARNINGS \ + TOML_PRAGMA_CLANG(diagnostic pop) \ + static_assert(true) + +#define TOML_SIMPLE_STATIC_ASSERT_MESSAGES 1 + +#elif TOML_MSVC + +#define TOML_PUSH_WARNINGS \ + __pragma(warning(push)) \ + static_assert(true) + +#if TOML_HAS_INCLUDE() +#pragma warning(push, 0) +#include +#pragma warning(pop) +#define TOML_DISABLE_CODE_ANALYSIS_WARNINGS \ + __pragma(warning(disable : ALL_CODE_ANALYSIS_WARNINGS)) \ + static_assert(true) +#else +#define TOML_DISABLE_CODE_ANALYSIS_WARNINGS static_assert(true) +#endif + +#define TOML_DISABLE_SWITCH_WARNINGS \ + __pragma(warning(disable : 4061)) \ + __pragma(warning(disable : 4062)) \ + __pragma(warning(disable : 4063)) \ + __pragma(warning(disable : 5262)) /* switch-case implicit fallthrough (false-positive) */ \ + __pragma(warning(disable : 26819)) /* cg: unannotated fallthrough */ \ + static_assert(true) + +#define TOML_DISABLE_SPAM_WARNINGS \ + __pragma(warning(disable : 4127)) /* conditional expr is constant */ \ + __pragma(warning(disable : 4324)) /* structure was padded due to alignment specifier */ \ + __pragma(warning(disable : 4348)) \ + __pragma(warning(disable : 4464)) /* relative include path contains '..' */ \ + __pragma(warning(disable : 4505)) /* unreferenced local function removed */ \ + __pragma(warning(disable : 4514)) /* unreferenced inline function has been removed */ \ + __pragma(warning(disable : 4582)) /* constructor is not implicitly called */ \ + __pragma(warning(disable : 4619)) /* there is no warning number 'XXXX' */ \ + __pragma(warning(disable : 4623)) /* default constructor was implicitly defined as deleted */ \ + __pragma(warning(disable : 4625)) /* copy constructor was implicitly defined as deleted */ \ + __pragma(warning(disable : 4626)) /* assignment operator was implicitly defined as deleted */ \ + __pragma(warning(disable : 4710)) /* function not inlined */ \ + __pragma(warning(disable : 4711)) /* function selected for automatic expansion */ \ + __pragma(warning(disable : 4820)) /* N bytes padding added */ \ + __pragma(warning(disable : 4946)) /* reinterpret_cast used between related classes */ \ + __pragma(warning(disable : 5026)) /* move constructor was implicitly defined as deleted */ \ + __pragma(warning(disable : 5027)) /* move assignment operator was implicitly defined as deleted */ \ + __pragma(warning(disable : 5039)) /* potentially throwing function passed to 'extern "C"' function */ \ + __pragma(warning(disable : 5045)) /* Compiler will insert Spectre mitigation */ \ + __pragma(warning(disable : 5264)) /* const variable is not used (false-positive) */ \ + __pragma(warning(disable : 26451)) \ + __pragma(warning(disable : 26490)) \ + __pragma(warning(disable : 26495)) \ + __pragma(warning(disable : 26812)) \ + __pragma(warning(disable : 26819)) \ + static_assert(true) + +#define TOML_DISABLE_ARITHMETIC_WARNINGS \ + __pragma(warning(disable : 4365)) /* argument signed/unsigned mismatch */ \ + __pragma(warning(disable : 4738)) /* storing 32-bit float result in memory */ \ + __pragma(warning(disable : 5219)) /* implicit conversion from integral to float */ \ + static_assert(true) + +#define TOML_POP_WARNINGS \ + __pragma(warning(pop)) \ + static_assert(true) + +#define TOML_DISABLE_WARNINGS \ + __pragma(warning(push, 0)) \ + __pragma(warning(disable : 4348)) \ + __pragma(warning(disable : 4668)) \ + __pragma(warning(disable : 5105)) \ + __pragma(warning(disable : 5264)) \ + TOML_DISABLE_CODE_ANALYSIS_WARNINGS; \ + TOML_DISABLE_SWITCH_WARNINGS; \ + TOML_DISABLE_SPAM_WARNINGS; \ + TOML_DISABLE_ARITHMETIC_WARNINGS; \ + static_assert(true) + +#define TOML_ENABLE_WARNINGS TOML_POP_WARNINGS + +#elif TOML_ICC + +#define TOML_PUSH_WARNINGS \ + __pragma(warning(push)) \ + static_assert(true) + +#define TOML_DISABLE_SPAM_WARNINGS \ + __pragma(warning(disable : 82)) /* storage class is not first */ \ + __pragma(warning(disable : 111)) /* statement unreachable (false-positive) */ \ + __pragma(warning(disable : 869)) /* unreferenced parameter */ \ + __pragma(warning(disable : 1011)) /* missing return (false-positive) */ \ + __pragma(warning(disable : 2261)) /* assume expr side-effects discarded */ \ + static_assert(true) + +#define TOML_POP_WARNINGS \ + __pragma(warning(pop)) \ + static_assert(true) + +#define TOML_DISABLE_WARNINGS \ + __pragma(warning(push, 0)) \ + TOML_DISABLE_SPAM_WARNINGS + +#define TOML_ENABLE_WARNINGS \ + __pragma(warning(pop)) \ + static_assert(true) + +#elif TOML_GCC + +#define TOML_PUSH_WARNINGS \ + TOML_PRAGMA_GCC(diagnostic push) \ + static_assert(true) + +#define TOML_DISABLE_SWITCH_WARNINGS \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wswitch") \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wswitch-enum") \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wswitch-default") \ + static_assert(true) + +#define TOML_DISABLE_ARITHMETIC_WARNINGS \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wfloat-equal") \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wsign-conversion") \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wchar-subscripts") \ + static_assert(true) + +#define TOML_DISABLE_SUGGEST_ATTR_WARNINGS \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wsuggest-attribute=const") \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wsuggest-attribute=pure") \ + static_assert(true) + +#define TOML_DISABLE_SPAM_WARNINGS \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wpadded") \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wcast-align") \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wcomment") \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wtype-limits") \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wuseless-cast") \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wchar-subscripts") \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wsubobject-linkage") \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wmissing-field-initializers") \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wmaybe-uninitialized") \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wnoexcept") \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wnull-dereference") \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wduplicated-branches") \ + static_assert(true) + +#define TOML_POP_WARNINGS \ + TOML_PRAGMA_GCC(diagnostic pop) \ + static_assert(true) + +#define TOML_DISABLE_WARNINGS \ + TOML_PRAGMA_GCC(diagnostic push) \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wall") \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wextra") \ + TOML_PRAGMA_GCC(diagnostic ignored "-Wpedantic") \ + TOML_DISABLE_SWITCH_WARNINGS; \ + TOML_DISABLE_ARITHMETIC_WARNINGS; \ + TOML_DISABLE_SUGGEST_ATTR_WARNINGS; \ + TOML_DISABLE_SPAM_WARNINGS; \ + static_assert(true) + +#define TOML_ENABLE_WARNINGS \ + TOML_PRAGMA_GCC(diagnostic pop) \ + static_assert(true) + +#endif + +#ifndef TOML_PUSH_WARNINGS +#define TOML_PUSH_WARNINGS static_assert(true) +#endif +#ifndef TOML_DISABLE_CODE_ANALYSIS_WARNINGS +#define TOML_DISABLE_CODE_ANALYSIS_WARNINGS static_assert(true) +#endif +#ifndef TOML_DISABLE_SWITCH_WARNINGS +#define TOML_DISABLE_SWITCH_WARNINGS static_assert(true) +#endif +#ifndef TOML_DISABLE_SUGGEST_ATTR_WARNINGS +#define TOML_DISABLE_SUGGEST_ATTR_WARNINGS static_assert(true) +#endif +#ifndef TOML_DISABLE_SPAM_WARNINGS +#define TOML_DISABLE_SPAM_WARNINGS static_assert(true) +#endif +#ifndef TOML_DISABLE_ARITHMETIC_WARNINGS +#define TOML_DISABLE_ARITHMETIC_WARNINGS static_assert(true) +#endif +#ifndef TOML_POP_WARNINGS +#define TOML_POP_WARNINGS static_assert(true) +#endif +#ifndef TOML_DISABLE_WARNINGS +#define TOML_DISABLE_WARNINGS static_assert(true) +#endif +#ifndef TOML_ENABLE_WARNINGS +#define TOML_ENABLE_WARNINGS static_assert(true) +#endif +#ifndef TOML_SIMPLE_STATIC_ASSERT_MESSAGES +#define TOML_SIMPLE_STATIC_ASSERT_MESSAGES 0 +#endif + +#ifdef TOML_CONFIG_HEADER +#include TOML_CONFIG_HEADER +#endif + +// is the library being built as a shared lib/dll using meson and friends? +#ifndef TOML_SHARED_LIB +#define TOML_SHARED_LIB 0 +#endif + +// header-only mode +#if !defined(TOML_HEADER_ONLY) && defined(TOML_ALL_INLINE) // was TOML_ALL_INLINE pre-2.0 +#define TOML_HEADER_ONLY TOML_ALL_INLINE +#endif +#if !defined(TOML_HEADER_ONLY) || (defined(TOML_HEADER_ONLY) && TOML_HEADER_ONLY) || TOML_INTELLISENSE +#undef TOML_HEADER_ONLY +#define TOML_HEADER_ONLY 1 +#endif +#if TOML_DOXYGEN || TOML_SHARED_LIB +#undef TOML_HEADER_ONLY +#define TOML_HEADER_ONLY 0 +#endif + +// internal implementation switch +#if defined(TOML_IMPLEMENTATION) || TOML_HEADER_ONLY +#undef TOML_IMPLEMENTATION +#define TOML_IMPLEMENTATION 1 +#else +#define TOML_IMPLEMENTATION 0 +#endif + +// dll/shared lib function exports (legacy - TOML_API was the old name for this setting) +#if !defined(TOML_EXPORTED_MEMBER_FUNCTION) && !defined(TOML_EXPORTED_STATIC_FUNCTION) \ + && !defined(TOML_EXPORTED_FREE_FUNCTION) && !defined(TOML_EXPORTED_CLASS) && defined(TOML_API) +#define TOML_EXPORTED_MEMBER_FUNCTION TOML_API +#define TOML_EXPORTED_STATIC_FUNCTION TOML_API +#define TOML_EXPORTED_FREE_FUNCTION TOML_API +#endif + +// dll/shared lib exports +#if TOML_SHARED_LIB +#undef TOML_API +#undef TOML_EXPORTED_CLASS +#undef TOML_EXPORTED_MEMBER_FUNCTION +#undef TOML_EXPORTED_STATIC_FUNCTION +#undef TOML_EXPORTED_FREE_FUNCTION +#if TOML_WINDOWS +#if TOML_IMPLEMENTATION +#define TOML_EXPORTED_CLASS __declspec(dllexport) +#define TOML_EXPORTED_FREE_FUNCTION __declspec(dllexport) +#else +#define TOML_EXPORTED_CLASS __declspec(dllimport) +#define TOML_EXPORTED_FREE_FUNCTION __declspec(dllimport) +#endif +#ifndef TOML_CALLCONV +#define TOML_CALLCONV __cdecl +#endif +#elif defined(__GNUC__) && __GNUC__ >= 4 +#define TOML_EXPORTED_CLASS __attribute__((visibility("default"))) +#define TOML_EXPORTED_MEMBER_FUNCTION __attribute__((visibility("default"))) +#define TOML_EXPORTED_STATIC_FUNCTION __attribute__((visibility("default"))) +#define TOML_EXPORTED_FREE_FUNCTION __attribute__((visibility("default"))) +#endif +#endif +#ifndef TOML_EXPORTED_CLASS +#define TOML_EXPORTED_CLASS +#endif +#ifndef TOML_EXPORTED_MEMBER_FUNCTION +#define TOML_EXPORTED_MEMBER_FUNCTION +#endif +#ifndef TOML_EXPORTED_STATIC_FUNCTION +#define TOML_EXPORTED_STATIC_FUNCTION +#endif +#ifndef TOML_EXPORTED_FREE_FUNCTION +#define TOML_EXPORTED_FREE_FUNCTION +#endif + +// experimental language features +#if !defined(TOML_ENABLE_UNRELEASED_FEATURES) && defined(TOML_UNRELEASED_FEATURES) // was TOML_UNRELEASED_FEATURES + // pre-3.0 +#define TOML_ENABLE_UNRELEASED_FEATURES TOML_UNRELEASED_FEATURES +#endif +#if (defined(TOML_ENABLE_UNRELEASED_FEATURES) && TOML_ENABLE_UNRELEASED_FEATURES) || TOML_INTELLISENSE +#undef TOML_ENABLE_UNRELEASED_FEATURES +#define TOML_ENABLE_UNRELEASED_FEATURES 1 +#endif +#ifndef TOML_ENABLE_UNRELEASED_FEATURES +#define TOML_ENABLE_UNRELEASED_FEATURES 0 +#endif + +// parser +#if !defined(TOML_ENABLE_PARSER) && defined(TOML_PARSER) // was TOML_PARSER pre-3.0 +#define TOML_ENABLE_PARSER TOML_PARSER +#endif +#if !defined(TOML_ENABLE_PARSER) || (defined(TOML_ENABLE_PARSER) && TOML_ENABLE_PARSER) || TOML_INTELLISENSE +#undef TOML_ENABLE_PARSER +#define TOML_ENABLE_PARSER 1 +#endif + +// formatters +#if !defined(TOML_ENABLE_FORMATTERS) || (defined(TOML_ENABLE_FORMATTERS) && TOML_ENABLE_FORMATTERS) || TOML_INTELLISENSE +#undef TOML_ENABLE_FORMATTERS +#define TOML_ENABLE_FORMATTERS 1 +#endif + +// SIMD +#if !defined(TOML_ENABLE_SIMD) || (defined(TOML_ENABLE_SIMD) && TOML_ENABLE_SIMD) || TOML_INTELLISENSE +#undef TOML_ENABLE_SIMD +#define TOML_ENABLE_SIMD 1 +#endif + +// windows compat +#if !defined(TOML_ENABLE_WINDOWS_COMPAT) && defined(TOML_WINDOWS_COMPAT) // was TOML_WINDOWS_COMPAT pre-3.0 +#define TOML_ENABLE_WINDOWS_COMPAT TOML_WINDOWS_COMPAT +#endif +#if !defined(TOML_ENABLE_WINDOWS_COMPAT) || (defined(TOML_ENABLE_WINDOWS_COMPAT) && TOML_ENABLE_WINDOWS_COMPAT) \ + || TOML_INTELLISENSE +#undef TOML_ENABLE_WINDOWS_COMPAT +#define TOML_ENABLE_WINDOWS_COMPAT 1 +#endif + +#if !TOML_WINDOWS +#undef TOML_ENABLE_WINDOWS_COMPAT +#define TOML_ENABLE_WINDOWS_COMPAT 0 +#endif + +#ifndef TOML_INCLUDE_WINDOWS_H +#define TOML_INCLUDE_WINDOWS_H 0 +#endif + +// custom optional +#ifdef TOML_OPTIONAL_TYPE +#define TOML_HAS_CUSTOM_OPTIONAL_TYPE 1 +#else +#define TOML_HAS_CUSTOM_OPTIONAL_TYPE 0 +#endif + +// exceptions (library use) +#if TOML_COMPILER_HAS_EXCEPTIONS +#if !defined(TOML_EXCEPTIONS) || (defined(TOML_EXCEPTIONS) && TOML_EXCEPTIONS) +#undef TOML_EXCEPTIONS +#define TOML_EXCEPTIONS 1 +#endif +#else +#if defined(TOML_EXCEPTIONS) && TOML_EXCEPTIONS +#error TOML_EXCEPTIONS was explicitly enabled but exceptions are disabled/unsupported by the compiler. +#endif +#undef TOML_EXCEPTIONS +#define TOML_EXCEPTIONS 0 +#endif + +// calling convention for static/free/friend functions +#ifndef TOML_CALLCONV +#define TOML_CALLCONV +#endif + +#ifndef TOML_UNDEF_MACROS +#define TOML_UNDEF_MACROS 1 +#endif + +#ifndef TOML_MAX_NESTED_VALUES +#define TOML_MAX_NESTED_VALUES 256 +// this refers to the depth of nested values, e.g. inline tables and arrays. +// 256 is crazy high! if you're hitting this limit with real input, TOML is probably the wrong tool for the job... +#endif + +#ifdef TOML_CHAR_8_STRINGS +#if TOML_CHAR_8_STRINGS +#error TOML_CHAR_8_STRINGS was removed in toml++ 2.0.0; all value setters and getters now work with char8_t strings implicitly. +#endif +#endif + +#ifdef TOML_LARGE_FILES +#if !TOML_LARGE_FILES +#error Support for !TOML_LARGE_FILES (i.e. 'small files') was removed in toml++ 3.0.0. +#endif +#endif + +#ifndef TOML_LIFETIME_HOOKS +#define TOML_LIFETIME_HOOKS 0 +#endif + +#ifdef NDEBUG +#undef TOML_ASSERT +#define TOML_ASSERT(expr) static_assert(true) +#endif +#ifndef TOML_ASSERT +#ifndef assert +TOML_DISABLE_WARNINGS; +#include +TOML_ENABLE_WARNINGS; +#endif +#define TOML_ASSERT(expr) assert(expr) +#endif +#ifdef NDEBUG +#define TOML_ASSERT_ASSUME(expr) TOML_ASSUME(expr) +#else +#define TOML_ASSERT_ASSUME(expr) TOML_ASSERT(expr) +#endif + +#if !defined(TOML_FLOAT_CHARCONV) && (TOML_GCC || TOML_CLANG || (TOML_ICC && !TOML_ICC_CL)) +// not supported by any version of GCC or Clang as of 26/11/2020 +// not supported by any version of ICC on Linux as of 11/01/2021 +#define TOML_FLOAT_CHARCONV 0 +#endif +#if !defined(TOML_INT_CHARCONV) && (defined(__EMSCRIPTEN__) || defined(__APPLE__)) +// causes link errors on emscripten +// causes Mac OS SDK version errors on some versions of Apple Clang +#define TOML_INT_CHARCONV 0 +#endif +#ifndef TOML_INT_CHARCONV +#define TOML_INT_CHARCONV 1 +#endif +#ifndef TOML_FLOAT_CHARCONV +#define TOML_FLOAT_CHARCONV 1 +#endif +#if (TOML_INT_CHARCONV || TOML_FLOAT_CHARCONV) && !TOML_HAS_INCLUDE() +#undef TOML_INT_CHARCONV +#undef TOML_FLOAT_CHARCONV +#define TOML_INT_CHARCONV 0 +#define TOML_FLOAT_CHARCONV 0 +#endif + +#if defined(__cpp_concepts) && __cpp_concepts >= 201907 +#define TOML_REQUIRES(...) requires(__VA_ARGS__) +#else +#define TOML_REQUIRES(...) +#endif +#define TOML_ENABLE_IF(...) , typename std::enable_if<(__VA_ARGS__), int>::type = 0 +#define TOML_CONSTRAINED_TEMPLATE(condition, ...) \ + template <__VA_ARGS__ TOML_ENABLE_IF(condition)> \ + TOML_REQUIRES(condition) +#define TOML_HIDDEN_CONSTRAINT(condition, ...) TOML_CONSTRAINED_TEMPLATE(condition, __VA_ARGS__) + +#ifndef TOML_ENABLE_FLOAT16 + +#ifdef __FLT16_MANT_DIG__ +#define TOML_FLOAT16_MANT_DIG __FLT16_MANT_DIG__ +#define TOML_FLOAT16_DIG __FLT16_DIG__ +#define TOML_FLOAT16_MIN_EXP __FLT16_MIN_EXP__ +#define TOML_FLOAT16_MIN_10_EXP __FLT16_MIN_10_EXP__ +#define TOML_FLOAT16_MAX_EXP __FLT16_MAX_EXP__ +#define TOML_FLOAT16_MAX_10_EXP __FLT16_MAX_10_EXP__ +#else +#define TOML_FLOAT16_MANT_DIG 0 +#define TOML_FLOAT16_DIG 0 +#define TOML_FLOAT16_MIN_EXP 0 +#define TOML_FLOAT16_MIN_10_EXP 0 +#define TOML_FLOAT16_MAX_EXP 0 +#define TOML_FLOAT16_MAX_10_EXP 0 +#endif + +#if (TOML_FLOAT16_MANT_DIG && TOML_FLOAT16_DIG && TOML_FLOAT16_MIN_EXP && TOML_FLOAT16_MIN_10_EXP \ + && TOML_FLOAT16_MAX_EXP && TOML_FLOAT16_MAX_10_EXP) +#define TOML_FLOAT16_LIMITS_SET 1 +#else +#define TOML_FLOAT16_LIMITS_SET 0 +#endif + +#if TOML_FLOAT16_LIMITS_SET + +#if TOML_CLANG // >= 15 +#if (TOML_ARCH_ARM || TOML_ARCH_AMD64 || TOML_ARCH_X86) +#define TOML_ENABLE_FLOAT16 1 +#endif + +#elif TOML_GCC +#if (TOML_ARCH_ARM || TOML_ARCH_AMD64 /* || TOML_ARCH_X86*/) +#define TOML_ENABLE_FLOAT16 1 +#endif + +#endif // clang/gcc + +#endif // TOML_FLOAT16_LIMITS_SET + +#endif // !defined(TOML_ENABLE_FLOAT16) + +#ifndef TOML_ENABLE_FLOAT16 +#define TOML_ENABLE_FLOAT16 0 +#endif + +#if defined(__SIZEOF_FLOAT128__) && defined(__FLT128_MANT_DIG__) && defined(__LDBL_MANT_DIG__) \ + && __FLT128_MANT_DIG__ > __LDBL_MANT_DIG__ +#define TOML_FLOAT128 __float128 +#endif + +#ifdef __SIZEOF_INT128__ +#define TOML_INT128 __int128_t +#define TOML_UINT128 __uint128_t +#endif + +// clang-format off + +//******** impl/version.h ******************************************************************************************** + +#define TOML_LIB_MAJOR 3 +#define TOML_LIB_MINOR 2 +#define TOML_LIB_PATCH 0 + +#define TOML_LANG_MAJOR 1 +#define TOML_LANG_MINOR 0 +#define TOML_LANG_PATCH 0 + +//******** impl/preprocessor.h *************************************************************************************** + +#define TOML_LIB_SINGLE_HEADER 1 + +#define TOML_MAKE_VERSION(major, minor, patch) \ + ((major) * 10000 + (minor) * 100 + (patch)) + +#if TOML_ENABLE_UNRELEASED_FEATURES + #define TOML_LANG_EFFECTIVE_VERSION \ + TOML_MAKE_VERSION(TOML_LANG_MAJOR, TOML_LANG_MINOR, TOML_LANG_PATCH+1) +#else + #define TOML_LANG_EFFECTIVE_VERSION \ + TOML_MAKE_VERSION(TOML_LANG_MAJOR, TOML_LANG_MINOR, TOML_LANG_PATCH) +#endif + +#define TOML_LANG_HIGHER_THAN(major, minor, patch) \ + (TOML_LANG_EFFECTIVE_VERSION > TOML_MAKE_VERSION(major, minor, patch)) + +#define TOML_LANG_AT_LEAST(major, minor, patch) \ + (TOML_LANG_EFFECTIVE_VERSION >= TOML_MAKE_VERSION(major, minor, patch)) + +#define TOML_LANG_UNRELEASED \ + TOML_LANG_HIGHER_THAN(TOML_LANG_MAJOR, TOML_LANG_MINOR, TOML_LANG_PATCH) + +#ifndef TOML_ABI_NAMESPACES + #if TOML_DOXYGEN + #define TOML_ABI_NAMESPACES 0 + #else + #define TOML_ABI_NAMESPACES 1 + #endif +#endif +#if TOML_ABI_NAMESPACES + #define TOML_NAMESPACE_START namespace toml { inline namespace TOML_CONCAT(v, TOML_LIB_MAJOR) + #define TOML_NAMESPACE_END } static_assert(true) + #define TOML_NAMESPACE ::toml::TOML_CONCAT(v, TOML_LIB_MAJOR) + #define TOML_ABI_NAMESPACE_START(name) inline namespace name { static_assert(true) + #define TOML_ABI_NAMESPACE_BOOL(cond, T, F) TOML_ABI_NAMESPACE_START(TOML_CONCAT(TOML_EVAL_BOOL_, cond)(T, F)) + #define TOML_ABI_NAMESPACE_END } static_assert(true) +#else + #define TOML_NAMESPACE_START namespace toml + #define TOML_NAMESPACE_END static_assert(true) + #define TOML_NAMESPACE toml + #define TOML_ABI_NAMESPACE_START(...) static_assert(true) + #define TOML_ABI_NAMESPACE_BOOL(...) static_assert(true) + #define TOML_ABI_NAMESPACE_END static_assert(true) +#endif +#define TOML_IMPL_NAMESPACE_START TOML_NAMESPACE_START { namespace impl +#define TOML_IMPL_NAMESPACE_END } TOML_NAMESPACE_END +#if TOML_HEADER_ONLY + #define TOML_ANON_NAMESPACE_START static_assert(TOML_IMPLEMENTATION); TOML_IMPL_NAMESPACE_START + #define TOML_ANON_NAMESPACE_END TOML_IMPL_NAMESPACE_END + #define TOML_ANON_NAMESPACE TOML_NAMESPACE::impl + #define TOML_EXTERNAL_LINKAGE inline + #define TOML_INTERNAL_LINKAGE inline +#else + #define TOML_ANON_NAMESPACE_START static_assert(TOML_IMPLEMENTATION); \ + using namespace toml; \ + namespace + #define TOML_ANON_NAMESPACE_END static_assert(true) + #define TOML_ANON_NAMESPACE + #define TOML_EXTERNAL_LINKAGE + #define TOML_INTERNAL_LINKAGE static +#endif + +// clang-format on + +// clang-format off + +#if TOML_SIMPLE_STATIC_ASSERT_MESSAGES + + #define TOML_SA_NEWLINE " " + #define TOML_SA_LIST_SEP ", " + #define TOML_SA_LIST_BEG " (" + #define TOML_SA_LIST_END ")" + #define TOML_SA_LIST_NEW " " + #define TOML_SA_LIST_NXT ", " + +#else + + #define TOML_SA_NEWLINE "\n| " + #define TOML_SA_LIST_SEP TOML_SA_NEWLINE " - " + #define TOML_SA_LIST_BEG TOML_SA_LIST_SEP + #define TOML_SA_LIST_END + #define TOML_SA_LIST_NEW TOML_SA_NEWLINE TOML_SA_NEWLINE + #define TOML_SA_LIST_NXT TOML_SA_LIST_NEW + +#endif + +#define TOML_SA_NATIVE_VALUE_TYPE_LIST \ + TOML_SA_LIST_BEG "std::string" \ + TOML_SA_LIST_SEP "int64_t" \ + TOML_SA_LIST_SEP "double" \ + TOML_SA_LIST_SEP "bool" \ + TOML_SA_LIST_SEP "toml::date" \ + TOML_SA_LIST_SEP "toml::time" \ + TOML_SA_LIST_SEP "toml::date_time" \ + TOML_SA_LIST_END + +#define TOML_SA_NODE_TYPE_LIST \ + TOML_SA_LIST_BEG "toml::table" \ + TOML_SA_LIST_SEP "toml::array" \ + TOML_SA_LIST_SEP "toml::value" \ + TOML_SA_LIST_SEP "toml::value" \ + TOML_SA_LIST_SEP "toml::value" \ + TOML_SA_LIST_SEP "toml::value" \ + TOML_SA_LIST_SEP "toml::value" \ + TOML_SA_LIST_SEP "toml::value" \ + TOML_SA_LIST_SEP "toml::value" \ + TOML_SA_LIST_END + +#define TOML_SA_UNWRAPPED_NODE_TYPE_LIST \ + TOML_SA_LIST_NEW "A native TOML value type" \ + TOML_SA_NATIVE_VALUE_TYPE_LIST \ + \ + TOML_SA_LIST_NXT "A TOML node type" \ + TOML_SA_NODE_TYPE_LIST + +// clang-format on + +TOML_PUSH_WARNINGS; +TOML_DISABLE_SPAM_WARNINGS; +TOML_DISABLE_SWITCH_WARNINGS; +TOML_DISABLE_SUGGEST_ATTR_WARNINGS; + +// misc warning false-positives +#if TOML_MSVC +#pragma warning(disable : 5031) // #pragma warning(pop): likely mismatch +#if TOML_SHARED_LIB +#pragma warning(disable : 4251) // dll exports for std lib types +#endif +#elif TOML_CLANG +#pragma clang diagnostic ignored "-Wheader-hygiene" +#if TOML_CLANG >= 12 +#pragma clang diagnostic ignored "-Wc++20-extensions" +#endif +#if (TOML_CLANG == 13) && !defined(__APPLE__) +#pragma clang diagnostic ignored "-Wreserved-identifier" +#endif +#endif + +//******** impl/std_new.h ******************************************************************************************** + +TOML_DISABLE_WARNINGS; +#include +TOML_ENABLE_WARNINGS; + +#if TOML_CLANG >= 8 || TOML_GCC >= 7 || TOML_ICC >= 1910 || TOML_MSVC >= 1914 +#define TOML_LAUNDER(x) __builtin_launder(x) +#elif defined(__cpp_lib_launder) && __cpp_lib_launder >= 201606 +#define TOML_LAUNDER(x) std::launder(x) +#else +#define TOML_LAUNDER(x) x +#endif + +//******** impl/std_string.h ***************************************************************************************** + +TOML_DISABLE_WARNINGS; +#include +#include +TOML_ENABLE_WARNINGS; + +#if TOML_DOXYGEN \ + || (defined(__cpp_char8_t) && __cpp_char8_t >= 201811 && defined(__cpp_lib_char8_t) \ + && __cpp_lib_char8_t >= 201907) +#define TOML_HAS_CHAR8 1 +#else +#define TOML_HAS_CHAR8 0 +#endif + +namespace toml // non-abi namespace; this is not an error +{ + using namespace std::string_literals; + using namespace std::string_view_literals; +} + +#if TOML_ENABLE_WINDOWS_COMPAT + +TOML_IMPL_NAMESPACE_START +{ + TOML_NODISCARD + TOML_EXPORTED_FREE_FUNCTION + std::string narrow(std::wstring_view); + + TOML_NODISCARD + TOML_EXPORTED_FREE_FUNCTION + std::wstring widen(std::string_view); + +#if TOML_HAS_CHAR8 + + TOML_NODISCARD + TOML_EXPORTED_FREE_FUNCTION + std::wstring widen(std::u8string_view); + +#endif +} +TOML_IMPL_NAMESPACE_END; + +#endif // TOML_ENABLE_WINDOWS_COMPAT + +//******** impl/std_optional.h *************************************************************************************** + +TOML_DISABLE_WARNINGS; +#if !TOML_HAS_CUSTOM_OPTIONAL_TYPE +#include +#endif +TOML_ENABLE_WARNINGS; + +TOML_NAMESPACE_START +{ +#if TOML_HAS_CUSTOM_OPTIONAL_TYPE + + template + using optional = TOML_OPTIONAL_TYPE; + +#else + + template + using optional = std::optional; + +#endif +} +TOML_NAMESPACE_END; + +//******** impl/forward_declarations.h ******************************************************************************* + +TOML_DISABLE_WARNINGS; +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +TOML_ENABLE_WARNINGS; +TOML_PUSH_WARNINGS; +#ifdef _MSC_VER +#pragma inline_recursion(on) +#pragma push_macro("min") +#pragma push_macro("max") +#undef min +#undef max +#endif + +#ifndef TOML_DISABLE_ENVIRONMENT_CHECKS +#define TOML_ENV_MESSAGE \ + "If you're seeing this error it's because you're building toml++ for an environment that doesn't conform to " \ + "one of the 'ground truths' assumed by the library. Essentially this just means that I don't have the " \ + "resources to test on more platforms, but I wish I did! You can try disabling the checks by defining " \ + "TOML_DISABLE_ENVIRONMENT_CHECKS, but your mileage may vary. Please consider filing an issue at " \ + "https://github.com/marzer/tomlplusplus/issues to help me improve support for your target environment. " \ + "Thanks!" + +static_assert(CHAR_BIT == 8, TOML_ENV_MESSAGE); +static_assert(FLT_RADIX == 2, TOML_ENV_MESSAGE); +static_assert('A' == 65, TOML_ENV_MESSAGE); +static_assert(sizeof(double) == 8, TOML_ENV_MESSAGE); +static_assert(std::numeric_limits::is_iec559, TOML_ENV_MESSAGE); +static_assert(std::numeric_limits::digits == 53, TOML_ENV_MESSAGE); +static_assert(std::numeric_limits::digits10 == 15, TOML_ENV_MESSAGE); + +#undef TOML_ENV_MESSAGE +#endif // !TOML_DISABLE_ENVIRONMENT_CHECKS + +// undocumented forward declarations are hidden from doxygen because they fuck it up =/ + +namespace toml // non-abi namespace; this is not an error +{ + using ::std::size_t; + using ::std::intptr_t; + using ::std::uintptr_t; + using ::std::ptrdiff_t; + using ::std::nullptr_t; + using ::std::int8_t; + using ::std::int16_t; + using ::std::int32_t; + using ::std::int64_t; + using ::std::uint8_t; + using ::std::uint16_t; + using ::std::uint32_t; + using ::std::uint64_t; + using ::std::uint_least32_t; + using ::std::uint_least64_t; +} + +TOML_NAMESPACE_START +{ + struct date; + struct time; + struct time_offset; + + TOML_ABI_NAMESPACE_BOOL(TOML_HAS_CUSTOM_OPTIONAL_TYPE, custopt, stdopt); + struct date_time; + TOML_ABI_NAMESPACE_END; + + struct source_position; + struct source_region; + + class node; + template + class node_view; + + class key; + class array; + class table; + template + class value; + + class path; + + class toml_formatter; + class json_formatter; + class yaml_formatter; + + TOML_ABI_NAMESPACE_BOOL(TOML_EXCEPTIONS, ex, noex); +#if TOML_EXCEPTIONS + using parse_result = table; +#else + class parse_result; +#endif + TOML_ABI_NAMESPACE_END; // TOML_EXCEPTIONS +} +TOML_NAMESPACE_END; + +TOML_IMPL_NAMESPACE_START +{ + using node_ptr = std::unique_ptr; + + TOML_ABI_NAMESPACE_BOOL(TOML_EXCEPTIONS, impl_ex, impl_noex); + class parser; + TOML_ABI_NAMESPACE_END; // TOML_EXCEPTIONS + + // clang-format off + + inline constexpr std::string_view control_char_escapes[] = + { + "\\u0000"sv, + "\\u0001"sv, + "\\u0002"sv, + "\\u0003"sv, + "\\u0004"sv, + "\\u0005"sv, + "\\u0006"sv, + "\\u0007"sv, + "\\b"sv, + "\\t"sv, + "\\n"sv, + "\\u000B"sv, + "\\f"sv, + "\\r"sv, + "\\u000E"sv, + "\\u000F"sv, + "\\u0010"sv, + "\\u0011"sv, + "\\u0012"sv, + "\\u0013"sv, + "\\u0014"sv, + "\\u0015"sv, + "\\u0016"sv, + "\\u0017"sv, + "\\u0018"sv, + "\\u0019"sv, + "\\u001A"sv, + "\\u001B"sv, + "\\u001C"sv, + "\\u001D"sv, + "\\u001E"sv, + "\\u001F"sv, + }; + + inline constexpr std::string_view node_type_friendly_names[] = + { + "none"sv, + "table"sv, + "array"sv, + "string"sv, + "integer"sv, + "floating-point"sv, + "boolean"sv, + "date"sv, + "time"sv, + "date-time"sv + }; + + // clang-format on +} +TOML_IMPL_NAMESPACE_END; + +#if TOML_ABI_NAMESPACES +#if TOML_EXCEPTIONS +#define TOML_PARSER_TYPENAME TOML_NAMESPACE::impl::impl_ex::parser +#else +#define TOML_PARSER_TYPENAME TOML_NAMESPACE::impl::impl_noex::parser +#endif +#else +#define TOML_PARSER_TYPENAME TOML_NAMESPACE::impl::parser +#endif + +namespace toml +{ +} + +TOML_NAMESPACE_START // abi namespace +{ + inline namespace literals + { + } + + enum class TOML_CLOSED_ENUM node_type : uint8_t + { + none, + table, + array, + string, + integer, + floating_point, + boolean, + date, + time, + date_time + }; + + template + inline std::basic_ostream& operator<<(std::basic_ostream& lhs, node_type rhs) + { + const auto str = impl::node_type_friendly_names[static_cast>(rhs)]; + using str_char_t = decltype(str)::value_type; + if constexpr (std::is_same_v) + return lhs << str; + else + { + if constexpr (sizeof(Char) == sizeof(str_char_t)) + return lhs << std::basic_string_view{ reinterpret_cast(str.data()), str.length() }; + else + return lhs << str.data(); + } + } + + enum class TOML_OPEN_FLAGS_ENUM value_flags : uint16_t // being an "OPEN" flags enum is not an error + { + none, + format_as_binary = 1, + format_as_octal = 2, + format_as_hexadecimal = 3, + }; + TOML_MAKE_FLAGS(value_flags); + + inline constexpr value_flags preserve_source_value_flags = + POXY_IMPLEMENTATION_DETAIL(value_flags{ static_cast>(-1) }); + + enum class TOML_CLOSED_FLAGS_ENUM format_flags : uint64_t + { + none, + quote_dates_and_times = (1ull << 0), + quote_infinities_and_nans = (1ull << 1), + allow_literal_strings = (1ull << 2), + allow_multi_line_strings = (1ull << 3), + allow_real_tabs_in_strings = (1ull << 4), + allow_unicode_strings = (1ull << 5), + allow_binary_integers = (1ull << 6), + allow_octal_integers = (1ull << 7), + allow_hexadecimal_integers = (1ull << 8), + indent_sub_tables = (1ull << 9), + indent_array_elements = (1ull << 10), + indentation = indent_sub_tables | indent_array_elements, + relaxed_float_precision = (1ull << 11), + terse_key_value_pairs = (1ull << 12), + }; + TOML_MAKE_FLAGS(format_flags); + + template + struct TOML_TRIVIAL_ABI inserter + { + static_assert(std::is_reference_v); + + T value; + }; + template + inserter(T &&) -> inserter; + template + inserter(T&) -> inserter; + + using default_formatter = toml_formatter; +} +TOML_NAMESPACE_END; + +TOML_IMPL_NAMESPACE_START +{ + template + using remove_cvref = std::remove_cv_t>; + + template + using common_signed_type = std::common_type_t...>; + + template + inline constexpr bool is_one_of = (false || ... || std::is_same_v); + + template + inline constexpr bool all_integral = (std::is_integral_v && ...); + + template + inline constexpr bool is_cvref = std::is_reference_v || std::is_const_v || std::is_volatile_v; + + template + inline constexpr bool is_wide_string = + is_one_of, const wchar_t*, wchar_t*, std::wstring_view, std::wstring>; + + template + inline constexpr bool value_retrieval_is_nothrow = !std::is_same_v, std::string> +#if TOML_HAS_CHAR8 + && !std::is_same_v, std::u8string> +#endif + + && !is_wide_string; + + template + struct copy_ref_; + template + using copy_ref = typename copy_ref_::type; + + template + struct copy_ref_ + { + using type = Dest; + }; + + template + struct copy_ref_ + { + using type = std::add_lvalue_reference_t; + }; + + template + struct copy_ref_ + { + using type = std::add_rvalue_reference_t; + }; + + template + struct copy_cv_; + template + using copy_cv = typename copy_cv_::type; + + template + struct copy_cv_ + { + using type = Dest; + }; + + template + struct copy_cv_ + { + using type = std::add_const_t; + }; + + template + struct copy_cv_ + { + using type = std::add_volatile_t; + }; + + template + struct copy_cv_ + { + using type = std::add_cv_t; + }; + + template + using copy_cvref = + copy_ref, std::remove_reference_t>, Dest>, Src>; + + template + inline constexpr bool dependent_false = false; + + template + inline constexpr bool first_is_same = false; + template + inline constexpr bool first_is_same = true; + + // general value traits + // (as they relate to their equivalent native TOML type) + template + struct value_traits + { + using native_type = void; + static constexpr bool is_native = false; + static constexpr bool is_losslessly_convertible_to_native = false; + static constexpr bool can_represent_native = false; + static constexpr bool can_partially_represent_native = false; + static constexpr auto type = node_type::none; + }; + + template + struct value_traits : value_traits + {}; + template + struct value_traits : value_traits + {}; + template + struct value_traits : value_traits + {}; + template + struct value_traits : value_traits + {}; + template + struct value_traits : value_traits + {}; + + // integer value_traits specializations - standard types + template + struct integer_limits + { + static constexpr auto min = (std::numeric_limits::min)(); + static constexpr auto max = (std::numeric_limits::max)(); + }; + template + struct integer_traits_base : integer_limits + { + using native_type = int64_t; + static constexpr bool is_native = std::is_same_v; + static constexpr bool is_signed = static_cast(-1) < T{}; // for impls not specializing std::is_signed + static constexpr auto type = node_type::integer; + static constexpr bool can_partially_represent_native = true; + }; + template + struct unsigned_integer_traits : integer_traits_base + { + static constexpr bool is_losslessly_convertible_to_native = integer_limits::max <= 9223372036854775807ULL; + static constexpr bool can_represent_native = false; + }; + template + struct signed_integer_traits : integer_traits_base + { + using native_type = int64_t; + static constexpr bool is_losslessly_convertible_to_native = + integer_limits::min >= (-9223372036854775807LL - 1LL) && integer_limits::max <= 9223372036854775807LL; + static constexpr bool can_represent_native = + integer_limits::min <= (-9223372036854775807LL - 1LL) && integer_limits::max >= 9223372036854775807LL; + }; + template ::is_signed> + struct integer_traits : signed_integer_traits + {}; + template + struct integer_traits : unsigned_integer_traits + {}; + template <> + struct value_traits : integer_traits + {}; + template <> + struct value_traits : integer_traits + {}; + template <> + struct value_traits : integer_traits + {}; + template <> + struct value_traits : integer_traits + {}; + template <> + struct value_traits : integer_traits + {}; + template <> + struct value_traits : integer_traits + {}; + template <> + struct value_traits : integer_traits + {}; + template <> + struct value_traits : integer_traits + {}; + template <> + struct value_traits : integer_traits + {}; + template <> + struct value_traits : integer_traits + {}; + static_assert(value_traits::is_native); + static_assert(value_traits::is_signed); + static_assert(value_traits::is_losslessly_convertible_to_native); + static_assert(value_traits::can_represent_native); + static_assert(value_traits::can_partially_represent_native); + + // integer value_traits specializations - non-standard types +#ifdef TOML_INT128 + template <> + struct integer_limits + { + static constexpr TOML_INT128 max = + static_cast((TOML_UINT128{ 1u } << ((__SIZEOF_INT128__ * CHAR_BIT) - 1)) - 1); + static constexpr TOML_INT128 min = -max - TOML_INT128{ 1 }; + }; + template <> + struct integer_limits + { + static constexpr TOML_UINT128 min = TOML_UINT128{}; + static constexpr TOML_UINT128 max = (2u * static_cast(integer_limits::max)) + 1u; + }; + template <> + struct value_traits : integer_traits + {}; + template <> + struct value_traits : integer_traits + {}; +#endif +#ifdef TOML_SMALL_INT_TYPE + template <> + struct value_traits : signed_integer_traits + {}; +#endif + + // floating-point traits base + template + struct float_traits_base + { + static constexpr auto type = node_type::floating_point; + using native_type = double; + static constexpr bool is_native = std::is_same_v; + static constexpr bool is_signed = true; + + static constexpr int bits = static_cast(sizeof(T) * CHAR_BIT); + static constexpr int digits = MantissaDigits; + static constexpr int digits10 = DecimalDigits; + + static constexpr bool is_losslessly_convertible_to_native = bits <= 64 // + && digits <= 53 // DBL_MANT_DIG + && digits10 <= 15; // DBL_DIG + + static constexpr bool can_represent_native = digits >= 53 // DBL_MANT_DIG + && digits10 >= 15; // DBL_DIG + + static constexpr bool can_partially_represent_native = digits > 0 && digits10 > 0; + }; + template + struct float_traits : float_traits_base::digits, std::numeric_limits::digits10> + {}; +#if TOML_ENABLE_FLOAT16 + template <> + struct float_traits<_Float16> : float_traits_base<_Float16, __FLT16_MANT_DIG__, __FLT16_DIG__> + {}; +#endif +#ifdef TOML_FLOAT128 + template <> + struct float_traits : float_traits_base + {}; +#endif + + // floating-point traits + template <> + struct value_traits : float_traits + {}; + template <> + struct value_traits : float_traits + {}; + template <> + struct value_traits : float_traits + {}; +#if TOML_ENABLE_FLOAT16 + template <> + struct value_traits<_Float16> : float_traits<_Float16> + {}; +#endif +#ifdef TOML_FLOAT128 + template <> + struct value_traits : float_traits + {}; +#endif +#ifdef TOML_SMALL_FLOAT_TYPE + template <> + struct value_traits : float_traits + {}; +#endif + static_assert(value_traits::is_native); + static_assert(value_traits::is_losslessly_convertible_to_native); + static_assert(value_traits::can_represent_native); + static_assert(value_traits::can_partially_represent_native); + + // string value_traits specializations - char-based strings + template + struct string_traits + { + using native_type = std::string; + static constexpr bool is_native = std::is_same_v; + static constexpr bool is_losslessly_convertible_to_native = true; + static constexpr bool can_represent_native = + !std::is_array_v && (!std::is_pointer_v || std::is_const_v>); + static constexpr bool can_partially_represent_native = can_represent_native; + static constexpr auto type = node_type::string; + }; + template <> + struct value_traits : string_traits + {}; + template <> + struct value_traits : string_traits + {}; + template <> + struct value_traits : string_traits + {}; + template + struct value_traits : string_traits + {}; + template <> + struct value_traits : string_traits + {}; + template + struct value_traits : string_traits + {}; + + // string value_traits specializations - char8_t-based strings +#if TOML_HAS_CHAR8 + template <> + struct value_traits : string_traits + {}; + template <> + struct value_traits : string_traits + {}; + template <> + struct value_traits : string_traits + {}; + template + struct value_traits : string_traits + {}; + template <> + struct value_traits : string_traits + {}; + template + struct value_traits : string_traits + {}; +#endif + + // string value_traits specializations - wchar_t-based strings on Windows +#if TOML_ENABLE_WINDOWS_COMPAT + template + struct wstring_traits + { + using native_type = std::string; + static constexpr bool is_native = false; + static constexpr bool is_losslessly_convertible_to_native = true; // narrow + static constexpr bool can_represent_native = std::is_same_v; // widen + static constexpr bool can_partially_represent_native = can_represent_native; + static constexpr auto type = node_type::string; + }; + template <> + struct value_traits : wstring_traits + {}; + template <> + struct value_traits : wstring_traits + {}; + template <> + struct value_traits : wstring_traits + {}; + template + struct value_traits : wstring_traits + {}; + template <> + struct value_traits : wstring_traits + {}; + template + struct value_traits : wstring_traits + {}; +#endif + + // other 'native' value_traits specializations + template + struct native_value_traits + { + using native_type = T; + static constexpr bool is_native = true; + static constexpr bool is_losslessly_convertible_to_native = true; + static constexpr bool can_represent_native = true; + static constexpr bool can_partially_represent_native = true; + static constexpr auto type = NodeType; + }; + template <> + struct value_traits : native_value_traits + {}; + template <> + struct value_traits : native_value_traits + {}; + template <> + struct value_traits