SCRIPT namespace replacements

This commit is contained in:
PJ Reiniger
2025-11-07 20:00:05 -05:00
committed by Peter Johnson
parent ae6c043632
commit 9aca8e0fd6
2622 changed files with 22275 additions and 22275 deletions

View File

@@ -4,11 +4,11 @@
#include "Drivetrain.hpp"
void Drivetrain::Drive(units::meters_per_second_t xSpeed,
units::meters_per_second_t ySpeed,
units::radians_per_second_t rot, bool fieldRelative,
units::second_t period) {
frc::ChassisSpeeds chassisSpeeds{xSpeed, ySpeed, rot};
void Drivetrain::Drive(wpi::units::meters_per_second_t xSpeed,
wpi::units::meters_per_second_t ySpeed,
wpi::units::radians_per_second_t rot, bool fieldRelative,
wpi::units::second_t period) {
wpi::math::ChassisSpeeds chassisSpeeds{xSpeed, ySpeed, rot};
if (fieldRelative) {
chassisSpeeds = chassisSpeeds.ToRobotRelative(m_imu.GetRotation2d());
}

View File

@@ -9,7 +9,7 @@
#include "Drivetrain.hpp"
class Robot : public frc::TimedRobot {
class Robot : public wpi::TimedRobot {
public:
void AutonomousPeriodic() override {
DriveWithJoystick(false);
@@ -19,27 +19,27 @@ class Robot : public frc::TimedRobot {
void TeleopPeriodic() override { DriveWithJoystick(true); }
private:
frc::XboxController m_controller{0};
wpi::XboxController m_controller{0};
Drivetrain m_swerve;
// Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0
// to 1.
frc::SlewRateLimiter<units::scalar> m_xspeedLimiter{3 / 1_s};
frc::SlewRateLimiter<units::scalar> m_yspeedLimiter{3 / 1_s};
frc::SlewRateLimiter<units::scalar> m_rotLimiter{3 / 1_s};
wpi::math::SlewRateLimiter<wpi::units::scalar> m_xspeedLimiter{3 / 1_s};
wpi::math::SlewRateLimiter<wpi::units::scalar> m_yspeedLimiter{3 / 1_s};
wpi::math::SlewRateLimiter<wpi::units::scalar> m_rotLimiter{3 / 1_s};
void DriveWithJoystick(bool fieldRelative) {
// Get the x speed. We are inverting this because Xbox controllers return
// negative values when we push forward.
const auto xSpeed = -m_xspeedLimiter.Calculate(
frc::ApplyDeadband(m_controller.GetLeftY(), 0.02)) *
wpi::math::ApplyDeadband(m_controller.GetLeftY(), 0.02)) *
Drivetrain::kMaxSpeed;
// Get the y speed or sideways/strafe speed. We are inverting this because
// we want a positive value when we pull to the left. Xbox controllers
// return positive values when you pull to the right by default.
const auto ySpeed = -m_yspeedLimiter.Calculate(
frc::ApplyDeadband(m_controller.GetLeftX(), 0.02)) *
wpi::math::ApplyDeadband(m_controller.GetLeftX(), 0.02)) *
Drivetrain::kMaxSpeed;
// Get the rate of angular rotation. We are inverting this because we want a
@@ -47,7 +47,7 @@ class Robot : public frc::TimedRobot {
// mathematics). Xbox controllers return positive values when you pull to
// the right by default.
const auto rot = -m_rotLimiter.Calculate(
frc::ApplyDeadband(m_controller.GetRightX(), 0.02)) *
wpi::math::ApplyDeadband(m_controller.GetRightX(), 0.02)) *
Drivetrain::kMaxAngularSpeed;
m_swerve.Drive(xSpeed, ySpeed, rot, fieldRelative, GetPeriod());
@@ -56,6 +56,6 @@ class Robot : public frc::TimedRobot {
#ifndef RUNNING_FRC_TESTS
int main() {
return frc::StartRobot<Robot>();
return wpi::StartRobot<Robot>();
}
#endif

View File

@@ -33,22 +33,22 @@ SwerveModule::SwerveModule(const int driveMotorChannel,
// Limit the PID Controller's input range between -pi and pi and set the input
// to be continuous.
m_turningPIDController.EnableContinuousInput(
-units::radian_t{std::numbers::pi}, units::radian_t{std::numbers::pi});
-wpi::units::radian_t{std::numbers::pi}, wpi::units::radian_t{std::numbers::pi});
}
frc::SwerveModuleState SwerveModule::GetState() const {
return {units::meters_per_second_t{m_driveEncoder.GetRate()},
units::radian_t{m_turningEncoder.GetDistance()}};
wpi::math::SwerveModuleState SwerveModule::GetState() const {
return {wpi::units::meters_per_second_t{m_driveEncoder.GetRate()},
wpi::units::radian_t{m_turningEncoder.GetDistance()}};
}
frc::SwerveModulePosition SwerveModule::GetPosition() const {
return {units::meter_t{m_driveEncoder.GetDistance()},
units::radian_t{m_turningEncoder.GetDistance()}};
wpi::math::SwerveModulePosition SwerveModule::GetPosition() const {
return {wpi::units::meter_t{m_driveEncoder.GetDistance()},
wpi::units::radian_t{m_turningEncoder.GetDistance()}};
}
void SwerveModule::SetDesiredState(frc::SwerveModuleState& referenceState) {
frc::Rotation2d encoderRotation{
units::radian_t{m_turningEncoder.GetDistance()}};
void SwerveModule::SetDesiredState(wpi::math::SwerveModuleState& referenceState) {
wpi::math::Rotation2d encoderRotation{
wpi::units::radian_t{m_turningEncoder.GetDistance()}};
// Optimize the reference state to avoid spinning further than 90 degrees
referenceState.Optimize(encoderRotation);
@@ -67,13 +67,13 @@ void SwerveModule::SetDesiredState(frc::SwerveModuleState& referenceState) {
// Calculate the turning motor output from the turning PID controller.
const auto turnOutput = m_turningPIDController.Calculate(
units::radian_t{m_turningEncoder.GetDistance()},
wpi::units::radian_t{m_turningEncoder.GetDistance()},
referenceState.angle.Radians());
const auto turnFeedforward = m_turnFeedforward.Calculate(
m_turningPIDController.GetSetpoint().velocity);
// Set the motor outputs.
m_driveMotor.SetVoltage(units::volt_t{driveOutput} + driveFeedforward);
m_turningMotor.SetVoltage(units::volt_t{turnOutput} + turnFeedforward);
m_driveMotor.SetVoltage(wpi::units::volt_t{driveOutput} + driveFeedforward);
m_turningMotor.SetVoltage(wpi::units::volt_t{turnOutput} + turnFeedforward);
}

View File

@@ -20,34 +20,34 @@ class Drivetrain {
public:
Drivetrain() { m_imu.ResetYaw(); }
void Drive(units::meters_per_second_t xSpeed,
units::meters_per_second_t ySpeed, units::radians_per_second_t rot,
bool fieldRelative, units::second_t period);
void Drive(wpi::units::meters_per_second_t xSpeed,
wpi::units::meters_per_second_t ySpeed, wpi::units::radians_per_second_t rot,
bool fieldRelative, wpi::units::second_t period);
void UpdateOdometry();
static constexpr units::meters_per_second_t kMaxSpeed =
static constexpr wpi::units::meters_per_second_t kMaxSpeed =
3.0_mps; // 3 meters per second
static constexpr units::radians_per_second_t kMaxAngularSpeed{
static constexpr wpi::units::radians_per_second_t kMaxAngularSpeed{
std::numbers::pi}; // 1/2 rotation per second
private:
frc::Translation2d m_frontLeftLocation{+0.381_m, +0.381_m};
frc::Translation2d m_frontRightLocation{+0.381_m, -0.381_m};
frc::Translation2d m_backLeftLocation{-0.381_m, +0.381_m};
frc::Translation2d m_backRightLocation{-0.381_m, -0.381_m};
wpi::math::Translation2d m_frontLeftLocation{+0.381_m, +0.381_m};
wpi::math::Translation2d m_frontRightLocation{+0.381_m, -0.381_m};
wpi::math::Translation2d m_backLeftLocation{-0.381_m, +0.381_m};
wpi::math::Translation2d m_backRightLocation{-0.381_m, -0.381_m};
SwerveModule m_frontLeft{1, 2, 0, 1, 2, 3};
SwerveModule m_frontRight{3, 4, 4, 5, 6, 7};
SwerveModule m_backLeft{5, 6, 8, 9, 10, 11};
SwerveModule m_backRight{7, 8, 12, 13, 14, 15};
frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat};
wpi::OnboardIMU m_imu{wpi::OnboardIMU::kFlat};
frc::SwerveDriveKinematics<4> m_kinematics{
wpi::math::SwerveDriveKinematics<4> m_kinematics{
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation,
m_backRightLocation};
frc::SwerveDriveOdometry<4> m_odometry{
wpi::math::SwerveDriveOdometry<4> m_odometry{
m_kinematics,
m_imu.GetRotation2d(),
{m_frontLeft.GetPosition(), m_frontRight.GetPosition(),

View File

@@ -23,9 +23,9 @@ class SwerveModule {
SwerveModule(int driveMotorChannel, int turningMotorChannel,
int driveEncoderChannelA, int driveEncoderChannelB,
int turningEncoderChannelA, int turningEncoderChannelB);
frc::SwerveModuleState GetState() const;
frc::SwerveModulePosition GetPosition() const;
void SetDesiredState(frc::SwerveModuleState& state);
wpi::math::SwerveModuleState GetState() const;
wpi::math::SwerveModulePosition GetPosition() const;
void SetDesiredState(wpi::math::SwerveModuleState& state);
private:
static constexpr double kWheelRadius = 0.0508;
@@ -36,21 +36,21 @@ class SwerveModule {
static constexpr auto kModuleMaxAngularAcceleration =
std::numbers::pi * 2_rad_per_s / 1_s; // radians per second^2
frc::PWMSparkMax m_driveMotor;
frc::PWMSparkMax m_turningMotor;
wpi::PWMSparkMax m_driveMotor;
wpi::PWMSparkMax m_turningMotor;
frc::Encoder m_driveEncoder;
frc::Encoder m_turningEncoder;
wpi::Encoder m_driveEncoder;
wpi::Encoder m_turningEncoder;
frc::PIDController m_drivePIDController{1.0, 0, 0};
frc::ProfiledPIDController<units::radians> m_turningPIDController{
wpi::math::PIDController m_drivePIDController{1.0, 0, 0};
wpi::math::ProfiledPIDController<wpi::units::radians> m_turningPIDController{
1.0,
0.0,
0.0,
{kModuleMaxAngularVelocity, kModuleMaxAngularAcceleration}};
frc::SimpleMotorFeedforward<units::meters> m_driveFeedforward{1_V,
wpi::math::SimpleMotorFeedforward<wpi::units::meters> m_driveFeedforward{1_V,
3_V / 1_mps};
frc::SimpleMotorFeedforward<units::radians> m_turnFeedforward{
wpi::math::SimpleMotorFeedforward<wpi::units::radians> m_turnFeedforward{
1_V, 0.5_V / 1_rad_per_s};
};