mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[cscore, wpilibcExamples] Use double-quote includes for wpi/ (#8346)
Use ERR and WARN in cscore to avoid conflict with Windows headers.
This commit is contained in:
@@ -2,12 +2,11 @@
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include <wpi/driverstation/XboxController.hpp>
|
||||
#include <wpi/framework/TimedRobot.hpp>
|
||||
#include <wpi/math/filter/SlewRateLimiter.hpp>
|
||||
#include <wpi/math/util/MathUtil.hpp>
|
||||
|
||||
#include "Drivetrain.hpp"
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/math/filter/SlewRateLimiter.hpp"
|
||||
#include "wpi/math/util/MathUtil.hpp"
|
||||
|
||||
class Robot : public wpi::TimedRobot {
|
||||
public:
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include <numbers>
|
||||
|
||||
#include <wpi/math/geometry/Rotation2d.hpp>
|
||||
#include "wpi/math/geometry/Rotation2d.hpp"
|
||||
|
||||
SwerveModule::SwerveModule(const int driveMotorChannel,
|
||||
const int turningMotorChannel,
|
||||
|
||||
@@ -6,12 +6,11 @@
|
||||
|
||||
#include <numbers>
|
||||
|
||||
#include <wpi/hardware/imu/OnboardIMU.hpp>
|
||||
#include <wpi/math/geometry/Translation2d.hpp>
|
||||
#include <wpi/math/kinematics/SwerveDriveKinematics.hpp>
|
||||
#include <wpi/math/kinematics/SwerveDriveOdometry.hpp>
|
||||
|
||||
#include "SwerveModule.hpp"
|
||||
#include "wpi/hardware/imu/OnboardIMU.hpp"
|
||||
#include "wpi/math/geometry/Translation2d.hpp"
|
||||
#include "wpi/math/kinematics/SwerveDriveKinematics.hpp"
|
||||
#include "wpi/math/kinematics/SwerveDriveOdometry.hpp"
|
||||
|
||||
/**
|
||||
* Represents a swerve drive style drivetrain.
|
||||
|
||||
@@ -6,17 +6,17 @@
|
||||
|
||||
#include <numbers>
|
||||
|
||||
#include <wpi/hardware/motor/PWMSparkMax.hpp>
|
||||
#include <wpi/hardware/rotation/Encoder.hpp>
|
||||
#include <wpi/math/controller/PIDController.hpp>
|
||||
#include <wpi/math/controller/ProfiledPIDController.hpp>
|
||||
#include <wpi/math/controller/SimpleMotorFeedforward.hpp>
|
||||
#include <wpi/math/kinematics/SwerveModulePosition.hpp>
|
||||
#include <wpi/math/kinematics/SwerveModuleState.hpp>
|
||||
#include <wpi/units/angular_velocity.hpp>
|
||||
#include <wpi/units/time.hpp>
|
||||
#include <wpi/units/velocity.hpp>
|
||||
#include <wpi/units/voltage.hpp>
|
||||
#include "wpi/hardware/motor/PWMSparkMax.hpp"
|
||||
#include "wpi/hardware/rotation/Encoder.hpp"
|
||||
#include "wpi/math/controller/PIDController.hpp"
|
||||
#include "wpi/math/controller/ProfiledPIDController.hpp"
|
||||
#include "wpi/math/controller/SimpleMotorFeedforward.hpp"
|
||||
#include "wpi/math/kinematics/SwerveModulePosition.hpp"
|
||||
#include "wpi/math/kinematics/SwerveModuleState.hpp"
|
||||
#include "wpi/units/angular_velocity.hpp"
|
||||
#include "wpi/units/time.hpp"
|
||||
#include "wpi/units/velocity.hpp"
|
||||
#include "wpi/units/voltage.hpp"
|
||||
|
||||
class SwerveModule {
|
||||
public:
|
||||
|
||||
Reference in New Issue
Block a user