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

@@ -7,7 +7,7 @@
#include "wpi/units/angle.hpp"
#include "wpi/units/angular_velocity.hpp"
using namespace frc;
using namespace wpi::xrp;
XRPGyro::XRPGyro() : m_simDevice("Gyro:XRPGyro") {
if (m_simDevice) {
@@ -27,61 +27,61 @@ XRPGyro::XRPGyro() : m_simDevice("Gyro:XRPGyro") {
}
}
units::radian_t XRPGyro::GetAngle() const {
wpi::units::radian_t XRPGyro::GetAngle() const {
return GetAngleZ();
}
frc::Rotation2d XRPGyro::GetRotation2d() const {
return frc::Rotation2d{GetAngle()};
wpi::math::Rotation2d XRPGyro::GetRotation2d() const {
return wpi::math::Rotation2d{GetAngle()};
}
units::radians_per_second_t XRPGyro::GetRate() const {
wpi::units::radians_per_second_t XRPGyro::GetRate() const {
return GetRateZ();
}
units::radians_per_second_t XRPGyro::GetRateX() const {
wpi::units::radians_per_second_t XRPGyro::GetRateX() const {
if (m_simRateX) {
return units::degrees_per_second_t{m_simRateX.Get()};
return wpi::units::degrees_per_second_t{m_simRateX.Get()};
}
return 0_rad_per_s;
}
units::radians_per_second_t XRPGyro::GetRateY() const {
wpi::units::radians_per_second_t XRPGyro::GetRateY() const {
if (m_simRateY) {
return units::degrees_per_second_t{m_simRateY.Get()};
return wpi::units::degrees_per_second_t{m_simRateY.Get()};
}
return 0_rad_per_s;
}
units::radians_per_second_t XRPGyro::GetRateZ() const {
wpi::units::radians_per_second_t XRPGyro::GetRateZ() const {
if (m_simRateZ) {
return units::degrees_per_second_t{m_simRateZ.Get()};
return wpi::units::degrees_per_second_t{m_simRateZ.Get()};
}
return 0_rad_per_s;
}
units::radian_t XRPGyro::GetAngleX() const {
wpi::units::radian_t XRPGyro::GetAngleX() const {
if (m_simAngleX) {
return units::degree_t{m_simAngleX.Get()} - m_angleXOffset;
return wpi::units::degree_t{m_simAngleX.Get()} - m_angleXOffset;
}
return 0_rad;
}
units::radian_t XRPGyro::GetAngleY() const {
wpi::units::radian_t XRPGyro::GetAngleY() const {
if (m_simAngleY) {
return units::degree_t{m_simAngleY.Get()} - m_angleYOffset;
return wpi::units::degree_t{m_simAngleY.Get()} - m_angleYOffset;
}
return 0_rad;
}
units::radian_t XRPGyro::GetAngleZ() const {
wpi::units::radian_t XRPGyro::GetAngleZ() const {
if (m_simAngleZ) {
return units::degree_t{m_simAngleZ.Get()} - m_angleZOffset;
return wpi::units::degree_t{m_simAngleZ.Get()} - m_angleZOffset;
}
return 0_rad;
@@ -89,8 +89,8 @@ units::radian_t XRPGyro::GetAngleZ() const {
void XRPGyro::Reset() {
if (m_simAngleX) {
m_angleXOffset = units::degree_t{m_simAngleX.Get()};
m_angleYOffset = units::degree_t{m_simAngleY.Get()};
m_angleZOffset = units::degree_t{m_simAngleZ.Get()};
m_angleXOffset = wpi::units::degree_t{m_simAngleX.Get()};
m_angleYOffset = wpi::units::degree_t{m_simAngleY.Get()};
m_angleZOffset = wpi::units::degree_t{m_simAngleZ.Get()};
}
}

View File

@@ -10,7 +10,7 @@
#include "wpi/system/Errors.hpp"
using namespace frc;
using namespace wpi::xrp;
std::map<int, std::string> XRPMotor::s_simDeviceMap = {
{0, "motorL"}, {1, "motorR"}, {2, "motor3"}, {3, "motor4"}};
@@ -19,12 +19,12 @@ std::set<int> XRPMotor::s_registeredDevices = {};
void XRPMotor::CheckDeviceAllocation(int deviceNum) {
if (s_simDeviceMap.count(deviceNum) == 0) {
throw FRC_MakeError(frc::err::ChannelIndexOutOfRange, "Channel {}",
throw FRC_MakeError(wpi::err::ChannelIndexOutOfRange, "Channel {}",
deviceNum);
}
if (s_registeredDevices.count(deviceNum) > 0) {
throw FRC_MakeError(frc::err::ResourceAlreadyAllocated, "Channel {}",
throw FRC_MakeError(wpi::err::ResourceAlreadyAllocated, "Channel {}",
deviceNum);
}

View File

@@ -9,7 +9,7 @@
#include "wpi/system/Errors.hpp"
#include "wpi/system/Timer.hpp"
using namespace frc;
using namespace wpi::xrp;
bool XRPOnBoardIO::GetUserButtonPressed() {
return m_userButton.Get();

View File

@@ -4,8 +4,8 @@
#include "wpi/xrp/XRPRangefinder.hpp"
using namespace frc;
using namespace wpi::xrp;
units::meter_t XRPRangefinder::GetDistance() const {
return units::meter_t{m_rangefinder.GetVoltage() / 5.0 * 4.0};
wpi::units::meter_t XRPRangefinder::GetDistance() const {
return wpi::units::meter_t{m_rangefinder.GetVoltage() / 5.0 * 4.0};
}

View File

@@ -4,7 +4,7 @@
#include "wpi/xrp/XRPReflectanceSensor.hpp"
using namespace frc;
using namespace wpi::xrp;
double XRPReflectanceSensor::GetLeftReflectanceValue() const {
return m_leftSensor.GetVoltage() / 5.0;

View File

@@ -12,7 +12,7 @@
#include "wpi/system/Errors.hpp"
#include "wpi/units/angle.hpp"
using namespace frc;
using namespace wpi::xrp;
std::map<int, std::string> XRPServo::s_simDeviceMap = {
{4, "servo1"}, {5, "servo2"}, {6, "servo3"}, {7, "servo4"}};
@@ -21,12 +21,12 @@ std::set<int> XRPServo::s_registeredDevices = {};
void XRPServo::CheckDeviceAllocation(int deviceNum) {
if (s_simDeviceMap.count(deviceNum) == 0) {
throw FRC_MakeError(frc::err::ChannelIndexOutOfRange, "Channel {}",
throw FRC_MakeError(wpi::err::ChannelIndexOutOfRange, "Channel {}",
deviceNum);
}
if (s_registeredDevices.count(deviceNum) > 0) {
throw FRC_MakeError(frc::err::ResourceAlreadyAllocated, "Channel {}",
throw FRC_MakeError(wpi::err::ResourceAlreadyAllocated, "Channel {}",
deviceNum);
}
@@ -46,8 +46,8 @@ XRPServo::XRPServo(int deviceNum) {
}
}
void XRPServo::SetAngle(units::radian_t angle) {
angle = std::clamp<units::radian_t>(angle, 0_deg, 180_deg);
void XRPServo::SetAngle(wpi::units::radian_t angle) {
angle = std::clamp<wpi::units::radian_t>(angle, 0_deg, 180_deg);
double pos = angle.value() / std::numbers::pi;
if (m_simPosition) {
@@ -55,9 +55,9 @@ void XRPServo::SetAngle(units::radian_t angle) {
}
}
units::radian_t XRPServo::GetAngle() const {
wpi::units::radian_t XRPServo::GetAngle() const {
if (m_simPosition) {
return units::radian_t{m_simPosition.Get() * std::numbers::pi};
return wpi::units::radian_t{m_simPosition.Get() * std::numbers::pi};
}
return 90_deg;

View File

@@ -9,7 +9,7 @@
#include "wpi/units/angle.hpp"
#include "wpi/units/angular_velocity.hpp"
namespace frc {
namespace wpi::xrp {
/**
* @ingroup xrp_api
@@ -41,14 +41,14 @@ class XRPGyro {
*
* @return the current heading of the robot in radians.
*/
units::radian_t GetAngle() const;
wpi::units::radian_t GetAngle() const;
/**
* Gets the angle the robot is facing.
*
* @return A Rotation2d with the current heading.
* @return A wpi::math::Rotation2d with the current heading.
*/
frc::Rotation2d GetRotation2d() const;
wpi::math::Rotation2d GetRotation2d() const;
/**
* Return the rate of rotation of the gyro
@@ -57,49 +57,49 @@ class XRPGyro {
*
* @return the current rate in radians per second
*/
units::radians_per_second_t GetRate() const;
wpi::units::radians_per_second_t GetRate() const;
/**
* Gets the rate of turn in radians-per-second around the X-axis.
*
* @return rate of turn in radians-per-second
*/
units::radians_per_second_t GetRateX() const;
wpi::units::radians_per_second_t GetRateX() const;
/**
* Gets the rate of turn in radians-per-second around the Y-axis.
*
* @return rate of turn in radians-per-second
*/
units::radians_per_second_t GetRateY() const;
wpi::units::radians_per_second_t GetRateY() const;
/**
* Gets the rate of turn in radians-per-second around the Z-axis.
*
* @return rate of turn in radians-per-second
*/
units::radians_per_second_t GetRateZ() const;
wpi::units::radians_per_second_t GetRateZ() const;
/**
* Gets the currently reported angle around the X-axis.
*
* @return current angle around X-axis in radians
*/
units::radian_t GetAngleX() const;
wpi::units::radian_t GetAngleX() const;
/**
* Gets the currently reported angle around the Y-axis.
*
* @return current angle around Y-axis in radians
*/
units::radian_t GetAngleY() const;
wpi::units::radian_t GetAngleY() const;
/**
* Gets the currently reported angle around the Z-axis.
*
* @return current angle around Z-axis in radians
*/
units::radian_t GetAngleZ() const;
wpi::units::radian_t GetAngleZ() const;
/**
* Reset the gyro angles to 0.
@@ -115,11 +115,11 @@ class XRPGyro {
hal::SimDouble m_simAngleY;
hal::SimDouble m_simAngleZ;
units::radian_t m_angleXOffset = 0_rad;
units::radian_t m_angleYOffset = 0_rad;
units::radian_t m_angleZOffset = 0_rad;
wpi::units::radian_t m_angleXOffset = 0_rad;
wpi::units::radian_t m_angleYOffset = 0_rad;
wpi::units::radian_t m_angleZOffset = 0_rad;
};
/** @} */
} // namespace frc
} // namespace wpi::xrp

View File

@@ -13,7 +13,7 @@
#include "wpi/hardware/motor/MotorSafety.hpp"
#include "wpi/util/deprecated.hpp"
namespace frc {
namespace wpi::xrp {
WPI_IGNORE_DEPRECATED
@@ -27,7 +27,7 @@ WPI_IGNORE_DEPRECATED
*
* <p>A SimDevice based motor controller representing the motors on an XRP robot
*/
class XRPMotor : public frc::MotorController, public frc::MotorSafety {
class XRPMotor : public wpi::MotorController, public wpi::MotorSafety {
public:
/**
* Constructs an XRPMotor.
@@ -64,4 +64,4 @@ class XRPMotor : public frc::MotorController, public frc::MotorSafety {
WPI_UNIGNORE_DEPRECATED
} // namespace frc
} // namespace wpi::xrp

View File

@@ -10,7 +10,7 @@
#include "wpi/hardware/discrete/DigitalOutput.hpp"
#include "wpi/units/time.hpp"
namespace frc {
namespace wpi::xrp {
/**
* @ingroup xrp_api
@@ -30,7 +30,7 @@ class XRPOnBoardIO {
XRPOnBoardIO() {} // No need to do anything. No configurable IO
static constexpr auto kMessageInterval = 1_s;
units::second_t m_nextMessageTime = 0_s;
wpi::units::second_t m_nextMessageTime = 0_s;
/**
* Gets if the USER button is pressed.
@@ -54,10 +54,10 @@ class XRPOnBoardIO {
bool GetLed() const;
private:
frc::DigitalInput m_userButton{0};
frc::DigitalOutput m_led{1};
wpi::DigitalInput m_userButton{0};
wpi::DigitalOutput m_led{1};
};
/** @} */
} // namespace frc
} // namespace wpi::xrp

View File

@@ -7,7 +7,7 @@
#include "wpi/hardware/discrete/AnalogInput.hpp"
#include "wpi/units/length.hpp"
namespace frc {
namespace wpi::xrp {
/**
* @ingroup xrp_api
@@ -23,12 +23,12 @@ class XRPRangefinder {
*
* @return distance in meters
*/
units::meter_t GetDistance() const;
wpi::units::meter_t GetDistance() const;
private:
frc::AnalogInput m_rangefinder{2};
wpi::AnalogInput m_rangefinder{2};
};
/** @} */
} // namespace frc
} // namespace wpi::xrp

View File

@@ -6,7 +6,7 @@
#include "wpi/hardware/discrete/AnalogInput.hpp"
namespace frc {
namespace wpi::xrp {
/**
* @ingroup xrp_api
@@ -31,10 +31,10 @@ class XRPReflectanceSensor {
double GetRightReflectanceValue() const;
private:
frc::AnalogInput m_leftSensor{0};
frc::AnalogInput m_rightSensor{1};
wpi::AnalogInput m_leftSensor{0};
wpi::AnalogInput m_rightSensor{1};
};
/** @} */
} // namespace frc
} // namespace wpi::xrp

View File

@@ -11,7 +11,7 @@
#include "wpi/hal/SimDevice.h"
#include "wpi/units/angle.hpp"
namespace frc {
namespace wpi::xrp {
/**
* @ingroup xrp_api
@@ -37,14 +37,14 @@ class XRPServo {
*
* @param angle Desired angle in radians
*/
void SetAngle(units::radian_t angle);
void SetAngle(wpi::units::radian_t angle);
/**
* Get the servo angle.
*
* @return Current servo angle in radians
*/
units::radian_t GetAngle() const;
wpi::units::radian_t GetAngle() const;
/**
* Set the servo position.
@@ -78,4 +78,4 @@ class XRPServo {
/** @} */
} // namespace frc
} // namespace wpi::xrp

View File

@@ -1,5 +1,5 @@
classes:
frc::XRPGyro:
wpi::xrp::XRPGyro:
methods:
XRPGyro:
GetAngle:

View File

@@ -1,5 +1,5 @@
classes:
frc::XRPMotor:
wpi::xrp::XRPMotor:
methods:
XRPMotor:
Set:

View File

@@ -1,5 +1,5 @@
classes:
frc::XRPOnBoardIO:
wpi::xrp::XRPOnBoardIO:
attributes:
kMessageInterval:
m_nextMessageTime:

View File

@@ -1,4 +1,4 @@
classes:
frc::XRPRangefinder:
wpi::xrp::XRPRangefinder:
methods:
GetDistance:

View File

@@ -1,5 +1,5 @@
classes:
frc::XRPReflectanceSensor:
wpi::xrp::XRPReflectanceSensor:
methods:
GetLeftReflectanceValue:
GetRightReflectanceValue:

View File

@@ -1,5 +1,5 @@
classes:
frc::XRPServo:
wpi::xrp::XRPServo:
methods:
XRPServo:
SetAngle: