diff --git a/README.md b/README.md index 9bd21fd..c0eb6b6 100644 --- a/README.md +++ b/README.md @@ -75,7 +75,7 @@ If unfamiliar with GitHub, go through tutorials in the [Using Git](#using-git) s #### CppCheck -- Download [CppCheck](https://sourceforge.net/projects/cppcheck/files/1.86/cppcheck-1.86-x64-Setup.msi/download). +- Download [CppCheck](https://github.com/danmar/cppcheck/releases/download/2.16.0/cppcheck-2.16.0-x64-Setup.msi). - If "Add CppCheck to Path" is an option during setup process, select YES. - If not, add `C:\Program Files\Cppcheck` to PATH - Read [this](https://stackoverflow.com/questions/44272416/how-to-add-a-folder-to-path-environment-variable-in-windows-10-with-screensho) for more information on adding files to PATH. @@ -181,6 +181,18 @@ To undo the going back: + + + + + + + + + + + + diff --git a/src/frc846/cpp/frc846/control/MotorMonkey.cc b/src/frc846/cpp/frc846/control/MotorMonkey.cc index d8df8a1..cf70a40 100644 --- a/src/frc846/cpp/frc846/control/MotorMonkey.cc +++ b/src/frc846/cpp/frc846/control/MotorMonkey.cc @@ -5,13 +5,12 @@ #include #include -#include "frc846/control/hardware/TalonFX_interm.h" -#include "frc846/control/hardware/SparkMXFX_interm.h" +#include +#include "frc846/control/hardware/SparkMXFX_interm.h" +#include "frc846/control/hardware/TalonFX_interm.h" #include "frc846/math/collection.h" -#include - // TODO: Add dynamic can/power management namespace frc846::control { diff --git a/src/frc846/cpp/frc846/control/hardware/SparkMXFX_interm.cc b/src/frc846/cpp/frc846/control/hardware/SparkMXFX_interm.cc index 9776a25..0ef9b4c 100644 --- a/src/frc846/cpp/frc846/control/hardware/SparkMXFX_interm.cc +++ b/src/frc846/cpp/frc846/control/hardware/SparkMXFX_interm.cc @@ -1,4 +1,5 @@ #include "frc846/control/hardware/SparkMXFX_interm.h" + #include "frc846/wpilib/util.h" namespace frc846::control::hardware { diff --git a/src/frc846/cpp/frc846/robot/swerve/drivetrain.cc b/src/frc846/cpp/frc846/robot/swerve/drivetrain.cc new file mode 100644 index 0000000..4635696 --- /dev/null +++ b/src/frc846/cpp/frc846/robot/swerve/drivetrain.cc @@ -0,0 +1,34 @@ +#include "frc846/robot/swerve/drivetrain.h" + +namespace frc846::robot::swerve { + +DrivetrainSubsystem::DrivetrainSubsystem(DrivetrainConfigs configs, bool enable) + : GenericSubsystem{"SwerveDrivetrain"}, configs_{configs}, modules_{} { + // TODO: finish +} + +void DrivetrainSubsystem::Setup() { + // TODO: finish +} + +DrivetrainTarget DrivetrainSubsystem::ZeroTarget() const { + return DrivetrainOLControlTarget{{0_fps, 0_fps}}; +} + +bool DrivetrainSubsystem::VerifyHardware() { + bool ok = true; + // TODO: finish + return ok; +} + +DrivetrainReadings DrivetrainSubsystem::ReadFromHardware() { + DrivetrainReadings readings; + // TODO: finish + return readings; +} + +void DrivetrainSubsystem::WriteToHardware(DrivetrainTarget target) { + // TODO: finish +} + +} // namespace frc846::robot::swerve \ No newline at end of file diff --git a/src/frc846/cpp/frc846/robot/swerve/odometry/swerve_pose.cc b/src/frc846/cpp/frc846/robot/swerve/odometry/swerve_pose.cc new file mode 100644 index 0000000..669db38 --- /dev/null +++ b/src/frc846/cpp/frc846/robot/swerve/odometry/swerve_pose.cc @@ -0,0 +1,30 @@ +#include "frc846/robot/swerve/odometry/swerve_pose.h" + +namespace frc846::robot::swerve::odometry { + +SwervePose SwervePose::rotate(units::degree_t angle) const { + return SwervePose{ + position.rotate(angle), bearing + angle, velocity.rotate(angle)}; +} + +SwervePose SwervePose::translate(frc846::math::Vector2D translation) const { + return SwervePose{position + translation, bearing, velocity}; +} + +SwervePose SwervePose::extrapolate(units::second_t time) const { + return SwervePose{ + position + frc846::math::Vector2D{velocity[0] * time, velocity[1] * time}, + bearing, velocity}; +} + +SwervePose SwervePose::operator+(const SwervePose& other) const { + return SwervePose{position + other.position, bearing + other.bearing, + velocity + other.velocity}; +} + +SwervePose SwervePose::operator-(const SwervePose& other) const { + return SwervePose{position - other.position, bearing - other.bearing, + velocity - other.velocity}; +} + +} // namespace frc846::robot::swerve::odometry diff --git a/src/frc846/cpp/frc846/robot/swerve/swerve_module.cc b/src/frc846/cpp/frc846/robot/swerve/swerve_module.cc index 81f37ea..98619f2 100644 --- a/src/frc846/cpp/frc846/robot/swerve/swerve_module.cc +++ b/src/frc846/cpp/frc846/robot/swerve/swerve_module.cc @@ -51,4 +51,8 @@ void SwerveModule::WriteToHardware(SwerveModuleTarget target) { // TODO: finish. Refer to howler_monkey for open-loop. } +void SwerveModule::SetSteerGains(frc846::control::base::MotorGains gains) { + steer_.SetGains(gains); +} + } // namespace frc846::robot::swerve \ No newline at end of file diff --git a/src/frc846/include/frc846/control/HigherMotorController.h b/src/frc846/include/frc846/control/HigherMotorController.h index 8a7d983..4969264 100644 --- a/src/frc846/include/frc846/control/HigherMotorController.h +++ b/src/frc846/include/frc846/control/HigherMotorController.h @@ -2,15 +2,14 @@ #include +#include + #include "frc846/control/base/motor_control_base.h" #include "frc846/control/base/motor_gains.h" #include "frc846/control/base/motor_specs.h" #include "frc846/control/config/construction_params.h" - #include "frc846/control/config/soft_limits.h" -#include - namespace frc846::control { /* diff --git a/src/frc846/include/frc846/control/MotorMonkey.h b/src/frc846/include/frc846/control/MotorMonkey.h index 5f734c8..69f7e0f 100644 --- a/src/frc846/include/frc846/control/MotorMonkey.h +++ b/src/frc846/include/frc846/control/MotorMonkey.h @@ -5,12 +5,12 @@ #include +#include "frc846/base/Loggable.h" #include "frc846/control/base/motor_control_base.h" #include "frc846/control/base/motor_gains.h" #include "frc846/control/base/motor_specs.h" #include "frc846/control/config/construction_params.h" #include "frc846/control/hardware/TalonFX_interm.h" -#include "frc846/base/Loggable.h" #define CONTROLLER_REGISTRY_SIZE 64 diff --git a/src/frc846/include/frc846/control/calculators/CircuitResistanceCalculator.h b/src/frc846/include/frc846/control/calculators/CircuitResistanceCalculator.h index 66d7111..e8a0ee2 100644 --- a/src/frc846/include/frc846/control/calculators/CircuitResistanceCalculator.h +++ b/src/frc846/include/frc846/control/calculators/CircuitResistanceCalculator.h @@ -2,7 +2,7 @@ #include -#include "frc846/wpilib/846_units.h" +#include "frc846/wpilib/units.h" namespace frc846::control::calculators { diff --git a/src/frc846/include/frc846/control/calculators/CurrentTorqueCalculator.h b/src/frc846/include/frc846/control/calculators/CurrentTorqueCalculator.h index df247e0..3ce74e2 100644 --- a/src/frc846/include/frc846/control/calculators/CurrentTorqueCalculator.h +++ b/src/frc846/include/frc846/control/calculators/CurrentTorqueCalculator.h @@ -2,7 +2,7 @@ #include "frc846/control/base/motor_control_base.h" #include "frc846/control/base/motor_specs.h" -#include "frc846/wpilib/846_units.h" +#include "frc846/wpilib/units.h" namespace frc846::control::calculators { diff --git a/src/frc846/include/frc846/control/calculators/VelocityPositionEstimator.h b/src/frc846/include/frc846/control/calculators/VelocityPositionEstimator.h index 0f8af5d..a66b7d7 100644 --- a/src/frc846/include/frc846/control/calculators/VelocityPositionEstimator.h +++ b/src/frc846/include/frc846/control/calculators/VelocityPositionEstimator.h @@ -4,7 +4,7 @@ #include #include -#include "frc846/wpilib/846_units.h" +#include "frc846/wpilib/units.h" namespace frc846::control::calculators { diff --git a/src/frc846/include/frc846/control/config/construction_params.h b/src/frc846/include/frc846/control/config/construction_params.h index ec8ef0c..b8626a3 100644 --- a/src/frc846/include/frc846/control/config/construction_params.h +++ b/src/frc846/include/frc846/control/config/construction_params.h @@ -4,7 +4,7 @@ #include #include -#include "frc846/wpilib/846_units.h" +#include "frc846/wpilib/units.h" namespace frc846::control::config { diff --git a/src/frc846/include/frc846/control/config/soft_limits.h b/src/frc846/include/frc846/control/config/soft_limits.h index c182eb1..7eaa357 100644 --- a/src/frc846/include/frc846/control/config/soft_limits.h +++ b/src/frc846/include/frc846/control/config/soft_limits.h @@ -1,6 +1,7 @@ #pragma once #include + #include namespace frc846::control::config { diff --git a/src/frc846/include/frc846/control/hardware/SparkMXFX_interm.h b/src/frc846/include/frc846/control/hardware/SparkMXFX_interm.h index 65a14c4..bbb5eaf 100644 --- a/src/frc846/include/frc846/control/hardware/SparkMXFX_interm.h +++ b/src/frc846/include/frc846/control/hardware/SparkMXFX_interm.h @@ -2,8 +2,9 @@ #include #include -#include + #include +#include #include "IntermediateController.h" diff --git a/src/frc846/include/frc846/control/simulation/MCSimulator.h b/src/frc846/include/frc846/control/simulation/MCSimulator.h index dee7e70..19c0d53 100644 --- a/src/frc846/include/frc846/control/simulation/MCSimulator.h +++ b/src/frc846/include/frc846/control/simulation/MCSimulator.h @@ -10,7 +10,7 @@ #include "frc846/control/base/motor_gains.h" #include "frc846/control/base/motor_specs.h" -#include "frc846/wpilib/846_units.h" +#include "frc846/wpilib/units.h" namespace frc846::control::simulation { diff --git a/src/frc846/include/frc846/math/fieldpoints.h b/src/frc846/include/frc846/math/fieldpoints.h index 3239933..59d8aeb 100644 --- a/src/frc846/include/frc846/math/fieldpoints.h +++ b/src/frc846/include/frc846/math/fieldpoints.h @@ -12,10 +12,10 @@ namespace frc846::math { struct FieldPoint { - VectorND point; + VectorND point; units::degree_t bearing; - VectorND velocity; + VectorND velocity; // Returns a FieldPoint that is 'mirrored' across the field FieldPoint mirror(bool shouldMirror = true) const { diff --git a/src/frc846/include/frc846/math/vectors.h b/src/frc846/include/frc846/math/vectors.h index 3dd207a..82888d6 100644 --- a/src/frc846/include/frc846/math/vectors.h +++ b/src/frc846/include/frc846/math/vectors.h @@ -12,11 +12,13 @@ #include "frc846/math/collection.h" namespace frc846::math { -template class VectorND { +template class VectorND { static_assert( N > 0, "VectorND can not be created with less than one dimension."); - static_assert(units::traits::is_unit_t(), - "VectorND can only be created with unit types."); + static_assert(units::traits::is_unit(), + "VectorND can only be created with unit types. Unit_t is invalid."); + + using T = units::unit_t; private: std::vector data; @@ -50,86 +52,86 @@ template class VectorND { } // Copy constructor for VectorND - VectorND(const VectorND& other) : VectorND() { + VectorND(const VectorND& other) : VectorND() { for (size_t i = 0; i < N; ++i) { data[i] = other[i]; } } - // Adds VectorND to this and returns result - VectorND operator+(const VectorND& other) const { - VectorND result; + // Adds VectorND to this and returns result + VectorND operator+(const VectorND& other) const { + VectorND result; for (size_t i = 0; i < N; ++i) { result[i] = data[i] + other[i]; } return result; } - // Subtracts VectorND from this and returns result - VectorND operator-(const VectorND& other) const { - VectorND result; + // Subtracts VectorND from this and returns result + VectorND operator-(const VectorND& other) const { + VectorND result; for (size_t i = 0; i < N; ++i) { result[i] = data[i] - other[i]; } return result; } - VectorND operator*(const double scalar) const { - VectorND result; + VectorND operator*(const double scalar) const { + VectorND result; for (size_t i = 0; i < N; ++i) { result[i] = data[i] * scalar; } return result; } - friend double operator*(double lhs, const VectorND& rhs) { + friend double operator*(double lhs, const VectorND& rhs) { return rhs * lhs; } - VectorND operator/(const double scalar) const { - VectorND result; + VectorND operator/(const double scalar) const { + VectorND result; for (size_t i = 0; i < N; ++i) { result[i] = data[i] / scalar; } return result; } - VectorND& operator+=(const VectorND& other) { + VectorND& operator+=(const VectorND& other) { for (size_t i = 0; i < N; ++i) { data[i] += other[i]; } return *this; } - VectorND& operator-=(const VectorND& other) { + VectorND& operator-=(const VectorND& other) { for (size_t i = 0; i < N; ++i) { data[i] -= other[i]; } return *this; } - VectorND& operator*=(const double scalar) { + VectorND& operator*=(const double scalar) { for (size_t i = 0; i < N; ++i) { data[i] *= scalar; } return *this; } - VectorND& operator/=(const double scalar) { + VectorND& operator/=(const double scalar) { for (size_t i = 0; i < N; ++i) { data[i] /= scalar; } return *this; } - void operator=(const VectorND& other) { + void operator=(const VectorND& other) { for (size_t i = 0; i < N; ++i) { data[i] = other[i]; } } // Uses 'safe' double comparison - bool operator==(const VectorND& other) const { + bool operator==(const VectorND& other) const { for (size_t i = 0; i < N; ++i) { if (!frc846::math::DEquals(data[i], other[i])) { return false; } } @@ -137,7 +139,7 @@ template class VectorND { } // Returns a vector rotated by a given angle. Default is clockwise rotation. - VectorND rotate(units::degree_t angle, bool clockwise = true) const { + VectorND rotate(units::degree_t angle, bool clockwise = true) const { static_assert(N == 2, "Rotation is only defined for 2D vectors."); if (clockwise) { angle = -angle; } return { @@ -146,7 +148,7 @@ template class VectorND { } // Returns the dot product of this vector and another - T dot(const VectorND& other) const { + T dot(const VectorND& other) const { T result = T{}; for (size_t i = 0; i < N; ++i) { result += data[i] * other[i].template to(); @@ -156,7 +158,7 @@ template class VectorND { // Returns the cross product of this vector and another // Cross product is only defined for 3D vectors - VectorND cross(const VectorND& other) const { + VectorND cross(const VectorND& other) const { static_assert(N == 3, "Cross product is only defined for 3D vectors."); return {data[1] * other[2] - data[2] * other[1], data[2] * other[0] - data[0] * other[2], @@ -173,17 +175,17 @@ template class VectorND { } // Returns the unit vector of this vector - VectorND unit() const { + VectorND unit() const { return *this / magnitude().template to(); } // Projects this vector onto another and returns - VectorND projectOntoAnother(const VectorND& other) const { + VectorND projectOntoAnother(const VectorND& other) const { return other.projectOntoThis(*this); } // Projects another vector onto this and returns - VectorND projectOntoThis(const VectorND& other) const { + VectorND projectOntoThis(const VectorND& other) const { return unit() * dot(other).template to(); } @@ -198,7 +200,7 @@ template class VectorND { // Returns the angle between this vector and another units::degree_t angleTo( - const VectorND& other, bool angleIsBearing = false) const { + const VectorND& other, bool angleIsBearing = false) const { return other.angle(angleIsBearing) - angle(angleIsBearing); } @@ -227,10 +229,10 @@ template class VectorND { // Commonly used vector types // 1D vector, units::inch_t -using Vector1D = VectorND; +using Vector1D = VectorND; // 2D vector, units::inch_t -using Vector2D = VectorND; +using Vector2D = VectorND; // 3D vector, units::inch_t -using Vector3D = VectorND; +using Vector3D = VectorND; } // namespace frc846::math \ No newline at end of file diff --git a/src/frc846/include/frc846/robot/calculators/VerticalArmCalculator.h b/src/frc846/include/frc846/robot/calculators/VerticalArmCalculator.h index 54837a0..38fab9b 100644 --- a/src/frc846/include/frc846/robot/calculators/VerticalArmCalculator.h +++ b/src/frc846/include/frc846/robot/calculators/VerticalArmCalculator.h @@ -8,7 +8,7 @@ #include "frc846/control/base/motor_gains.h" #include "frc846/math/calculator.h" #include "frc846/math/constants.h" -#include "frc846/wpilib/846_units.h" +#include "frc846/wpilib/units.h" namespace frc846::robot::calculators { diff --git a/src/frc846/include/frc846/robot/swerve/drivetrain.h b/src/frc846/include/frc846/robot/swerve/drivetrain.h new file mode 100644 index 0000000..3786311 --- /dev/null +++ b/src/frc846/include/frc846/robot/swerve/drivetrain.h @@ -0,0 +1,63 @@ +#pragma once + +#include +#include + +#include "frc846/robot/GenericSubsystem.h" +#include "frc846/robot/swerve/odometry/swerve_pose.h" +#include "frc846/robot/swerve/swerve_module.h" + +namespace frc846::robot::swerve { + +/* +DrivetrainConfigs + +Contains all configs related to the specific drivetrain in use. +*/ +struct DrivetrainConfigs {}; + +struct DrivetrainReadings { + frc846::robot::swerve::odometry::SwervePose pose; +}; + +// Open-loop control, for use during teleop +struct DrivetrainOLControlTarget { + frc846::math::VectorND velocity; +}; + +// Allows for acceleration-based control of the drivetrain +struct DrivetrainAccelerationControlTarget { + frc846::math::VectorND linear_acceleration; + units::degrees_per_second_squared_t angular_acceleration; +}; + +using DrivetrainTarget = std::variant; + +/* +DrivetrainSubsystem + +A generic class to control a 4-module Kraken x60 swerve drive with CANCoders. +*/ +class DrivetrainSubsystem + : public frc846::robot::GenericSubsystem { +public: + DrivetrainSubsystem(DrivetrainConfigs configs, bool enable); + + void Setup() override; + + DrivetrainTarget ZeroTarget() const override; + + bool VerifyHardware() override; + +private: + DrivetrainReadings ReadFromHardware() override; + + void WriteToHardware(DrivetrainTarget target) override; + + DrivetrainConfigs configs_; + std::array modules_; +}; + +} // namespace frc846::robot::swerve \ No newline at end of file diff --git a/src/frc846/include/frc846/robot/swerve/odometry/swerve_pose.h b/src/frc846/include/frc846/robot/swerve/odometry/swerve_pose.h new file mode 100644 index 0000000..1a5318a --- /dev/null +++ b/src/frc846/include/frc846/robot/swerve/odometry/swerve_pose.h @@ -0,0 +1,34 @@ +#pragma once + +#include "frc846/math/vectors.h" + +namespace frc846::robot::swerve::odometry { + +/* +SwervePose + +A class representing the pose of a swerve drive robot. Contains Vector2D (check +math/vectors.h) position and velocity, and a bearing (degrees). +*/ +struct SwervePose { + frc846::math::Vector2D position; + units::degree_t bearing; + frc846::math::VectorND velocity; + + SwervePose rotate(units::degree_t angle) const; + SwervePose translate(frc846::math::Vector2D translation) const; + + /* + Extrapolates the pose of the robot by the given time, knowing the velocity. + Can be used for latency compensation. + + @note Can be innacurate with large time intervals, especially if the robot is + moving at a non-constant velocity. + */ + SwervePose extrapolate(units::second_t time) const; + + SwervePose operator+(const SwervePose& other) const; + SwervePose operator-(const SwervePose& other) const; +}; + +} // namespace frc846::robot::swerve::odometry \ No newline at end of file diff --git a/src/frc846/include/frc846/robot/swerve/swerve_module.h b/src/frc846/include/frc846/robot/swerve/swerve_module.h index 3172adf..bb43a37 100644 --- a/src/frc846/include/frc846/robot/swerve/swerve_module.h +++ b/src/frc846/include/frc846/robot/swerve/swerve_module.h @@ -1,17 +1,16 @@ #pragma once -#include "frc846/robot/GenericSubsystem.h" -#include "frc846/control/HigherMotorController.h" -#include "frc846/control/HMCHelper.h" - #include +#include #include #include -#include +#include #include -#include +#include "frc846/control/HMCHelper.h" +#include "frc846/control/HigherMotorController.h" +#include "frc846/robot/GenericSubsystem.h" namespace frc846::robot::swerve { @@ -21,11 +20,13 @@ struct SwerveModuleReadings { units::degree_t steer_pos; }; +// Allows for torque-based control by DrivetrainSubsystem struct SwerveModuleTorqueControlTarget { units::newton_meter_t drive; units::newton_meter_t steer; }; +// For open-loop control by DrivetrainSubsystem struct SwerveModuleOLControlTarget { double drive; units::degree_t steer; @@ -34,6 +35,13 @@ struct SwerveModuleOLControlTarget { using SwerveModuleTarget = std::variant; +/* +SwerveModule + +A class representing a single swerve module. Controls a drive and steer motor +and a CANcoder. Meant to be constructed as a child subsystem of +DrivetrainSubsystem. +*/ class SwerveModule : public frc846::robot::GenericSubsystem { @@ -42,6 +50,12 @@ class SwerveModule units::compound_unit>>; public: + /* + SwerveModule() + + Constructs a SwerveModule object with the given parameters. For use by + DrivetrainSubsystem. + */ SwerveModule(Loggable& parent, std::string loc, frc846::control::config::MotorConstructionParameters drive_params, frc846::control::config::MotorConstructionParameters steer_params, @@ -55,15 +69,19 @@ class SwerveModule bool VerifyHardware() override; - void SetMaxSpeed(units::feet_per_second_t max_speed); + /* + SetSteerGains() + + Sets the gains for the steer motor controller. Should be called after + SwerveModuleSubsystem Setup, in DrivetrainSubsystem Setup. + */ + void SetSteerGains(frc846::control::base::MotorGains gains); private: SwerveModuleReadings ReadFromHardware() override; void WriteToHardware(SwerveModuleTarget target) override; - units::feet_per_second_t max_speed_ = 10.0_fps; - frc846::control::HigherMotorController drive_; frc846::control::HigherMotorController steer_; diff --git a/src/frc846/include/frc846/wpilib/846_units.h b/src/frc846/include/frc846/wpilib/units.h similarity index 100% rename from src/frc846/include/frc846/wpilib/846_units.h rename to src/frc846/include/frc846/wpilib/units.h diff --git a/src/frc846/include/frc846/wpilib/util.h b/src/frc846/include/frc846/wpilib/util.h index 0c90856..50f8fcd 100644 --- a/src/frc846/include/frc846/wpilib/util.h +++ b/src/frc846/include/frc846/wpilib/util.h @@ -1,5 +1,5 @@ -#include #include +#include namespace frc846::wpilib { diff --git a/style.standard b/style.standard index 13b525c..aa1e8b6 100644 --- a/style.standard +++ b/style.standard @@ -1 +1 @@ -{ BasedOnStyle: Google, AccessModifierOffset: -2, AlignAfterOpenBracket: DontAlign, AlignConsecutiveAssignments: false, AlignConsecutiveDeclarations: false, AlignEscapedNewlines: Left, AlignOperands: true, AlignTrailingComments: true, AllowAllParametersOfDeclarationOnNextLine: true, AllowShortBlocksOnASingleLine: true, AllowShortCaseLabelsOnASingleLine: true, AllowShortEnumsOnASingleLine: true, AllowShortFunctionsOnASingleLine: true, AllowShortIfStatementsOnASingleLine: true, AllowShortLambdasOnASingleLine: Inline, AllowShortLoopsOnASingleLine: false, AlwaysBreakAfterReturnType: None, AlwaysBreakBeforeMultilineStrings: false, AlwaysBreakTemplateDeclarations: false, BinPackArguments: true, BinPackParameters: true, BreakAfterJavaFieldAnnotations: false, BreakBeforeBinaryOperators: None, BreakBeforeBraces: Attach, BreakBeforeConceptDeclarations: false, BreakBeforeTernaryOperators: true, BreakConstructorInitializersBeforeComma: false, ColumnLimit: 80, CompactNamespaces: false, ConstructorInitializerAllOnOneLineOrOnePerLine: true, ConstructorInitializerIndentWidth: 4, ContinuationIndentWidth: 4, Cpp11BracedListStyle: true, DeriveLineEnding: true, DerivePointerAlignment: true, DisableFormat: false, FixNamespaceComments: false, IndentAccessModifiers: false, IndentCaseLabels: false, IndentExternBlock: AfterExternBlock, IndentPPDirectives: None, IndentWidth: 2, InsertTrailingCommas: None, KeepEmptyLinesAtTheStartOfBlocks: false, MacroBlockBegin: "", MacroBlockEnd: "", MaxEmptyLinesToKeep: 1, NamespaceIndentation: None, PenaltyBreakAssignment: 2, PenaltyBreakBeforeFirstCallParameter: 19, PenaltyBreakComment: 300, PenaltyBreakFirstLessLess: 120, PenaltyBreakString: 1000, PenaltyExcessCharacter: 1000000, PenaltyReturnTypeOnItsOwnLine: 60, PointerAlignment: Left, ReflowComments: true, SortIncludes: false, SortUsingDeclarations: true, SpaceAfterCStyleCast: false, SpaceAfterLogicalNot: false, SpaceAfterTemplateKeyword: true, SpaceAroundPointerQualifiers: Default, SpaceBeforeAssignmentOperators: true, SpaceBeforeCaseColon: false, SpaceBeforeCpp11BracedList: false, SpaceBeforeCtorInitializerColon: true, SpaceBeforeInheritanceColon: true, SpaceBeforeParens: ControlStatements, SpaceBeforeRangeBasedForLoopColon: true, SpaceBeforeSquareBrackets: false, SpaceInEmptyBlock: false, SpaceInEmptyParentheses: false, SpacesBeforeTrailingComments: 2, SpacesInAngles: false, SpacesInCStyleCastParentheses: false, SpacesInContainerLiterals: false, SpacesInParentheses: false, SpacesInSquareBrackets: false, Standard: Auto, TabWidth: 2, UseCRLF: false, UseTab: Never } \ No newline at end of file +{ BasedOnStyle: Google, AccessModifierOffset: -2, AlignAfterOpenBracket: DontAlign, AlignConsecutiveAssignments: false, AlignConsecutiveDeclarations: false, AlignEscapedNewlines: Left, AlignOperands: true, AlignTrailingComments: true, AllowAllParametersOfDeclarationOnNextLine: true, AllowShortBlocksOnASingleLine: true, AllowShortCaseLabelsOnASingleLine: true, AllowShortEnumsOnASingleLine: true, AllowShortFunctionsOnASingleLine: true, AllowShortIfStatementsOnASingleLine: true, AllowShortLambdasOnASingleLine: Inline, AllowShortLoopsOnASingleLine: false, AlwaysBreakAfterReturnType: None, AlwaysBreakBeforeMultilineStrings: false, AlwaysBreakTemplateDeclarations: false, BinPackArguments: true, BinPackParameters: true, BreakAfterJavaFieldAnnotations: false, BreakBeforeBinaryOperators: None, BreakBeforeBraces: Attach, BreakBeforeConceptDeclarations: false, BreakBeforeTernaryOperators: true, BreakConstructorInitializersBeforeComma: false, ColumnLimit: 80, CompactNamespaces: false, ConstructorInitializerAllOnOneLineOrOnePerLine: true, ConstructorInitializerIndentWidth: 4, ContinuationIndentWidth: 4, Cpp11BracedListStyle: true, DeriveLineEnding: true, DerivePointerAlignment: true, DisableFormat: false, FixNamespaceComments: false, IndentAccessModifiers: false, IndentCaseLabels: false, IndentExternBlock: AfterExternBlock, IndentPPDirectives: None, IndentWidth: 2, InsertTrailingCommas: None, KeepEmptyLinesAtTheStartOfBlocks: false, MacroBlockBegin: "", MacroBlockEnd: "", MaxEmptyLinesToKeep: 1, NamespaceIndentation: None, PenaltyBreakAssignment: 2, PenaltyBreakBeforeFirstCallParameter: 19, PenaltyBreakComment: 300, PenaltyBreakFirstLessLess: 120, PenaltyBreakString: 1000, PenaltyExcessCharacter: 1000000, PenaltyReturnTypeOnItsOwnLine: 60, PointerAlignment: Left, ReflowComments: true, SortIncludes: true, SortUsingDeclarations: true, SpaceAfterCStyleCast: false, SpaceAfterLogicalNot: false, SpaceAfterTemplateKeyword: true, SpaceAroundPointerQualifiers: Default, SpaceBeforeAssignmentOperators: true, SpaceBeforeCaseColon: false, SpaceBeforeCpp11BracedList: false, SpaceBeforeCtorInitializerColon: true, SpaceBeforeInheritanceColon: true, SpaceBeforeParens: ControlStatements, SpaceBeforeRangeBasedForLoopColon: true, SpaceBeforeSquareBrackets: false, SpaceInEmptyBlock: false, SpaceInEmptyParentheses: false, SpacesBeforeTrailingComments: 2, SpacesInAngles: false, SpacesInCStyleCastParentheses: false, SpacesInContainerLiterals: false, SpacesInParentheses: false, SpacesInSquareBrackets: false, Standard: Auto, TabWidth: 2, UseCRLF: false, UseTab: Never } \ No newline at end of file