diff --git a/benchmark/src/main/native/thirdparty/benchmark/src/sysinfo.cpp b/benchmark/src/main/native/thirdparty/benchmark/src/sysinfo.cpp index 86922c0da6..93ad20b2f9 100644 --- a/benchmark/src/main/native/thirdparty/benchmark/src/sysinfo.cpp +++ b/benchmark/src/main/native/thirdparty/benchmark/src/sysinfo.cpp @@ -441,7 +441,7 @@ std::vector GetCacheSizes() { return GetCacheSizesQNX(); #elif defined(BENCHMARK_OS_QURT) || defined(__EMSCRIPTEN__) return std::vector(); -#elif defined(__FRC_ROBORIO__) +#elif defined(__WPILIB_ROBORIO__) return std::vector(); #else return GetCacheSizesFromKVFS(); diff --git a/commandsv2/src/main/native/cpp/frc2/command/CommandPtr.cpp b/commandsv2/src/main/native/cpp/frc2/command/CommandPtr.cpp index fdf9c40849..f45e1c60c2 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/CommandPtr.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/CommandPtr.cpp @@ -37,7 +37,7 @@ CommandPtr::CommandPtr(CommandPtr&& rhs) { void CommandPtr::AssertValid() const { if (!m_ptr) { - throw FRC_MakeError(wpi::err::CommandIllegalUse, + throw WPILIB_MakeError(wpi::err::CommandIllegalUse, "Moved-from CommandPtr object used!\nMoved out at:\n{}", m_moveOutSite); } diff --git a/commandsv2/src/main/native/cpp/frc2/command/CommandScheduler.cpp b/commandsv2/src/main/native/cpp/frc2/command/CommandScheduler.cpp index 36115042dc..aecb9d395c 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/CommandScheduler.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/CommandScheduler.cpp @@ -284,7 +284,7 @@ void CommandScheduler::UnregisterAllSubsystems() { void CommandScheduler::SetDefaultCommand(Subsystem* subsystem, CommandPtr&& defaultCommand) { if (!defaultCommand.get()->HasRequirement(subsystem)) { - throw FRC_MakeError(wpi::err::CommandIllegalUse, "{}", + throw WPILIB_MakeError(wpi::err::CommandIllegalUse, "{}", "Default commands must require their subsystem!"); } RequireUngrouped(defaultCommand.get()); @@ -430,7 +430,7 @@ void CommandScheduler::OnCommandFinish(Action action) { void CommandScheduler::RequireUngrouped(const Command* command) { auto stacktrace = command->GetPreviousCompositionSite(); if (stacktrace.has_value()) { - throw FRC_MakeError(wpi::err::CommandIllegalUse, + throw WPILIB_MakeError(wpi::err::CommandIllegalUse, "Commands that have been composed may not be added to " "another composition or scheduled individually!" "\nOriginally composed at:\n{}", @@ -454,7 +454,7 @@ void CommandScheduler::RequireUngrouped( void CommandScheduler::RequireUngroupedAndUnscheduled(const Command* command) { if (IsScheduled(command)) { - throw FRC_MakeError(wpi::err::CommandIllegalUse, + throw WPILIB_MakeError(wpi::err::CommandIllegalUse, "Commands that have been scheduled individually may " "not be added to another composition!"); } diff --git a/commandsv2/src/main/native/cpp/frc2/command/ParallelCommandGroup.cpp b/commandsv2/src/main/native/cpp/frc2/command/ParallelCommandGroup.cpp index 2580c8d571..a4a822acc8 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/ParallelCommandGroup.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/ParallelCommandGroup.cpp @@ -69,7 +69,7 @@ void ParallelCommandGroup::AddCommands( CommandScheduler::GetInstance().RequireUngroupedAndUnscheduled(commands); if (isRunning) { - throw FRC_MakeError(wpi::err::CommandIllegalUse, + throw WPILIB_MakeError(wpi::err::CommandIllegalUse, "Commands cannot be added to a CommandGroup " "while the group is running"); } @@ -85,7 +85,7 @@ void ParallelCommandGroup::AddCommands( } m_commands.emplace_back(std::move(command), false); } else { - throw FRC_MakeError(wpi::err::CommandIllegalUse, + throw WPILIB_MakeError(wpi::err::CommandIllegalUse, "Multiple commands in a parallel group cannot " "require the same subsystems"); } diff --git a/commandsv2/src/main/native/cpp/frc2/command/ParallelDeadlineGroup.cpp b/commandsv2/src/main/native/cpp/frc2/command/ParallelDeadlineGroup.cpp index 39909d95ff..07804e9ff9 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/ParallelDeadlineGroup.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/ParallelDeadlineGroup.cpp @@ -69,7 +69,7 @@ void ParallelDeadlineGroup::AddCommands( CommandScheduler::GetInstance().RequireUngroupedAndUnscheduled(commands); if (!m_finished) { - throw FRC_MakeError(wpi::err::CommandIllegalUse, + throw WPILIB_MakeError(wpi::err::CommandIllegalUse, "Commands cannot be added to a CommandGroup " "while the group is running"); } @@ -85,7 +85,7 @@ void ParallelDeadlineGroup::AddCommands( } m_commands.emplace_back(std::move(command), false); } else { - throw FRC_MakeError(wpi::err::CommandIllegalUse, + throw WPILIB_MakeError(wpi::err::CommandIllegalUse, "Multiple commands in a parallel group cannot " "require the same subsystems"); } diff --git a/commandsv2/src/main/native/cpp/frc2/command/ParallelRaceGroup.cpp b/commandsv2/src/main/native/cpp/frc2/command/ParallelRaceGroup.cpp index 0c2f28108b..ad1228eec7 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/ParallelRaceGroup.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/ParallelRaceGroup.cpp @@ -56,7 +56,7 @@ void ParallelRaceGroup::AddCommands( CommandScheduler::GetInstance().RequireUngroupedAndUnscheduled(commands); if (isRunning) { - throw FRC_MakeError(wpi::err::CommandIllegalUse, + throw WPILIB_MakeError(wpi::err::CommandIllegalUse, "Commands cannot be added to a CommandGroup " "while the group is running"); } @@ -72,7 +72,7 @@ void ParallelRaceGroup::AddCommands( } m_commands.emplace_back(std::move(command)); } else { - throw FRC_MakeError(wpi::err::CommandIllegalUse, + throw WPILIB_MakeError(wpi::err::CommandIllegalUse, "Multiple commands in a parallel group cannot " "require the same subsystems"); } diff --git a/commandsv2/src/main/native/cpp/frc2/command/SequentialCommandGroup.cpp b/commandsv2/src/main/native/cpp/frc2/command/SequentialCommandGroup.cpp index fdbc9c20db..295d8a8fe0 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/SequentialCommandGroup.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/SequentialCommandGroup.cpp @@ -68,7 +68,7 @@ void SequentialCommandGroup::AddCommands( CommandScheduler::GetInstance().RequireUngroupedAndUnscheduled(commands); if (m_currentCommandIndex != invalid_index) { - throw FRC_MakeError(wpi::err::CommandIllegalUse, + throw WPILIB_MakeError(wpi::err::CommandIllegalUse, "Commands cannot be added to a CommandGroup " "while the group is running"); } diff --git a/commandsv2/src/main/native/include/wpi/commands2/CommandScheduler.hpp b/commandsv2/src/main/native/include/wpi/commands2/CommandScheduler.hpp index 527772cef0..95a06a0807 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/CommandScheduler.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/CommandScheduler.hpp @@ -212,7 +212,7 @@ class CommandScheduler final : public wpi::util::Sendable, template T> void SetDefaultCommand(Subsystem* subsystem, T&& defaultCommand) { if (!defaultCommand.HasRequirement(subsystem)) { - throw FRC_MakeError(wpi::err::CommandIllegalUse, + throw WPILIB_MakeError(wpi::err::CommandIllegalUse, "Default commands must require their subsystem!"); } SetDefaultCommandImpl(subsystem, std::make_unique>( diff --git a/hal/src/main/native/systemcore/FRCDriverStation.cpp b/hal/src/main/native/systemcore/FRCDriverStation.cpp index ed64ebc1f6..fb13ed30c5 100644 --- a/hal/src/main/native/systemcore/FRCDriverStation.cpp +++ b/hal/src/main/native/systemcore/FRCDriverStation.cpp @@ -40,7 +40,7 @@ #include "wpi/util/timestamp.h" static_assert(sizeof(int32_t) >= sizeof(int), - "FRC_NetworkComm status variable is larger than 32 bits"); + "WPILIB_NetworkComm status variable is larger than 32 bits"); static_assert(MRC_MAX_NUM_AXES == HAL_kMaxJoystickAxes); static_assert(MRC_MAX_NUM_POVS == HAL_kMaxJoystickPOVs); diff --git a/hal/src/main/native/systemcore/HAL.cpp b/hal/src/main/native/systemcore/HAL.cpp index a5e0f311f0..74c7feefb9 100644 --- a/hal/src/main/native/systemcore/HAL.cpp +++ b/hal/src/main/native/systemcore/HAL.cpp @@ -303,7 +303,7 @@ HAL_Bool HAL_Initialize(int32_t timeout, int32_t mode) { // return false; // } - // FRC_NetworkCommunication_Reserve(nullptr); + // WPILIB_NetworkCommunication_Reserve(nullptr); int32_t status = 0; diff --git a/ntcoreffi/src/main/native/cpp/DataLogManager.cpp b/ntcoreffi/src/main/native/cpp/DataLogManager.cpp index 6f5498a74b..13e808a2f7 100644 --- a/ntcoreffi/src/main/native/cpp/DataLogManager.cpp +++ b/ntcoreffi/src/main/native/cpp/DataLogManager.cpp @@ -43,7 +43,7 @@ void ReportErrorV(int32_t status, const char* fileName, int lineNumber, // fmt::format_to(fmt::appender{out}, "Warning: "); // fmt::vformat_to(fmt::appender{out}, format, args); // out.push_back('\0'); - // FRC_NetworkCommunication_sendError(status < 0, status, 0, out.data(), + // WPILIB_NetworkCommunication_sendError(status < 0, status, 0, out.data(), // "DataLogManager", ""); // #endif } @@ -57,7 +57,7 @@ inline void ReportError(int32_t status, const char* fileName, int lineNumber, } } // namespace frc -#define FRC_ReportError(status, format, ...) \ +#define WPILIB_ReportError(status, format, ...) \ do { \ if ((status) != 0) { \ ::frc::ReportError(status, __FILE__, __LINE__, __FUNCTION__, \ @@ -71,7 +71,7 @@ inline bool IsSystemTimeValid() { // TODO when we get a proper low level library, and time setting return false; // uint8_t timeWasSet = 0; - // FRC_NetworkCommunication_getTimeWasSet(&timeWasSet); + // WPILIB_NetworkCommunication_getTimeWasSet(&timeWasSet); // return timeWasSet != 0; #else return true; @@ -109,7 +109,7 @@ enum MatchType { kNone, kPractice, kQualification, kElimination }; inline void UpdateMatchInfo() { // #ifdef __FRC_SYSTEMCORE__ // gGameSpecificMessageSize = sizeof(gGameSpecificMessage); - // FRC_NetworkCommunication_getMatchInfo(gEventName, &gMatchType, + // WPILIB_NetworkCommunication_getMatchInfo(gEventName, &gMatchType, // &gMatchNumber, // &gReplayNumber, // gGameSpecificMessage, @@ -144,7 +144,7 @@ inline uint16_t GetMatchNumber() { inline bool IsDSAttached() { // #ifdef __FRC_SYSTEMCORE__ // struct ControlWord_t cw; - // FRC_NetworkCommunication_getControlWord(&cw); + // WPILIB_NetworkCommunication_getControlWord(&cw); // return cw.dsAttached; // #else return true; @@ -154,7 +154,7 @@ inline bool IsDSAttached() { inline bool IsFMSAttached() { // #ifdef __FRC_SYSTEMCORE__ // struct ControlWord_t cw; - // FRC_NetworkCommunication_getControlWord(&cw); + // WPILIB_NetworkCommunication_getControlWord(&cw); // return cw.fmsAttached; // #else return false; @@ -250,7 +250,7 @@ static std::string MakeLogFilename(std::string_view filenameOverride) { static std::mt19937 rng(dev()); std::uniform_int_distribution dist(0, 15); const char* v = "0123456789abcdef"; - std::string filename = "FRC_TBD_"; + std::string filename = "WPILIB_TBD_"; for (int i = 0; i < 16; i++) { filename += v[dist(rng)]; } @@ -271,7 +271,7 @@ Thread::~Thread() { } void Thread::Main() { - // based on free disk space, scan for "old" FRC_*.wpilog files and remove + // based on free disk space, scan for "old" WPILIB_*.wpilog files and remove { std::error_code ec; uintmax_t freeSpace; @@ -282,14 +282,14 @@ void Thread::Main() { freeSpace = UINTMAX_MAX; } if (freeSpace < kFreeSpaceThreshold) { - // Delete oldest FRC_*.wpilog files (ignore FRC_TBD_*.wpilog as we just + // Delete oldest WPILIB_*.wpilog files (ignore WPILIB_TBD_*.wpilog as we just // created one) std::vector entries; for (auto&& entry : fs::directory_iterator{m_logDir, ec}) { auto stem = entry.path().stem().string(); - if (wpi::util::starts_with(stem, "FRC_") && + if (wpi::util::starts_with(stem, "WPILIB_") && entry.path().extension() == ".wpilog" && - !wpi::util::starts_with(stem, "FRC_TBD_")) { + !wpi::util::starts_with(stem, "WPILIB_TBD_")) { entries.emplace_back(entry); } } @@ -306,7 +306,7 @@ void Thread::Main() { } auto size = entry.file_size(); if (fs::remove(entry.path(), ec)) { - FRC_ReportError(warn::Warning, "DataLogManager: Deleted {}", + WPILIB_ReportError(warn::Warning, "DataLogManager: Deleted {}", entry.path().string()); freeSpace += size; if (freeSpace >= kFreeSpaceThreshold) { @@ -318,7 +318,7 @@ void Thread::Main() { } } } else if (freeSpace < 2 * kFreeSpaceThreshold) { - FRC_ReportError( + WPILIB_ReportError( warn::Warning, "DataLogManager: Log storage device has {} MB of free space " "remaining! Logs will get deleted below {} MB of free space. " @@ -376,7 +376,7 @@ void Thread::Main() { if (RobotController::IsSystemTimeValid()) { std::time_t now = std::time(nullptr); auto tm = std::gmtime(&now); - m_log.SetFilename(fmt::format("FRC_{:%Y%m%d_%H%M%S}.wpilog", *tm)); + m_log.SetFilename(fmt::format("WPILIB_{:%Y%m%d_%H%M%S}.wpilog", *tm)); dsRenamed = true; } else { dsAttachCount = 0; // wait a bit and try again @@ -415,7 +415,7 @@ void Thread::Main() { } std::time_t now = std::time(nullptr); m_log.SetFilename( - fmt::format("FRC_{:%Y%m%d_%H%M%S}_{}_{}{}.wpilog", + fmt::format("WPILIB_{:%Y%m%d_%H%M%S}_{}_{}{}.wpilog", *std::gmtime(&now), DriverStation::GetEventName(), matchTypeChar, DriverStation::GetMatchNumber())); fmsRenamed = true; @@ -456,7 +456,7 @@ void Thread::StopNTLog() { void Thread::StartConsoleLog() { if (!m_consoleLoggerEnabled) { m_consoleLoggerEnabled = true; - m_consoleLogger = {"/home/systemcore/FRC_UserProgram.log", m_log, "output"}; + m_consoleLogger = {"/home/systemcore/WPILIB_UserProgram.log", m_log, "output"}; } } @@ -469,13 +469,13 @@ void Thread::StopConsoleLog() { Instance::Instance(std::string_view dir, std::string_view filename, double period) { - // Delete all previously existing FRC_TBD_*.wpilog files. These only exist + // Delete all previously existing WPILIB_TBD_*.wpilog files. These only exist // when the robot never connects to the DS, so they are very unlikely to // have useful data and just clutter the filesystem. auto logDir = MakeLogDir(dir); std::error_code ec; for (auto&& entry : fs::directory_iterator{logDir, ec}) { - if (wpi::util::starts_with(entry.path().stem().string(), "FRC_TBD_") && + if (wpi::util::starts_with(entry.path().stem().string(), "WPILIB_TBD_") && entry.path().extension() == ".wpilog") { if (!fs::remove(entry, ec)) { wpi::util::print(stderr, "DataLogManager: could not delete {}\n", diff --git a/ntcoreffi/src/main/native/include/DataLogManager.h b/ntcoreffi/src/main/native/include/DataLogManager.h index 71ad522deb..de6b8c70fd 100644 --- a/ntcoreffi/src/main/native/include/DataLogManager.h +++ b/ntcoreffi/src/main/native/include/DataLogManager.h @@ -23,14 +23,14 @@ namespace wpi { * The data file will be saved to a USB flash drive in a folder named "logs" if * one is attached, or to /home/systemcore/logs otherwise. * - * Log files are initially named "FRC_TBD_{random}.wpilog" until the DS + * Log files are initially named "WPILIB_TBD_{random}.wpilog" until the DS * connects. After the DS connects, the log file is renamed to - * "FRC_yyyyMMdd_HHmmss.wpilog" (where the date/time is UTC). If the FMS is + * "WPILIB_yyyyMMdd_HHmmss.wpilog" (where the date/time is UTC). If the FMS is * connected and provides a match number, the log file is renamed to - * "FRC_yyyyMMdd_HHmmss_{event}_{match}.wpilog". + * "WPILIB_yyyyMMdd_HHmmss_{event}_{match}.wpilog". * - * On startup, all existing FRC_TBD log files are deleted. If there is less than - * 50 MB of free space on the target storage, FRC_ log files are deleted (oldest + * On startup, all existing WPILIB_TBD log files are deleted. If there is less than + * 50 MB of free space on the target storage, WPILIB_ log files are deleted (oldest * to newest) until there is 50 MB free OR there are 10 files remaining. * * By default, all NetworkTables value changes are stored to the data log. diff --git a/romiVendordep/src/main/native/cpp/romi/OnBoardIO.cpp b/romiVendordep/src/main/native/cpp/romi/OnBoardIO.cpp index 6bc7e67d5d..1a5c6e1706 100644 --- a/romiVendordep/src/main/native/cpp/romi/OnBoardIO.cpp +++ b/romiVendordep/src/main/native/cpp/romi/OnBoardIO.cpp @@ -37,7 +37,7 @@ bool OnBoardIO::GetButtonBPressed() { auto currentTime = wpi::Timer::GetTimestamp(); if (currentTime > m_nextMessageTime) { - FRC_ReportError(wpi::err::Error, "{}", "Button B was not configured"); + WPILIB_ReportError(wpi::err::Error, "{}", "Button B was not configured"); m_nextMessageTime = currentTime + kMessageInterval; } return false; @@ -50,7 +50,7 @@ bool OnBoardIO::GetButtonCPressed() { auto currentTime = wpi::Timer::GetTimestamp(); if (currentTime > m_nextMessageTime) { - FRC_ReportError(wpi::err::Error, "{}", "Button C was not configured"); + WPILIB_ReportError(wpi::err::Error, "{}", "Button C was not configured"); m_nextMessageTime = currentTime + kMessageInterval; } return false; @@ -62,7 +62,7 @@ void OnBoardIO::SetGreenLed(bool value) { } else { auto currentTime = wpi::Timer::GetTimestamp(); if (currentTime > m_nextMessageTime) { - FRC_ReportError(wpi::err::Error, "{}", "Green LED was not configured"); + WPILIB_ReportError(wpi::err::Error, "{}", "Green LED was not configured"); m_nextMessageTime = currentTime + kMessageInterval; } } @@ -74,7 +74,7 @@ void OnBoardIO::SetRedLed(bool value) { } else { auto currentTime = wpi::Timer::GetTimestamp(); if (currentTime > m_nextMessageTime) { - FRC_ReportError(wpi::err::Error, "{}", "Red LED was not configured"); + WPILIB_ReportError(wpi::err::Error, "{}", "Red LED was not configured"); m_nextMessageTime = currentTime + kMessageInterval; } } diff --git a/simulation/halsim_ds_socket/src/main/native/cpp/main.cpp b/simulation/halsim_ds_socket/src/main/native/cpp/main.cpp index 9934110cbd..a4ed0ce07e 100644 --- a/simulation/halsim_ds_socket/src/main/native/cpp/main.cpp +++ b/simulation/halsim_ds_socket/src/main/native/cpp/main.cpp @@ -3,7 +3,7 @@ // the WPILib BSD license file in the root directory of this project. /*---------------------------------------------------------------------------- -** This extension reimplements enough of the FRC_Network layer to enable the +** This extension reimplements enough of the WPILIB_Network layer to enable the ** simulator to communicate with a driver station. That includes a ** simple udp layer for communication. ** The protocol does not appear to be well documented; this implementation diff --git a/upstream_utils/benchmark_patches/0001-Add-roboRIO-benchmark-support.patch b/upstream_utils/benchmark_patches/0001-Add-roboRIO-benchmark-support.patch index 45c77ce8dc..3d496379b1 100644 --- a/upstream_utils/benchmark_patches/0001-Add-roboRIO-benchmark-support.patch +++ b/upstream_utils/benchmark_patches/0001-Add-roboRIO-benchmark-support.patch @@ -15,7 +15,7 @@ index 60e9e5c219a470944609f36773b4d8effa019059..86922c0da6303e1c35b4f7cb92a751fb return GetCacheSizesQNX(); #elif defined(BENCHMARK_OS_QURT) || defined(__EMSCRIPTEN__) return std::vector(); -+#elif defined(__FRC_ROBORIO__) ++#elif defined(__WPILIB_ROBORIO__) + return std::vector(); #else return GetCacheSizesFromKVFS(); diff --git a/wpilibc/src/main/native/cpp/ExpansionHub.cpp b/wpilibc/src/main/native/cpp/ExpansionHub.cpp index 57a189e713..d737713f8c 100644 --- a/wpilibc/src/main/native/cpp/ExpansionHub.cpp +++ b/wpilibc/src/main/native/cpp/ExpansionHub.cpp @@ -43,7 +43,7 @@ class ExpansionHub::DataStore { }; std::shared_ptr ExpansionHub::GetForUsbId(int usbId) { - FRC_AssertMessage(usbId >= 0 && usbId < NumUsbPorts, "USB {} out of range", + WPILIB_AssertMessage(usbId >= 0 && usbId < NumUsbPorts, "USB {} out of range", usbId); std::scoped_lock lock{m_handleLock}; std::weak_ptr& weakStore = m_storeMap[usbId]; diff --git a/wpilibc/src/main/native/cpp/ExpansionHubMotor.cpp b/wpilibc/src/main/native/cpp/ExpansionHubMotor.cpp index de81506a75..2a21df3182 100644 --- a/wpilibc/src/main/native/cpp/ExpansionHubMotor.cpp +++ b/wpilibc/src/main/native/cpp/ExpansionHubMotor.cpp @@ -20,11 +20,11 @@ ExpansionHubMotor::ExpansionHubMotor(int usbId, int channel) m_channel{channel}, m_velocityPidConstants{usbId, channel, true}, m_positionPidConstants{usbId, channel, false} { - FRC_AssertMessage(channel >= 0 && channel < ExpansionHub::NumMotorPorts, + WPILIB_AssertMessage(channel >= 0 && channel < ExpansionHub::NumMotorPorts, "ExHub Motor Channel {} out of range", channel); if (!m_hub.CheckAndReserveMotor(channel)) { - throw FRC_MakeError(err::ResourceAlreadyAllocated, "Channel {}", channel); + throw WPILIB_MakeError(err::ResourceAlreadyAllocated, "Channel {}", channel); } m_hub.ReportUsage(fmt::format("ExHubServo[{}]", channel), "ExHubServo"); @@ -153,7 +153,7 @@ ExpansionHubPidConstants& ExpansionHubMotor::GetPositionPidConstants() { void ExpansionHubMotor::Follow(const ExpansionHubMotor& leader) { if (m_hub.GetUsbId() != leader.m_hub.GetUsbId()) { - throw FRC_MakeError(err::InvalidParameter, + throw WPILIB_MakeError(err::InvalidParameter, "Cannot follow motor on different hub"); } m_modePublisher.Set(kFollowerMode); diff --git a/wpilibc/src/main/native/cpp/ExpansionHubServo.cpp b/wpilibc/src/main/native/cpp/ExpansionHubServo.cpp index 786de57e2c..04ea224303 100644 --- a/wpilibc/src/main/native/cpp/ExpansionHubServo.cpp +++ b/wpilibc/src/main/native/cpp/ExpansionHubServo.cpp @@ -11,11 +11,11 @@ using namespace wpi; ExpansionHubServo::ExpansionHubServo(int usbId, int channel) : m_hub{usbId}, m_channel{channel} { - FRC_AssertMessage(channel >= 0 && channel < ExpansionHub::NumServoPorts, + WPILIB_AssertMessage(channel >= 0 && channel < ExpansionHub::NumServoPorts, "ExHub Servo Channel {} out of range", channel); if (!m_hub.CheckAndReserveServo(channel)) { - throw FRC_MakeError(err::ResourceAlreadyAllocated, "Channel {}", channel); + throw WPILIB_MakeError(err::ResourceAlreadyAllocated, "Channel {}", channel); } m_hub.ReportUsage(fmt::format("ExHubServo[{}]", channel), "ExHubServo"); @@ -97,7 +97,7 @@ wpi::units::degree_t ExpansionHubServo::GetServoAngleRange() { void ExpansionHubServo::SetPWMRange(wpi::units::microsecond_t minPwm, wpi::units::microsecond_t maxPwm) { if (maxPwm <= minPwm) { - throw FRC_MakeError(err::ParameterOutOfRange, + throw WPILIB_MakeError(err::ParameterOutOfRange, "Max PWM must be greater than Min PWM"); } m_minPwm = minPwm; @@ -109,7 +109,7 @@ void ExpansionHubServo::SetReversed(bool reversed) {} void ExpansionHubServo::SetAngleRange(wpi::units::degree_t minAngle, wpi::units::degree_t maxAngle) { if (maxAngle <= minAngle) { - throw FRC_MakeError(err::ParameterOutOfRange, + throw WPILIB_MakeError(err::ParameterOutOfRange, "Max angle must be greater than Min angle"); } m_minServoAngle = minAngle; diff --git a/wpilibc/src/main/native/cpp/counter/Tachometer.cpp b/wpilibc/src/main/native/cpp/counter/Tachometer.cpp index 180121e967..75dc55e50b 100644 --- a/wpilibc/src/main/native/cpp/counter/Tachometer.cpp +++ b/wpilibc/src/main/native/cpp/counter/Tachometer.cpp @@ -21,7 +21,7 @@ Tachometer::Tachometer(int channel, EdgeConfiguration configuration) m_handle = HAL_InitializeCounter( channel, configuration == EdgeConfiguration::kRisingEdge, stackTrace.c_str(), &status); - FRC_CheckErrorStatus(status, "{}", channel); + WPILIB_CheckErrorStatus(status, "{}", channel); HAL_ReportUsage("IO", channel, "Tachometer"); wpi::util::SendableRegistry::Add(this, "Tachometer", channel); @@ -31,7 +31,7 @@ void Tachometer::SetEdgeConfiguration(EdgeConfiguration configuration) { int32_t status = 0; bool rising = configuration == EdgeConfiguration::kRisingEdge; HAL_SetCounterEdgeConfiguration(m_handle, rising, &status); - FRC_CheckErrorStatus(status, "{}", m_channel); + WPILIB_CheckErrorStatus(status, "{}", m_channel); } wpi::units::hertz_t Tachometer::GetFrequency() const { @@ -45,7 +45,7 @@ wpi::units::hertz_t Tachometer::GetFrequency() const { wpi::units::second_t Tachometer::GetPeriod() const { int32_t status = 0; double period = HAL_GetCounterPeriod(m_handle, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); return wpi::units::second_t{period}; } @@ -76,14 +76,14 @@ wpi::units::revolutions_per_minute_t Tachometer::GetRevolutionsPerMinute() const bool Tachometer::GetStopped() const { int32_t status = 0; bool stopped = HAL_GetCounterStopped(m_handle, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); return stopped; } void Tachometer::SetMaxPeriod(wpi::units::second_t maxPeriod) { int32_t status = 0; HAL_SetCounterMaxPeriod(m_handle, maxPeriod.value(), &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); } void Tachometer::InitSendable(wpi::util::SendableBuilder& builder) { diff --git a/wpilibc/src/main/native/cpp/counter/UpDownCounter.cpp b/wpilibc/src/main/native/cpp/counter/UpDownCounter.cpp index 9aaef67aed..a3af24c72d 100644 --- a/wpilibc/src/main/native/cpp/counter/UpDownCounter.cpp +++ b/wpilibc/src/main/native/cpp/counter/UpDownCounter.cpp @@ -22,7 +22,7 @@ UpDownCounter::UpDownCounter(int channel, EdgeConfiguration configuration) m_handle = HAL_InitializeCounter( channel, configuration == EdgeConfiguration::kRisingEdge, stackTrace.c_str(), &status); - FRC_CheckErrorStatus(status, "{}", channel); + WPILIB_CheckErrorStatus(status, "{}", channel); Reset(); @@ -33,21 +33,21 @@ UpDownCounter::UpDownCounter(int channel, EdgeConfiguration configuration) int UpDownCounter::GetCount() const { int32_t status = 0; int val = HAL_GetCounter(m_handle, &status); - FRC_CheckErrorStatus(status, "{}", m_channel); + WPILIB_CheckErrorStatus(status, "{}", m_channel); return val; } void UpDownCounter::Reset() { int32_t status = 0; HAL_ResetCounter(m_handle, &status); - FRC_CheckErrorStatus(status, "{}", m_channel); + WPILIB_CheckErrorStatus(status, "{}", m_channel); } void UpDownCounter::SetEdgeConfiguration(EdgeConfiguration configuration) { int32_t status = 0; bool rising = configuration == EdgeConfiguration::kRisingEdge; HAL_SetCounterEdgeConfiguration(m_handle, rising, &status); - FRC_CheckErrorStatus(status, "{}", m_channel); + WPILIB_CheckErrorStatus(status, "{}", m_channel); } void UpDownCounter::InitSendable(wpi::util::SendableBuilder& builder) { diff --git a/wpilibc/src/main/native/cpp/driverstation/DriverStation.cpp b/wpilibc/src/main/native/cpp/driverstation/DriverStation.cpp index 6dc93e0607..26fcec7993 100644 --- a/wpilibc/src/main/native/cpp/driverstation/DriverStation.cpp +++ b/wpilibc/src/main/native/cpp/driverstation/DriverStation.cpp @@ -202,11 +202,11 @@ Instance::~Instance() { bool DriverStation::GetStickButton(int stick, int button) { if (stick < 0 || stick >= kJoystickPorts) { - FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); + WPILIB_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); return false; } if (button < 0 || button >= 64) { - FRC_ReportError(warn::BadJoystickIndex, "button {} out of range", button); + WPILIB_ReportError(warn::BadJoystickIndex, "button {} out of range", button); return false; } @@ -230,11 +230,11 @@ bool DriverStation::GetStickButton(int stick, int button) { std::optional DriverStation::GetStickButtonIfAvailable(int stick, int button) { if (stick < 0 || stick >= kJoystickPorts) { - FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); + WPILIB_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); return false; } if (button < 0 || button >= 64) { - FRC_ReportError(warn::BadJoystickIndex, "button {} out of range", button); + WPILIB_ReportError(warn::BadJoystickIndex, "button {} out of range", button); return false; } @@ -252,11 +252,11 @@ std::optional DriverStation::GetStickButtonIfAvailable(int stick, bool DriverStation::GetStickButtonPressed(int stick, int button) { if (stick < 0 || stick >= kJoystickPorts) { - FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); + WPILIB_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); return false; } if (button < 0 || button >= 64) { - FRC_ReportError(warn::BadJoystickIndex, "button {} out of range", button); + WPILIB_ReportError(warn::BadJoystickIndex, "button {} out of range", button); return false; } @@ -285,11 +285,11 @@ bool DriverStation::GetStickButtonPressed(int stick, int button) { bool DriverStation::GetStickButtonReleased(int stick, int button) { if (stick < 0 || stick >= kJoystickPorts) { - FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); + WPILIB_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); return false; } if (button < 0 || button >= 64) { - FRC_ReportError(warn::BadJoystickIndex, "button {} out of range", button); + WPILIB_ReportError(warn::BadJoystickIndex, "button {} out of range", button); return false; } @@ -318,11 +318,11 @@ bool DriverStation::GetStickButtonReleased(int stick, int button) { double DriverStation::GetStickAxis(int stick, int axis) { if (stick < 0 || stick >= kJoystickPorts) { - FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); + WPILIB_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); return 0.0; } if (axis < 0 || axis >= HAL_kMaxJoystickAxes) { - FRC_ReportError(warn::BadJoystickAxis, "axis {} out of range", axis); + WPILIB_ReportError(warn::BadJoystickAxis, "axis {} out of range", axis); return 0.0; } @@ -345,11 +345,11 @@ double DriverStation::GetStickAxis(int stick, int axis) { std::optional DriverStation::GetStickAxisIfAvailable(int stick, int axis) { if (stick < 0 || stick >= kJoystickPorts) { - FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); + WPILIB_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); return 0.0; } if (axis < 0 || axis >= HAL_kMaxJoystickAxes) { - FRC_ReportError(warn::BadJoystickAxis, "axis {} out of range", axis); + WPILIB_ReportError(warn::BadJoystickAxis, "axis {} out of range", axis); return 0.0; } @@ -367,11 +367,11 @@ std::optional DriverStation::GetStickAxisIfAvailable(int stick, DriverStation::POVDirection DriverStation::GetStickPOV(int stick, int pov) { if (stick < 0 || stick >= kJoystickPorts) { - FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); + WPILIB_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); return kCenter; } if (pov < 0 || pov >= HAL_kMaxJoystickPOVs) { - FRC_ReportError(warn::BadJoystickAxis, "POV {} out of range", pov); + WPILIB_ReportError(warn::BadJoystickAxis, "POV {} out of range", pov); return kCenter; } @@ -393,7 +393,7 @@ DriverStation::POVDirection DriverStation::GetStickPOV(int stick, int pov) { uint64_t DriverStation::GetStickButtons(int stick) { if (stick < 0 || stick >= kJoystickPorts) { - FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); + WPILIB_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); return 0; } @@ -409,7 +409,7 @@ int DriverStation::GetStickAxesMaximumIndex(int stick) { int DriverStation::GetStickAxesAvailable(int stick) { if (stick < 0 || stick >= kJoystickPorts) { - FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); + WPILIB_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); return 0; } @@ -425,7 +425,7 @@ int DriverStation::GetStickPOVsMaximumIndex(int stick) { int DriverStation::GetStickPOVsAvailable(int stick) { if (stick < 0 || stick >= kJoystickPorts) { - FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); + WPILIB_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); return 0; } @@ -441,7 +441,7 @@ int DriverStation::GetStickButtonsMaximumIndex(int stick) { uint64_t DriverStation::GetStickButtonsAvailable(int stick) { if (stick < 0 || stick >= kJoystickPorts) { - FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); + WPILIB_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); return 0; } @@ -453,7 +453,7 @@ uint64_t DriverStation::GetStickButtonsAvailable(int stick) { bool DriverStation::GetJoystickIsGamepad(int stick) { if (stick < 0 || stick >= kJoystickPorts) { - FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); + WPILIB_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); return false; } @@ -465,7 +465,7 @@ bool DriverStation::GetJoystickIsGamepad(int stick) { int DriverStation::GetJoystickType(int stick) { if (stick < 0 || stick >= kJoystickPorts) { - FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); + WPILIB_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); return -1; } @@ -477,7 +477,7 @@ int DriverStation::GetJoystickType(int stick) { std::string DriverStation::GetJoystickName(int stick) { if (stick < 0 || stick >= kJoystickPorts) { - FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); + WPILIB_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick); } HAL_JoystickDescriptor descriptor; @@ -632,7 +632,7 @@ wpi::units::second_t DriverStation::GetMatchTime() { double DriverStation::GetBatteryVoltage() { int32_t status = 0; double voltage = HAL_GetVinVoltage(&status); - FRC_CheckErrorStatus(status, "getVinVoltage"); + WPILIB_CheckErrorStatus(status, "getVinVoltage"); return voltage; } diff --git a/wpilibc/src/main/native/cpp/driverstation/GenericHID.cpp b/wpilibc/src/main/native/cpp/driverstation/GenericHID.cpp index a9f497f2e0..e73bc9dbf4 100644 --- a/wpilibc/src/main/native/cpp/driverstation/GenericHID.cpp +++ b/wpilibc/src/main/native/cpp/driverstation/GenericHID.cpp @@ -15,7 +15,7 @@ using namespace wpi; GenericHID::GenericHID(int port) { if (port < 0 || port >= DriverStation::kJoystickPorts) { - throw FRC_MakeError(warn::BadJoystickIndex, "port {} out of range", port); + throw WPILIB_MakeError(warn::BadJoystickIndex, "port {} out of range", port); } m_port = port; } diff --git a/wpilibc/src/main/native/cpp/event/EventLoop.cpp b/wpilibc/src/main/native/cpp/event/EventLoop.cpp index 03d31c1353..90df5a66d3 100644 --- a/wpilibc/src/main/native/cpp/event/EventLoop.cpp +++ b/wpilibc/src/main/native/cpp/event/EventLoop.cpp @@ -24,7 +24,7 @@ EventLoop::EventLoop() {} void EventLoop::Bind(wpi::util::unique_function action) { if (m_running) { - throw FRC_MakeError(err::Error, + throw WPILIB_MakeError(err::Error, "Cannot bind EventLoop while it is running"); } m_bindings.emplace_back(std::move(action)); @@ -39,7 +39,7 @@ void EventLoop::Poll() { void EventLoop::Clear() { if (m_running) { - throw FRC_MakeError(err::Error, + throw WPILIB_MakeError(err::Error, "Cannot clear EventLoop while it is running"); } m_bindings.clear(); diff --git a/wpilibc/src/main/native/cpp/hardware/accelerometer/AnalogAccelerometer.cpp b/wpilibc/src/main/native/cpp/hardware/accelerometer/AnalogAccelerometer.cpp index e350913b25..05024d7d2a 100644 --- a/wpilibc/src/main/native/cpp/hardware/accelerometer/AnalogAccelerometer.cpp +++ b/wpilibc/src/main/native/cpp/hardware/accelerometer/AnalogAccelerometer.cpp @@ -20,7 +20,7 @@ AnalogAccelerometer::AnalogAccelerometer(int channel) AnalogAccelerometer::AnalogAccelerometer(AnalogInput* channel) : m_analogInput(channel, wpi::util::NullDeleter()) { if (!channel) { - throw FRC_MakeError(err::NullParameter, "channel"); + throw WPILIB_MakeError(err::NullParameter, "channel"); } InitAccelerometer(); } @@ -28,7 +28,7 @@ AnalogAccelerometer::AnalogAccelerometer(AnalogInput* channel) AnalogAccelerometer::AnalogAccelerometer(std::shared_ptr channel) : m_analogInput(channel) { if (!channel) { - throw FRC_MakeError(err::NullParameter, "channel"); + throw WPILIB_MakeError(err::NullParameter, "channel"); } InitAccelerometer(); } diff --git a/wpilibc/src/main/native/cpp/hardware/bus/CAN.cpp b/wpilibc/src/main/native/cpp/hardware/bus/CAN.cpp index ab84e8831a..09cde472cd 100644 --- a/wpilibc/src/main/native/cpp/hardware/bus/CAN.cpp +++ b/wpilibc/src/main/native/cpp/hardware/bus/CAN.cpp @@ -22,7 +22,7 @@ CAN::CAN(int busId, int deviceId, int deviceManufacturer, int deviceType) { m_handle = HAL_InitializeCAN( busId, static_cast(deviceManufacturer), deviceId, static_cast(deviceType), &status); - FRC_CheckErrorStatus(status, "device id {} mfg {} type {}", deviceId, + WPILIB_CheckErrorStatus(status, "device id {} mfg {} type {}", deviceId, deviceManufacturer, deviceType); HAL_ReportUsage( @@ -33,20 +33,20 @@ CAN::CAN(int busId, int deviceId, int deviceManufacturer, int deviceType) { void CAN::WritePacket(int apiId, const HAL_CANMessage& message) { int32_t status = 0; HAL_WriteCANPacket(m_handle, apiId, &message, &status); - FRC_CheckErrorStatus(status, "WritePacket"); + WPILIB_CheckErrorStatus(status, "WritePacket"); } void CAN::WritePacketRepeating(int apiId, const HAL_CANMessage& message, int repeatMs) { int32_t status = 0; HAL_WriteCANPacketRepeating(m_handle, apiId, &message, repeatMs, &status); - FRC_CheckErrorStatus(status, "WritePacketRepeating"); + WPILIB_CheckErrorStatus(status, "WritePacketRepeating"); } void CAN::WriteRTRFrame(int apiId, const HAL_CANMessage& message) { int32_t status = 0; HAL_WriteCANRTRFrame(m_handle, apiId, &message, &status); - FRC_CheckErrorStatus(status, "WriteRTRFrame"); + WPILIB_CheckErrorStatus(status, "WriteRTRFrame"); } int CAN::WritePacketNoError(int apiId, const HAL_CANMessage& message) { @@ -71,7 +71,7 @@ int CAN::WriteRTRFrameNoError(int apiId, const HAL_CANMessage& message) { void CAN::StopPacketRepeating(int apiId) { int32_t status = 0; HAL_StopCANPacketRepeating(m_handle, apiId, &status); - FRC_CheckErrorStatus(status, "StopPacketRepeating"); + WPILIB_CheckErrorStatus(status, "StopPacketRepeating"); } bool CAN::ReadPacketNew(int apiId, HAL_CANReceiveMessage* data) { @@ -81,7 +81,7 @@ bool CAN::ReadPacketNew(int apiId, HAL_CANReceiveMessage* data) { return false; } if (status != 0) { - FRC_CheckErrorStatus(status, "ReadPacketNew"); + WPILIB_CheckErrorStatus(status, "ReadPacketNew"); return false; } else { return true; @@ -95,7 +95,7 @@ bool CAN::ReadPacketLatest(int apiId, HAL_CANReceiveMessage* data) { return false; } if (status != 0) { - FRC_CheckErrorStatus(status, "ReadPacketLatest"); + WPILIB_CheckErrorStatus(status, "ReadPacketLatest"); return false; } else { return true; @@ -111,7 +111,7 @@ bool CAN::ReadPacketTimeout(int apiId, int timeoutMs, return false; } if (status != 0) { - FRC_CheckErrorStatus(status, "ReadPacketTimeout"); + WPILIB_CheckErrorStatus(status, "ReadPacketTimeout"); return false; } else { return true; diff --git a/wpilibc/src/main/native/cpp/hardware/bus/I2C.cpp b/wpilibc/src/main/native/cpp/hardware/bus/I2C.cpp index 9c10fb2bb5..f616ad5d38 100644 --- a/wpilibc/src/main/native/cpp/hardware/bus/I2C.cpp +++ b/wpilibc/src/main/native/cpp/hardware/bus/I2C.cpp @@ -17,7 +17,7 @@ I2C::I2C(Port port, int deviceAddress) int32_t status = 0; HAL_InitializeI2C(m_port, &status); - FRC_CheckErrorStatus(status, "Port {}", static_cast(port)); + WPILIB_CheckErrorStatus(status, "Port {}", static_cast(port)); HAL_ReportUsage( fmt::format("I2C[{}][{}]", static_cast(port), deviceAddress), ""); @@ -60,10 +60,10 @@ bool I2C::WriteBulk(uint8_t* data, int count) { bool I2C::Read(int registerAddress, int count, uint8_t* buffer) { if (count < 1) { - throw FRC_MakeError(err::ParameterOutOfRange, "count {}", count); + throw WPILIB_MakeError(err::ParameterOutOfRange, "count {}", count); } if (!buffer) { - throw FRC_MakeError(err::NullParameter, "buffer"); + throw WPILIB_MakeError(err::NullParameter, "buffer"); } uint8_t regAddr = registerAddress; return Transaction(®Addr, sizeof(regAddr), buffer, count); @@ -71,10 +71,10 @@ bool I2C::Read(int registerAddress, int count, uint8_t* buffer) { bool I2C::ReadOnly(int count, uint8_t* buffer) { if (count < 1) { - throw FRC_MakeError(err::ParameterOutOfRange, "count {}", count); + throw WPILIB_MakeError(err::ParameterOutOfRange, "count {}", count); } if (!buffer) { - throw FRC_MakeError(err::NullParameter, "buffer"); + throw WPILIB_MakeError(err::NullParameter, "buffer"); } return HAL_ReadI2C(m_port, m_deviceAddress, buffer, count) < 0; } diff --git a/wpilibc/src/main/native/cpp/hardware/bus/SerialPort.cpp b/wpilibc/src/main/native/cpp/hardware/bus/SerialPort.cpp index 33c3b8b46d..7bf4b3d82c 100644 --- a/wpilibc/src/main/native/cpp/hardware/bus/SerialPort.cpp +++ b/wpilibc/src/main/native/cpp/hardware/bus/SerialPort.cpp @@ -19,15 +19,15 @@ SerialPort::SerialPort(int baudRate, Port port, int dataBits, m_portHandle = HAL_InitializeSerialPort(static_cast(port), &status); - FRC_CheckErrorStatus(status, "Port {}", static_cast(port)); + WPILIB_CheckErrorStatus(status, "Port {}", static_cast(port)); HAL_SetSerialBaudRate(m_portHandle, baudRate, &status); - FRC_CheckErrorStatus(status, "SetSerialBaudRate {}", baudRate); + WPILIB_CheckErrorStatus(status, "SetSerialBaudRate {}", baudRate); HAL_SetSerialDataBits(m_portHandle, dataBits, &status); - FRC_CheckErrorStatus(status, "SetSerialDataBits {}", dataBits); + WPILIB_CheckErrorStatus(status, "SetSerialDataBits {}", dataBits); HAL_SetSerialParity(m_portHandle, parity, &status); - FRC_CheckErrorStatus(status, "SetSerialParity {}", static_cast(parity)); + WPILIB_CheckErrorStatus(status, "SetSerialParity {}", static_cast(parity)); HAL_SetSerialStopBits(m_portHandle, stopBits, &status); - FRC_CheckErrorStatus(status, "SetSerialStopBits {}", + WPILIB_CheckErrorStatus(status, "SetSerialStopBits {}", static_cast(stopBits)); // Set the default timeout to 5 seconds. @@ -49,15 +49,15 @@ SerialPort::SerialPort(int baudRate, std::string_view portName, Port port, m_portHandle = HAL_InitializeSerialPortDirect(static_cast(port), std::string(portName).c_str(), &status); - FRC_CheckErrorStatus(status, "Port {}", static_cast(port)); + WPILIB_CheckErrorStatus(status, "Port {}", static_cast(port)); HAL_SetSerialBaudRate(m_portHandle, baudRate, &status); - FRC_CheckErrorStatus(status, "SetSerialBaudRate {}", baudRate); + WPILIB_CheckErrorStatus(status, "SetSerialBaudRate {}", baudRate); HAL_SetSerialDataBits(m_portHandle, dataBits, &status); - FRC_CheckErrorStatus(status, "SetSerialDataBits {}", dataBits); + WPILIB_CheckErrorStatus(status, "SetSerialDataBits {}", dataBits); HAL_SetSerialParity(m_portHandle, parity, &status); - FRC_CheckErrorStatus(status, "SetSerialParity {}", static_cast(parity)); + WPILIB_CheckErrorStatus(status, "SetSerialParity {}", static_cast(parity)); HAL_SetSerialStopBits(m_portHandle, stopBits, &status); - FRC_CheckErrorStatus(status, "SetSerialStopBits {}", + WPILIB_CheckErrorStatus(status, "SetSerialStopBits {}", static_cast(stopBits)); // Set the default timeout to 5 seconds. @@ -74,33 +74,33 @@ SerialPort::SerialPort(int baudRate, std::string_view portName, Port port, void SerialPort::SetFlowControl(SerialPort::FlowControl flowControl) { int32_t status = 0; HAL_SetSerialFlowControl(m_portHandle, flowControl, &status); - FRC_CheckErrorStatus(status, "SetFlowControl {}", + WPILIB_CheckErrorStatus(status, "SetFlowControl {}", static_cast(flowControl)); } void SerialPort::EnableTermination(char terminator) { int32_t status = 0; HAL_EnableSerialTermination(m_portHandle, terminator, &status); - FRC_CheckErrorStatus(status, "EnableTermination {}", terminator); + WPILIB_CheckErrorStatus(status, "EnableTermination {}", terminator); } void SerialPort::DisableTermination() { int32_t status = 0; HAL_DisableSerialTermination(m_portHandle, &status); - FRC_CheckErrorStatus(status, "DisableTermination"); + WPILIB_CheckErrorStatus(status, "DisableTermination"); } int SerialPort::GetBytesReceived() { int32_t status = 0; int retVal = HAL_GetSerialBytesReceived(m_portHandle, &status); - FRC_CheckErrorStatus(status, "GetBytesReceived"); + WPILIB_CheckErrorStatus(status, "GetBytesReceived"); return retVal; } int SerialPort::Read(char* buffer, int count) { int32_t status = 0; int retVal = HAL_ReadSerial(m_portHandle, buffer, count, &status); - FRC_CheckErrorStatus(status, "Read"); + WPILIB_CheckErrorStatus(status, "Read"); return retVal; } @@ -112,42 +112,42 @@ int SerialPort::Write(std::string_view buffer) { int32_t status = 0; int retVal = HAL_WriteSerial(m_portHandle, buffer.data(), buffer.size(), &status); - FRC_CheckErrorStatus(status, "Write"); + WPILIB_CheckErrorStatus(status, "Write"); return retVal; } void SerialPort::SetTimeout(wpi::units::second_t timeout) { int32_t status = 0; HAL_SetSerialTimeout(m_portHandle, timeout.value(), &status); - FRC_CheckErrorStatus(status, "SetTimeout"); + WPILIB_CheckErrorStatus(status, "SetTimeout"); } void SerialPort::SetReadBufferSize(int size) { int32_t status = 0; HAL_SetSerialReadBufferSize(m_portHandle, size, &status); - FRC_CheckErrorStatus(status, "SetReadBufferSize {}", size); + WPILIB_CheckErrorStatus(status, "SetReadBufferSize {}", size); } void SerialPort::SetWriteBufferSize(int size) { int32_t status = 0; HAL_SetSerialWriteBufferSize(m_portHandle, size, &status); - FRC_CheckErrorStatus(status, "SetWriteBufferSize {}", size); + WPILIB_CheckErrorStatus(status, "SetWriteBufferSize {}", size); } void SerialPort::SetWriteBufferMode(SerialPort::WriteBufferMode mode) { int32_t status = 0; HAL_SetSerialWriteMode(m_portHandle, mode, &status); - FRC_CheckErrorStatus(status, "SetWriteBufferMode {}", static_cast(mode)); + WPILIB_CheckErrorStatus(status, "SetWriteBufferMode {}", static_cast(mode)); } void SerialPort::Flush() { int32_t status = 0; HAL_FlushSerial(m_portHandle, &status); - FRC_CheckErrorStatus(status, "Flush"); + WPILIB_CheckErrorStatus(status, "Flush"); } void SerialPort::Reset() { int32_t status = 0; HAL_ClearSerial(m_portHandle, &status); - FRC_CheckErrorStatus(status, "Reset"); + WPILIB_CheckErrorStatus(status, "Reset"); } diff --git a/wpilibc/src/main/native/cpp/hardware/discrete/AnalogInput.cpp b/wpilibc/src/main/native/cpp/hardware/discrete/AnalogInput.cpp index 88672b7195..96433efd32 100644 --- a/wpilibc/src/main/native/cpp/hardware/discrete/AnalogInput.cpp +++ b/wpilibc/src/main/native/cpp/hardware/discrete/AnalogInput.cpp @@ -21,14 +21,14 @@ using namespace wpi; AnalogInput::AnalogInput(int channel) { if (!SensorUtil::CheckAnalogInputChannel(channel)) { - throw FRC_MakeError(err::ChannelIndexOutOfRange, "Channel {}", channel); + throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Channel {}", channel); } m_channel = channel; int32_t status = 0; std::string stackTrace = wpi::util::GetStackTrace(1); m_port = HAL_InitializeAnalogInputPort(channel, stackTrace.c_str(), &status); - FRC_CheckErrorStatus(status, "Channel {}", channel); + WPILIB_CheckErrorStatus(status, "Channel {}", channel); HAL_ReportUsage("IO", channel, "AnalogInput"); @@ -38,28 +38,28 @@ AnalogInput::AnalogInput(int channel) { int AnalogInput::GetValue() const { int32_t status = 0; int value = HAL_GetAnalogValue(m_port, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); return value; } int AnalogInput::GetAverageValue() const { int32_t status = 0; int value = HAL_GetAnalogAverageValue(m_port, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); return value; } double AnalogInput::GetVoltage() const { int32_t status = 0; double voltage = HAL_GetAnalogVoltage(m_port, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); return voltage; } double AnalogInput::GetAverageVoltage() const { int32_t status = 0; double voltage = HAL_GetAnalogAverageVoltage(m_port, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); return voltage; } @@ -70,53 +70,53 @@ int AnalogInput::GetChannel() const { void AnalogInput::SetAverageBits(int bits) { int32_t status = 0; HAL_SetAnalogAverageBits(m_port, bits, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); } int AnalogInput::GetAverageBits() const { int32_t status = 0; int averageBits = HAL_GetAnalogAverageBits(m_port, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); return averageBits; } void AnalogInput::SetOversampleBits(int bits) { int32_t status = 0; HAL_SetAnalogOversampleBits(m_port, bits, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); } int AnalogInput::GetOversampleBits() const { int32_t status = 0; int oversampleBits = HAL_GetAnalogOversampleBits(m_port, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); return oversampleBits; } int AnalogInput::GetLSBWeight() const { int32_t status = 0; int lsbWeight = HAL_GetAnalogLSBWeight(m_port, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); return lsbWeight; } int AnalogInput::GetOffset() const { int32_t status = 0; int offset = HAL_GetAnalogOffset(m_port, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); return offset; } void AnalogInput::SetSampleRate(double samplesPerSecond) { int32_t status = 0; HAL_SetAnalogSampleRate(samplesPerSecond, &status); - FRC_CheckErrorStatus(status, "SetSampleRate"); + WPILIB_CheckErrorStatus(status, "SetSampleRate"); } double AnalogInput::GetSampleRate() { int32_t status = 0; double sampleRate = HAL_GetAnalogSampleRate(&status); - FRC_CheckErrorStatus(status, "GetSampleRate"); + WPILIB_CheckErrorStatus(status, "GetSampleRate"); return sampleRate; } diff --git a/wpilibc/src/main/native/cpp/hardware/discrete/DigitalInput.cpp b/wpilibc/src/main/native/cpp/hardware/discrete/DigitalInput.cpp index 8e4c0554a3..04739bc8ec 100644 --- a/wpilibc/src/main/native/cpp/hardware/discrete/DigitalInput.cpp +++ b/wpilibc/src/main/native/cpp/hardware/discrete/DigitalInput.cpp @@ -20,14 +20,14 @@ using namespace wpi; DigitalInput::DigitalInput(int channel) { if (!SensorUtil::CheckDigitalChannel(channel)) { - throw FRC_MakeError(err::ChannelIndexOutOfRange, "Channel {}", channel); + throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Channel {}", channel); } m_channel = channel; int32_t status = 0; std::string stackTrace = wpi::util::GetStackTrace(1); m_handle = HAL_InitializeDIOPort(channel, true, stackTrace.c_str(), &status); - FRC_CheckErrorStatus(status, "Channel {}", channel); + WPILIB_CheckErrorStatus(status, "Channel {}", channel); HAL_ReportUsage("IO", channel, "DigitalInput"); wpi::util::SendableRegistry::Add(this, "DigitalInput", channel); @@ -36,7 +36,7 @@ DigitalInput::DigitalInput(int channel) { bool DigitalInput::Get() const { int32_t status = 0; bool value = HAL_GetDIO(m_handle, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); return value; } diff --git a/wpilibc/src/main/native/cpp/hardware/discrete/DigitalOutput.cpp b/wpilibc/src/main/native/cpp/hardware/discrete/DigitalOutput.cpp index 40725aeaf1..8b7615c5f7 100644 --- a/wpilibc/src/main/native/cpp/hardware/discrete/DigitalOutput.cpp +++ b/wpilibc/src/main/native/cpp/hardware/discrete/DigitalOutput.cpp @@ -21,14 +21,14 @@ using namespace wpi; DigitalOutput::DigitalOutput(int channel) { m_pwmGenerator = HAL_kInvalidHandle; if (!SensorUtil::CheckDigitalChannel(channel)) { - throw FRC_MakeError(err::ChannelIndexOutOfRange, "Channel {}", channel); + throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Channel {}", channel); } m_channel = channel; int32_t status = 0; std::string stackTrace = wpi::util::GetStackTrace(1); m_handle = HAL_InitializeDIOPort(channel, false, stackTrace.c_str(), &status); - FRC_CheckErrorStatus(status, "Channel {}", channel); + WPILIB_CheckErrorStatus(status, "Channel {}", channel); HAL_ReportUsage("IO", channel, "DigitalOutput"); wpi::util::SendableRegistry::Add(this, "DigitalOutput", channel); @@ -48,13 +48,13 @@ DigitalOutput::~DigitalOutput() { void DigitalOutput::Set(bool value) { int32_t status = 0; HAL_SetDIO(m_handle, value, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); } bool DigitalOutput::Get() const { int32_t status = 0; bool val = HAL_GetDIO(m_handle, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); return val; } @@ -65,20 +65,20 @@ int DigitalOutput::GetChannel() const { void DigitalOutput::Pulse(wpi::units::second_t pulseLength) { int32_t status = 0; HAL_Pulse(m_handle, pulseLength.value(), &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); } bool DigitalOutput::IsPulsing() const { int32_t status = 0; bool value = HAL_IsPulsing(m_handle, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); return value; } void DigitalOutput::SetPWMRate(double rate) { int32_t status = 0; HAL_SetDigitalPWMRate(rate, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); } void DigitalOutput::EnablePPS(double dutyCycle) { @@ -89,13 +89,13 @@ void DigitalOutput::EnablePPS(double dutyCycle) { int32_t status = 0; m_pwmGenerator = HAL_AllocateDigitalPWM(&status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); HAL_SetDigitalPWMPPS(m_pwmGenerator, dutyCycle, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); HAL_SetDigitalPWMOutputChannel(m_pwmGenerator, m_channel, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); } void DigitalOutput::EnablePWM(double initialDutyCycle) { @@ -106,13 +106,13 @@ void DigitalOutput::EnablePWM(double initialDutyCycle) { int32_t status = 0; m_pwmGenerator = HAL_AllocateDigitalPWM(&status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); HAL_SetDigitalPWMDutyCycle(m_pwmGenerator, initialDutyCycle, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); HAL_SetDigitalPWMOutputChannel(m_pwmGenerator, m_channel, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); } void DigitalOutput::DisablePWM() { @@ -125,7 +125,7 @@ void DigitalOutput::DisablePWM() { // Disable the output by routing to a dead bit. HAL_SetDigitalPWMOutputChannel(m_pwmGenerator, SensorUtil::GetNumDigitalChannels(), &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); HAL_FreeDigitalPWM(m_pwmGenerator); @@ -135,7 +135,7 @@ void DigitalOutput::DisablePWM() { void DigitalOutput::UpdateDutyCycle(double dutyCycle) { int32_t status = 0; HAL_SetDigitalPWMDutyCycle(m_pwmGenerator, dutyCycle, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); } void DigitalOutput::SetSimDevice(HAL_SimDeviceHandle device) { diff --git a/wpilibc/src/main/native/cpp/hardware/discrete/PWM.cpp b/wpilibc/src/main/native/cpp/hardware/discrete/PWM.cpp index eb589eb98b..0c9c5d42dc 100644 --- a/wpilibc/src/main/native/cpp/hardware/discrete/PWM.cpp +++ b/wpilibc/src/main/native/cpp/hardware/discrete/PWM.cpp @@ -20,13 +20,13 @@ using namespace wpi; PWM::PWM(int channel, bool registerSendable) { if (!SensorUtil::CheckPWMChannel(channel)) { - throw FRC_MakeError(err::ChannelIndexOutOfRange, "Channel {}", channel); + throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Channel {}", channel); } auto stack = wpi::util::GetStackTrace(1); int32_t status = 0; m_handle = HAL_InitializePWMPort(channel, stack.c_str(), &status); - FRC_CheckErrorStatus(status, "Channel {}", channel); + WPILIB_CheckErrorStatus(status, "Channel {}", channel); m_channel = channel; @@ -47,13 +47,13 @@ PWM::~PWM() { void PWM::SetPulseTime(wpi::units::microsecond_t time) { int32_t status = 0; HAL_SetPWMPulseTimeMicroseconds(m_handle, time.value(), &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); } wpi::units::microsecond_t PWM::GetPulseTime() const { int32_t status = 0; double value = HAL_GetPWMPulseTimeMicroseconds(m_handle, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); return wpi::units::microsecond_t{value}; } @@ -61,7 +61,7 @@ wpi::units::microsecond_t PWM::GetPulseTime() const { void PWM::SetDisabled() { int32_t status = 0; HAL_SetPWMPulseTimeMicroseconds(m_handle, 0, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); } void PWM::SetOutputPeriod(OutputPeriod mult) { @@ -81,11 +81,11 @@ void PWM::SetOutputPeriod(OutputPeriod mult) { &status); // Don't squelch any outputs break; default: - throw FRC_MakeError(err::InvalidParameter, "OutputPeriod value {}", + throw WPILIB_MakeError(err::InvalidParameter, "OutputPeriod value {}", static_cast(mult)); } - FRC_CheckErrorStatus(status, "Channel {}", m_channel); + WPILIB_CheckErrorStatus(status, "Channel {}", m_channel); } int PWM::GetChannel() const { diff --git a/wpilibc/src/main/native/cpp/hardware/imu/OnboardIMU.cpp b/wpilibc/src/main/native/cpp/hardware/imu/OnboardIMU.cpp index 3c99e038ac..174e62f7b4 100644 --- a/wpilibc/src/main/native/cpp/hardware/imu/OnboardIMU.cpp +++ b/wpilibc/src/main/native/cpp/hardware/imu/OnboardIMU.cpp @@ -53,7 +53,7 @@ wpi::math::Quaternion OnboardIMU::GetQuaternion() { HAL_Quaternion val; int32_t status = 0; HAL_GetIMUQuaternion(&val, &status); - FRC_CheckErrorStatus(status, "Onboard IMU"); + WPILIB_CheckErrorStatus(status, "Onboard IMU"); return wpi::math::Quaternion{val.w, val.x, val.y, val.z}; } @@ -71,7 +71,7 @@ wpi::units::radian_t OnboardIMU::GetAngleX() { HAL_GetIMUEulerAnglesPortrait(&val, &status); break; } - FRC_CheckErrorStatus(status, "Onboard IMU"); + WPILIB_CheckErrorStatus(status, "Onboard IMU"); return wpi::units::radian_t{val.x}; } @@ -89,7 +89,7 @@ wpi::units::radian_t OnboardIMU::GetAngleY() { HAL_GetIMUEulerAnglesPortrait(&val, &status); break; } - FRC_CheckErrorStatus(status, "Onboard IMU"); + WPILIB_CheckErrorStatus(status, "Onboard IMU"); return wpi::units::radian_t{val.y}; } @@ -107,7 +107,7 @@ wpi::units::radian_t OnboardIMU::GetAngleZ() { HAL_GetIMUEulerAnglesPortrait(&val, &status); break; } - FRC_CheckErrorStatus(status, "Onboard IMU"); + WPILIB_CheckErrorStatus(status, "Onboard IMU"); return wpi::units::radian_t{val.z}; } @@ -115,7 +115,7 @@ wpi::units::radians_per_second_t OnboardIMU::GetGyroRateX() { HAL_GyroRate3d val; int32_t status = 0; HAL_GetIMUGyroRates(&val, &status); - FRC_CheckErrorStatus(status, "Onboard IMU"); + WPILIB_CheckErrorStatus(status, "Onboard IMU"); return wpi::units::radians_per_second_t{val.x}; } @@ -123,7 +123,7 @@ wpi::units::radians_per_second_t OnboardIMU::GetGyroRateY() { HAL_GyroRate3d val; int32_t status = 0; HAL_GetIMUGyroRates(&val, &status); - FRC_CheckErrorStatus(status, "Onboard IMU"); + WPILIB_CheckErrorStatus(status, "Onboard IMU"); return wpi::units::radians_per_second_t{val.y}; } @@ -131,7 +131,7 @@ wpi::units::radians_per_second_t OnboardIMU::GetGyroRateZ() { HAL_GyroRate3d val; int32_t status = 0; HAL_GetIMUGyroRates(&val, &status); - FRC_CheckErrorStatus(status, "Onboard IMU"); + WPILIB_CheckErrorStatus(status, "Onboard IMU"); return wpi::units::radians_per_second_t{val.z}; } @@ -139,7 +139,7 @@ wpi::units::meters_per_second_squared_t OnboardIMU::GetAccelX() { HAL_Acceleration3d val; int32_t status = 0; HAL_GetIMUAcceleration(&val, &status); - FRC_CheckErrorStatus(status, "Onboard IMU"); + WPILIB_CheckErrorStatus(status, "Onboard IMU"); return wpi::units::meters_per_second_squared_t{val.x}; } @@ -147,7 +147,7 @@ wpi::units::meters_per_second_squared_t OnboardIMU::GetAccelY() { HAL_Acceleration3d val; int32_t status = 0; HAL_GetIMUAcceleration(&val, &status); - FRC_CheckErrorStatus(status, "Onboard IMU"); + WPILIB_CheckErrorStatus(status, "Onboard IMU"); return wpi::units::meters_per_second_squared_t{val.x}; } @@ -155,6 +155,6 @@ wpi::units::meters_per_second_squared_t OnboardIMU::GetAccelZ() { HAL_Acceleration3d val; int32_t status = 0; HAL_GetIMUAcceleration(&val, &status); - FRC_CheckErrorStatus(status, "Onboard IMU"); + WPILIB_CheckErrorStatus(status, "Onboard IMU"); return wpi::units::meters_per_second_squared_t{val.x}; } diff --git a/wpilibc/src/main/native/cpp/hardware/led/AddressableLED.cpp b/wpilibc/src/main/native/cpp/hardware/led/AddressableLED.cpp index 175ecdfcb9..46a898c5d1 100644 --- a/wpilibc/src/main/native/cpp/hardware/led/AddressableLED.cpp +++ b/wpilibc/src/main/native/cpp/hardware/led/AddressableLED.cpp @@ -19,13 +19,13 @@ using namespace wpi; AddressableLED::AddressableLED(int channel) : m_channel{channel} { if (!SensorUtil::CheckDigitalChannel(channel)) { - throw FRC_MakeError(err::ChannelIndexOutOfRange, "Channel {}", channel); + throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Channel {}", channel); } int32_t status = 0; auto stack = wpi::util::GetStackTrace(1); m_handle = HAL_InitializeAddressableLED(channel, stack.c_str(), &status); - FRC_CheckErrorStatus(status, "Channel {}", channel); + WPILIB_CheckErrorStatus(status, "Channel {}", channel); HAL_ReportUsage("IO", channel, "AddressableLED"); } @@ -38,14 +38,14 @@ void AddressableLED::SetStart(int start) { m_start = start; int32_t status = 0; HAL_SetAddressableLEDStart(m_handle, start, &status); - FRC_CheckErrorStatus(status, "Channel {} start {}", m_channel, start); + WPILIB_CheckErrorStatus(status, "Channel {} start {}", m_channel, start); } void AddressableLED::SetLength(int length) { m_length = length; int32_t status = 0; HAL_SetAddressableLEDLength(m_handle, length, &status); - FRC_CheckErrorStatus(status, "Channel {} length {}", m_channel, length); + WPILIB_CheckErrorStatus(status, "Channel {} length {}", m_channel, length); } static_assert(sizeof(AddressableLED::LEDData) == sizeof(HAL_AddressableLEDData), @@ -57,7 +57,7 @@ void AddressableLED::SetData(std::span ledData) { m_start, std::min(static_cast(m_length), ledData.size()), static_cast(m_colorOrder), ledData.data(), &status); - FRC_CheckErrorStatus(status, "Port {}", m_channel); + WPILIB_CheckErrorStatus(status, "Port {}", m_channel); } void AddressableLED::SetData(std::initializer_list ledData) { @@ -71,7 +71,7 @@ void AddressableLED::SetGlobalData(int start, ColorOrder colorOrder, start, ledData.size(), static_cast(colorOrder), ledData.data(), &status); - FRC_CheckErrorStatus(status, ""); + WPILIB_CheckErrorStatus(status, ""); } void AddressableLED::LEDData::SetHSV(int h, int s, int v) { diff --git a/wpilibc/src/main/native/cpp/hardware/motor/MotorSafety.cpp b/wpilibc/src/main/native/cpp/hardware/motor/MotorSafety.cpp index 4191dca54f..93c21dc790 100644 --- a/wpilibc/src/main/native/cpp/hardware/motor/MotorSafety.cpp +++ b/wpilibc/src/main/native/cpp/hardware/motor/MotorSafety.cpp @@ -158,7 +158,7 @@ void MotorSafety::Check() { } if (stopTime < Timer::GetFPGATimestamp()) { - FRC_ReportError(err::Timeout, + WPILIB_ReportError(err::Timeout, "{}... Output not updated often enough. See " "https://docs.wpilib.org/motorsafety for more information.", GetDescription()); @@ -168,7 +168,7 @@ void MotorSafety::Check() { } catch (wpi::RuntimeError& e) { e.Report(); } catch (std::exception& e) { - FRC_ReportError(err::Error, "{} StopMotor threw unexpected exception: {}", + WPILIB_ReportError(err::Error, "{} StopMotor threw unexpected exception: {}", GetDescription(), e.what()); } } diff --git a/wpilibc/src/main/native/cpp/hardware/pneumatic/Compressor.cpp b/wpilibc/src/main/native/cpp/hardware/pneumatic/Compressor.cpp index 6cd10ed747..a71800de39 100644 --- a/wpilibc/src/main/native/cpp/hardware/pneumatic/Compressor.cpp +++ b/wpilibc/src/main/native/cpp/hardware/pneumatic/Compressor.cpp @@ -16,7 +16,7 @@ Compressor::Compressor(int busId, int module, PneumaticsModuleType moduleType) : m_module{PneumaticsBase::GetForType(busId, module, moduleType)}, m_moduleType{moduleType} { if (!m_module->ReserveCompressor()) { - throw FRC_MakeError(err::ResourceAlreadyAllocated, "{}", module); + throw WPILIB_MakeError(err::ResourceAlreadyAllocated, "{}", module); } m_module->EnableCompressorDigital(); diff --git a/wpilibc/src/main/native/cpp/hardware/pneumatic/DoubleSolenoid.cpp b/wpilibc/src/main/native/cpp/hardware/pneumatic/DoubleSolenoid.cpp index adc46f6298..008a0763d9 100644 --- a/wpilibc/src/main/native/cpp/hardware/pneumatic/DoubleSolenoid.cpp +++ b/wpilibc/src/main/native/cpp/hardware/pneumatic/DoubleSolenoid.cpp @@ -22,11 +22,11 @@ DoubleSolenoid::DoubleSolenoid(int busId, int module, m_forwardChannel{forwardChannel}, m_reverseChannel{reverseChannel} { if (!m_module->CheckSolenoidChannel(m_forwardChannel)) { - throw FRC_MakeError(err::ChannelIndexOutOfRange, "Channel {}", + throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Channel {}", m_forwardChannel); } if (!m_module->CheckSolenoidChannel(m_reverseChannel)) { - throw FRC_MakeError(err::ChannelIndexOutOfRange, "Channel {}", + throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Channel {}", m_reverseChannel); } @@ -37,13 +37,13 @@ DoubleSolenoid::DoubleSolenoid(int busId, int module, int allocMask = m_module->CheckAndReserveSolenoids(m_mask); if (allocMask != 0) { if (allocMask == m_mask) { - throw FRC_MakeError(err::ResourceAlreadyAllocated, "Channels {} and {}", + throw WPILIB_MakeError(err::ResourceAlreadyAllocated, "Channels {} and {}", m_forwardChannel, m_reverseChannel); } else if (allocMask == m_forwardMask) { - throw FRC_MakeError(err::ResourceAlreadyAllocated, "Channel {}", + throw WPILIB_MakeError(err::ResourceAlreadyAllocated, "Channel {}", m_forwardChannel); } else { - throw FRC_MakeError(err::ResourceAlreadyAllocated, "Channel {}", + throw WPILIB_MakeError(err::ResourceAlreadyAllocated, "Channel {}", m_reverseChannel); } } diff --git a/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticHub.cpp b/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticHub.cpp index e394842586..caf0009d36 100644 --- a/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticHub.cpp +++ b/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticHub.cpp @@ -48,7 +48,7 @@ std::unique_ptr> std::weak_ptr& PneumaticHub::GetDataStore(int busId, int module) { int32_t numBuses = HAL_GetNumCanBuses(); - FRC_AssertMessage(busId >= 0 && busId < numBuses, + WPILIB_AssertMessage(busId >= 0 && busId < numBuses, "Bus {} out of range. Must be [0-{}).", busId, numBuses); if (!m_handleMaps) { m_handleMaps = std::make_unique< @@ -63,7 +63,7 @@ class PneumaticHub::DataStore { int32_t status = 0; HAL_REVPHHandle handle = HAL_InitializeREVPH(busId, module, stackTrace, &status); - FRC_CheckErrorStatus(status, "Module {}", module); + WPILIB_CheckErrorStatus(status, "Module {}", module); m_moduleObject = PneumaticHub{busId, handle, module}; m_moduleObject.m_dataStore = std::shared_ptr{this, wpi::util::NullDeleter()}; @@ -72,7 +72,7 @@ class PneumaticHub::DataStore { // Check PH firmware version if (version.FirmwareMajor > 0 && version.FirmwareMajor < 22) { - throw FRC_MakeError( + throw WPILIB_MakeError( err::AssertionFailure, "The Pneumatic Hub has firmware version {}.{}.{}, and must be " "updated to version 2022.0.0 or later using the REV Hardware Client", @@ -117,36 +117,36 @@ PneumaticHub::PneumaticHub(int /* busId */, HAL_REVPHHandle handle, int module) bool PneumaticHub::GetCompressor() const { int32_t status = 0; auto result = HAL_GetREVPHCompressor(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return result; } void PneumaticHub::DisableCompressor() { int32_t status = 0; HAL_SetREVPHClosedLoopControlDisabled(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); } void PneumaticHub::EnableCompressorDigital() { int32_t status = 0; HAL_SetREVPHClosedLoopControlDigital(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); } void PneumaticHub::EnableCompressorAnalog( wpi::units::pounds_per_square_inch_t minPressure, wpi::units::pounds_per_square_inch_t maxPressure) { if (minPressure >= maxPressure) { - throw FRC_MakeError(err::InvalidParameter, + throw WPILIB_MakeError(err::InvalidParameter, "maxPressure must be greater than minPressure"); } if (minPressure < 0_psi || minPressure > 120_psi) { - throw FRC_MakeError(err::ParameterOutOfRange, + throw WPILIB_MakeError(err::ParameterOutOfRange, "minPressure must be between 0 and 120 PSI, got {}", minPressure); } if (maxPressure < 0_psi || maxPressure > 120_psi) { - throw FRC_MakeError(err::ParameterOutOfRange, + throw WPILIB_MakeError(err::ParameterOutOfRange, "maxPressure must be between 0 and 120 PSI, got {}", maxPressure); } @@ -160,23 +160,23 @@ void PneumaticHub::EnableCompressorAnalog( int32_t status = 0; HAL_SetREVPHClosedLoopControlAnalog(m_handle, minAnalogVoltage.value(), maxAnalogVoltage.value(), &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); } void PneumaticHub::EnableCompressorHybrid( wpi::units::pounds_per_square_inch_t minPressure, wpi::units::pounds_per_square_inch_t maxPressure) { if (minPressure >= maxPressure) { - throw FRC_MakeError(err::InvalidParameter, + throw WPILIB_MakeError(err::InvalidParameter, "maxPressure must be greater than minPressure"); } if (minPressure < 0_psi || minPressure > 120_psi) { - throw FRC_MakeError(err::ParameterOutOfRange, + throw WPILIB_MakeError(err::ParameterOutOfRange, "minPressure must be between 0 and 120 PSI, got {}", minPressure); } if (maxPressure < 0_psi || maxPressure > 120_psi) { - throw FRC_MakeError(err::ParameterOutOfRange, + throw WPILIB_MakeError(err::ParameterOutOfRange, "maxPressure must be between 0 and 120 PSI, got {}", maxPressure); } @@ -190,40 +190,40 @@ void PneumaticHub::EnableCompressorHybrid( int32_t status = 0; HAL_SetREVPHClosedLoopControlHybrid(m_handle, minAnalogVoltage.value(), maxAnalogVoltage.value(), &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); } CompressorConfigType PneumaticHub::GetCompressorConfigType() const { int32_t status = 0; auto result = HAL_GetREVPHCompressorConfig(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return static_cast(result); } bool PneumaticHub::GetPressureSwitch() const { int32_t status = 0; auto result = HAL_GetREVPHPressureSwitch(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return result; } wpi::units::ampere_t PneumaticHub::GetCompressorCurrent() const { int32_t status = 0; auto result = HAL_GetREVPHCompressorCurrent(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return wpi::units::ampere_t{result}; } void PneumaticHub::SetSolenoids(int mask, int values) { int32_t status = 0; HAL_SetREVPHSolenoids(m_handle, mask, values, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); } int PneumaticHub::GetSolenoids() const { int32_t status = 0; auto result = HAL_GetREVPHSolenoids(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return result; } @@ -234,7 +234,7 @@ int PneumaticHub::GetModuleNumber() const { int PneumaticHub::GetSolenoidDisabledList() const { int32_t status = 0; auto result = HAL_GetREVPHSolenoidDisabledList(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return result; } @@ -242,7 +242,7 @@ void PneumaticHub::FireOneShot(int index) { int32_t status = 0; HAL_FireREVPHOneShot(m_handle, index, m_dataStore->m_oneShotDurMs[index].value(), &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); } void PneumaticHub::SetOneShotDuration(int index, wpi::units::second_t duration) { @@ -287,7 +287,7 @@ PneumaticHub::Version PneumaticHub::GetVersion() const { HAL_REVPHVersion halVersions; std::memset(&halVersions, 0, sizeof(halVersions)); HAL_GetREVPHVersion(m_handle, &halVersions, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); PneumaticHub::Version versions; static_assert(sizeof(halVersions) == sizeof(versions)); static_assert(std::is_standard_layout_v); @@ -301,7 +301,7 @@ PneumaticHub::Faults PneumaticHub::GetFaults() const { HAL_REVPHFaults halFaults; std::memset(&halFaults, 0, sizeof(halFaults)); HAL_GetREVPHFaults(m_handle, &halFaults, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); PneumaticHub::Faults faults; static_assert(sizeof(halFaults) == sizeof(faults)); static_assert(std::is_standard_layout_v); @@ -315,7 +315,7 @@ PneumaticHub::StickyFaults PneumaticHub::GetStickyFaults() const { HAL_REVPHStickyFaults halStickyFaults; std::memset(&halStickyFaults, 0, sizeof(halStickyFaults)); HAL_GetREVPHStickyFaults(m_handle, &halStickyFaults, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); PneumaticHub::StickyFaults stickyFaults; static_assert(sizeof(halStickyFaults) == sizeof(stickyFaults)); static_assert(std::is_standard_layout_v); @@ -359,7 +359,7 @@ bool PneumaticHub::Faults::GetChannelFault(int channel) const { case 15: return Channel15Fault != 0; default: - throw FRC_MakeError(err::ChannelIndexOutOfRange, + throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Pneumatics fault channel out of bounds!"); } } @@ -367,50 +367,50 @@ bool PneumaticHub::Faults::GetChannelFault(int channel) const { void PneumaticHub::ClearStickyFaults() { int32_t status = 0; HAL_ClearREVPHStickyFaults(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); } wpi::units::volt_t PneumaticHub::GetInputVoltage() const { int32_t status = 0; auto voltage = HAL_GetREVPHVoltage(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return wpi::units::volt_t{voltage}; } wpi::units::volt_t PneumaticHub::Get5VRegulatedVoltage() const { int32_t status = 0; auto voltage = HAL_GetREVPH5VVoltage(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return wpi::units::volt_t{voltage}; } wpi::units::ampere_t PneumaticHub::GetSolenoidsTotalCurrent() const { int32_t status = 0; auto current = HAL_GetREVPHSolenoidCurrent(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return wpi::units::ampere_t{current}; } wpi::units::volt_t PneumaticHub::GetSolenoidsVoltage() const { int32_t status = 0; auto voltage = HAL_GetREVPHSolenoidVoltage(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return wpi::units::volt_t{voltage}; } wpi::units::volt_t PneumaticHub::GetAnalogVoltage(int channel) const { int32_t status = 0; auto voltage = HAL_GetREVPHAnalogVoltage(m_handle, channel, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return wpi::units::volt_t{voltage}; } wpi::units::pounds_per_square_inch_t PneumaticHub::GetPressure(int channel) const { int32_t status = 0; auto sensorVoltage = HAL_GetREVPHAnalogVoltage(m_handle, channel, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); auto supplyVoltage = HAL_GetREVPH5VVoltage(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return VoltsToPSI(wpi::units::volt_t{sensorVoltage}, wpi::units::volt_t{supplyVoltage}); } diff --git a/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticsBase.cpp b/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticsBase.cpp index 072f02eb57..b094293799 100644 --- a/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticsBase.cpp +++ b/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticsBase.cpp @@ -34,7 +34,7 @@ std::shared_ptr PneumaticsBase::GetForType( } else if (moduleType == PneumaticsModuleType::REVPH) { return PneumaticHub::GetForModule(busId, module); } - throw FRC_MakeError(err::InvalidParameter, "{}", + throw WPILIB_MakeError(err::InvalidParameter, "{}", static_cast(moduleType)); } @@ -44,6 +44,6 @@ int PneumaticsBase::GetDefaultForType(PneumaticsModuleType moduleType) { } else if (moduleType == PneumaticsModuleType::REVPH) { return SensorUtil::GetDefaultREVPHModule(); } - throw FRC_MakeError(err::InvalidParameter, "{}", + throw WPILIB_MakeError(err::InvalidParameter, "{}", static_cast(moduleType)); } diff --git a/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticsControlModule.cpp b/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticsControlModule.cpp index 9278ec3760..d4027c5f33 100644 --- a/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticsControlModule.cpp +++ b/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticsControlModule.cpp @@ -32,7 +32,7 @@ std::unique_ptr< std::weak_ptr& PneumaticsControlModule::GetDataStore(int busId, int module) { int32_t numBuses = HAL_GetNumCanBuses(); - FRC_AssertMessage(busId >= 0 && busId < numBuses, + WPILIB_AssertMessage(busId >= 0 && busId < numBuses, "Bus {} out of range. Must be [0-{}).", busId, numBuses); if (!m_handleMaps) { m_handleMaps = std::make_unique{this, wpi::util::NullDeleter()}; @@ -92,20 +92,20 @@ PneumaticsControlModule::PneumaticsControlModule(int /* busId */, bool PneumaticsControlModule::GetCompressor() const { int32_t status = 0; auto result = HAL_GetCTREPCMCompressor(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return result; } void PneumaticsControlModule::DisableCompressor() { int32_t status = 0; HAL_SetCTREPCMClosedLoopControl(m_handle, false, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); } void PneumaticsControlModule::EnableCompressorDigital() { int32_t status = 0; HAL_SetCTREPCMClosedLoopControl(m_handle, true, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); } void PneumaticsControlModule::EnableCompressorAnalog( @@ -113,7 +113,7 @@ void PneumaticsControlModule::EnableCompressorAnalog( wpi::units::pounds_per_square_inch_t maxPressure) { int32_t status = 0; HAL_SetCTREPCMClosedLoopControl(m_handle, true, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); } void PneumaticsControlModule::EnableCompressorHybrid( @@ -121,13 +121,13 @@ void PneumaticsControlModule::EnableCompressorHybrid( wpi::units::pounds_per_square_inch_t maxPressure) { int32_t status = 0; HAL_SetCTREPCMClosedLoopControl(m_handle, true, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); } CompressorConfigType PneumaticsControlModule::GetCompressorConfigType() const { int32_t status = 0; auto result = HAL_GetCTREPCMClosedLoopControl(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return result ? CompressorConfigType::Digital : CompressorConfigType::Disabled; } @@ -135,85 +135,85 @@ CompressorConfigType PneumaticsControlModule::GetCompressorConfigType() const { bool PneumaticsControlModule::GetPressureSwitch() const { int32_t status = 0; auto result = HAL_GetCTREPCMPressureSwitch(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return result; } wpi::units::ampere_t PneumaticsControlModule::GetCompressorCurrent() const { int32_t status = 0; auto result = HAL_GetCTREPCMCompressorCurrent(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return wpi::units::ampere_t{result}; } bool PneumaticsControlModule::GetCompressorCurrentTooHighFault() const { int32_t status = 0; auto result = HAL_GetCTREPCMCompressorCurrentTooHighFault(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return result; } bool PneumaticsControlModule::GetCompressorCurrentTooHighStickyFault() const { int32_t status = 0; auto result = HAL_GetCTREPCMCompressorCurrentTooHighStickyFault(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return result; } bool PneumaticsControlModule::GetCompressorShortedFault() const { int32_t status = 0; auto result = HAL_GetCTREPCMCompressorShortedFault(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return result; } bool PneumaticsControlModule::GetCompressorShortedStickyFault() const { int32_t status = 0; auto result = HAL_GetCTREPCMCompressorShortedStickyFault(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return result; } bool PneumaticsControlModule::GetCompressorNotConnectedFault() const { int32_t status = 0; auto result = HAL_GetCTREPCMCompressorNotConnectedFault(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return result; } bool PneumaticsControlModule::GetCompressorNotConnectedStickyFault() const { int32_t status = 0; auto result = HAL_GetCTREPCMCompressorNotConnectedStickyFault(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return result; } bool PneumaticsControlModule::GetSolenoidVoltageFault() const { int32_t status = 0; auto result = HAL_GetCTREPCMSolenoidVoltageFault(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return result; } bool PneumaticsControlModule::GetSolenoidVoltageStickyFault() const { int32_t status = 0; auto result = HAL_GetCTREPCMSolenoidVoltageStickyFault(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return result; } void PneumaticsControlModule::ClearAllStickyFaults() { int32_t status = 0; HAL_ClearAllCTREPCMStickyFaults(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); } void PneumaticsControlModule::SetSolenoids(int mask, int values) { int32_t status = 0; HAL_SetCTREPCMSolenoids(m_handle, mask, values, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); } int PneumaticsControlModule::GetSolenoids() const { int32_t status = 0; auto result = HAL_GetCTREPCMSolenoids(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return result; } @@ -224,14 +224,14 @@ int PneumaticsControlModule::GetModuleNumber() const { int PneumaticsControlModule::GetSolenoidDisabledList() const { int32_t status = 0; auto result = HAL_GetCTREPCMSolenoidDisabledList(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return result; } void PneumaticsControlModule::FireOneShot(int index) { int32_t status = 0; HAL_FireCTREPCMOneShot(m_handle, index, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); } void PneumaticsControlModule::SetOneShotDuration(int index, @@ -239,7 +239,7 @@ void PneumaticsControlModule::SetOneShotDuration(int index, int32_t status = 0; wpi::units::millisecond_t millis = duration; HAL_SetCTREPCMOneShotDuration(m_handle, index, millis.to(), &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); } bool PneumaticsControlModule::CheckSolenoidChannel(int channel) const { diff --git a/wpilibc/src/main/native/cpp/hardware/pneumatic/Solenoid.cpp b/wpilibc/src/main/native/cpp/hardware/pneumatic/Solenoid.cpp index 66eda08750..7dd8b3d162 100644 --- a/wpilibc/src/main/native/cpp/hardware/pneumatic/Solenoid.cpp +++ b/wpilibc/src/main/native/cpp/hardware/pneumatic/Solenoid.cpp @@ -19,12 +19,12 @@ Solenoid::Solenoid(int busId, int module, PneumaticsModuleType moduleType, : m_module{PneumaticsBase::GetForType(busId, module, moduleType)}, m_channel{channel} { if (!m_module->CheckSolenoidChannel(m_channel)) { - throw FRC_MakeError(err::ChannelIndexOutOfRange, "Channel {}", m_channel); + throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Channel {}", m_channel); } m_mask = 1 << channel; if (m_module->CheckAndReserveSolenoids(m_mask) != 0) { - throw FRC_MakeError(err::ResourceAlreadyAllocated, "Channel {}", m_channel); + throw WPILIB_MakeError(err::ResourceAlreadyAllocated, "Channel {}", m_channel); } m_module->ReportUsage(fmt::format("Solenoid[{}]", m_channel), "Solenoid"); diff --git a/wpilibc/src/main/native/cpp/hardware/power/PowerDistribution.cpp b/wpilibc/src/main/native/cpp/hardware/power/PowerDistribution.cpp index 1f1886bbd0..7ed631beb2 100644 --- a/wpilibc/src/main/native/cpp/hardware/power/PowerDistribution.cpp +++ b/wpilibc/src/main/native/cpp/hardware/power/PowerDistribution.cpp @@ -35,9 +35,9 @@ PowerDistribution::PowerDistribution(int busId) { busId, kDefaultModule, HAL_PowerDistributionType::HAL_PowerDistributionType_kAutomatic, stack.c_str(), &status); - FRC_CheckErrorStatus(status, "Module {}", kDefaultModule); + WPILIB_CheckErrorStatus(status, "Module {}", kDefaultModule); m_module = HAL_GetPowerDistributionModuleNumber(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); if (HAL_GetPowerDistributionType(m_handle, &status) == HAL_PowerDistributionType::HAL_PowerDistributionType_kCTRE) { @@ -56,9 +56,9 @@ PowerDistribution::PowerDistribution(int busId, int module, m_handle = HAL_InitializePowerDistribution( busId, module, static_cast(moduleType), stack.c_str(), &status); - FRC_CheckErrorStatus(status, "Module {}", module); + WPILIB_CheckErrorStatus(status, "Module {}", module); m_module = HAL_GetPowerDistributionModuleNumber(m_handle, &status); - FRC_ReportError(status, "Module {}", module); + WPILIB_ReportError(status, "Module {}", module); if (moduleType == ModuleType::kCTRE) { HAL_ReportUsage("PDP_CTRE", m_module, ""); @@ -71,21 +71,21 @@ PowerDistribution::PowerDistribution(int busId, int module, int PowerDistribution::GetNumChannels() const { int32_t status = 0; int32_t size = HAL_GetPowerDistributionNumChannels(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return size; } double PowerDistribution::GetVoltage() const { int32_t status = 0; double voltage = HAL_GetPowerDistributionVoltage(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return voltage; } double PowerDistribution::GetTemperature() const { int32_t status = 0; double temperature = HAL_GetPowerDistributionTemperature(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return temperature; } @@ -93,7 +93,7 @@ double PowerDistribution::GetCurrent(int channel) const { int32_t status = 0; double current = HAL_GetPowerDistributionChannelCurrent(m_handle, channel, &status); - FRC_ReportError(status, "Module {} Channel {}", m_module, channel); + WPILIB_ReportError(status, "Module {} Channel {}", m_module, channel); return current; } @@ -105,41 +105,41 @@ std::vector PowerDistribution::GetAllCurrents() const { HAL_GetPowerDistributionAllChannelCurrents(m_handle, currents.data(), size, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return currents; } double PowerDistribution::GetTotalCurrent() const { int32_t status = 0; double current = HAL_GetPowerDistributionTotalCurrent(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return current; } double PowerDistribution::GetTotalPower() const { int32_t status = 0; double power = HAL_GetPowerDistributionTotalPower(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return power; } double PowerDistribution::GetTotalEnergy() const { int32_t status = 0; double energy = HAL_GetPowerDistributionTotalEnergy(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return energy; } void PowerDistribution::ResetTotalEnergy() { int32_t status = 0; HAL_ResetPowerDistributionTotalEnergy(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); } void PowerDistribution::ClearStickyFaults() { int32_t status = 0; HAL_ClearPowerDistributionStickyFaults(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); } int PowerDistribution::GetModule() const { @@ -149,21 +149,21 @@ int PowerDistribution::GetModule() const { PowerDistribution::ModuleType PowerDistribution::GetType() const { int32_t status = 0; auto type = HAL_GetPowerDistributionType(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return static_cast(type); } bool PowerDistribution::GetSwitchableChannel() const { int32_t status = 0; bool state = HAL_GetPowerDistributionSwitchableChannel(m_handle, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); return state; } void PowerDistribution::SetSwitchableChannel(bool enabled) { int32_t status = 0; HAL_SetPowerDistributionSwitchableChannel(m_handle, enabled, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); } PowerDistribution::Version PowerDistribution::GetVersion() const { @@ -171,7 +171,7 @@ PowerDistribution::Version PowerDistribution::GetVersion() const { HAL_PowerDistributionVersion halVersion; std::memset(&halVersion, 0, sizeof(halVersion)); HAL_GetPowerDistributionVersion(m_handle, &halVersion, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); PowerDistribution::Version version; static_assert(sizeof(halVersion) == sizeof(version)); static_assert(std::is_standard_layout_v); @@ -185,7 +185,7 @@ PowerDistribution::Faults PowerDistribution::GetFaults() const { HAL_PowerDistributionFaults halFaults; std::memset(&halFaults, 0, sizeof(halFaults)); HAL_GetPowerDistributionFaults(m_handle, &halFaults, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); PowerDistribution::Faults faults; static_assert(sizeof(halFaults) == sizeof(faults)); static_assert(std::is_standard_layout_v); @@ -245,7 +245,7 @@ bool PowerDistribution::Faults::GetBreakerFault(int channel) const { case 23: return Channel23BreakerFault != 0; default: - throw FRC_MakeError(err::ChannelIndexOutOfRange, + throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Power distribution fault channel out of bounds!"); } } @@ -301,7 +301,7 @@ bool PowerDistribution::StickyFaults::GetBreakerFault(int channel) const { case 23: return Channel23BreakerFault != 0; default: - throw FRC_MakeError(err::ChannelIndexOutOfRange, + throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Power distribution fault channel out of bounds!"); } } @@ -311,7 +311,7 @@ PowerDistribution::StickyFaults PowerDistribution::GetStickyFaults() const { HAL_PowerDistributionStickyFaults halStickyFaults; std::memset(&halStickyFaults, 0, sizeof(halStickyFaults)); HAL_GetPowerDistributionStickyFaults(m_handle, &halStickyFaults, &status); - FRC_ReportError(status, "Module {}", m_module); + WPILIB_ReportError(status, "Module {}", m_module); PowerDistribution::StickyFaults stickyFaults; static_assert(sizeof(halStickyFaults) == sizeof(stickyFaults)); static_assert(std::is_standard_layout_v); diff --git a/wpilibc/src/main/native/cpp/hardware/rotation/DutyCycle.cpp b/wpilibc/src/main/native/cpp/hardware/rotation/DutyCycle.cpp index 24b4f33cfa..d58e29ac13 100644 --- a/wpilibc/src/main/native/cpp/hardware/rotation/DutyCycle.cpp +++ b/wpilibc/src/main/native/cpp/hardware/rotation/DutyCycle.cpp @@ -20,7 +20,7 @@ using namespace wpi; DutyCycle::DutyCycle(int channel) : m_channel{channel} { if (!SensorUtil::CheckDigitalChannel(channel)) { - throw FRC_MakeError(err::ChannelIndexOutOfRange, "Channel {}", channel); + throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Channel {}", channel); } InitDutyCycle(); } @@ -29,7 +29,7 @@ void DutyCycle::InitDutyCycle() { int32_t status = 0; std::string stackTrace = wpi::util::GetStackTrace(1); m_handle = HAL_InitializeDutyCycle(m_channel, stackTrace.c_str(), &status); - FRC_CheckErrorStatus(status, "Channel {}", GetSourceChannel()); + WPILIB_CheckErrorStatus(status, "Channel {}", GetSourceChannel()); HAL_ReportUsage("IO", m_channel, "DutyCycle"); wpi::util::SendableRegistry::Add(this, "Duty Cycle", m_channel); } @@ -37,21 +37,21 @@ void DutyCycle::InitDutyCycle() { wpi::units::hertz_t DutyCycle::GetFrequency() const { int32_t status = 0; auto retVal = HAL_GetDutyCycleFrequency(m_handle, &status); - FRC_CheckErrorStatus(status, "Channel {}", GetSourceChannel()); + WPILIB_CheckErrorStatus(status, "Channel {}", GetSourceChannel()); return wpi::units::hertz_t{retVal}; } double DutyCycle::GetOutput() const { int32_t status = 0; auto retVal = HAL_GetDutyCycleOutput(m_handle, &status); - FRC_CheckErrorStatus(status, "Channel {}", GetSourceChannel()); + WPILIB_CheckErrorStatus(status, "Channel {}", GetSourceChannel()); return retVal; } wpi::units::second_t DutyCycle::GetHighTime() const { int32_t status = 0; auto retVal = HAL_GetDutyCycleHighTime(m_handle, &status); - FRC_CheckErrorStatus(status, "Channel {}", GetSourceChannel()); + WPILIB_CheckErrorStatus(status, "Channel {}", GetSourceChannel()); return wpi::units::nanosecond_t{static_cast(retVal)}; } diff --git a/wpilibc/src/main/native/cpp/hardware/rotation/Encoder.cpp b/wpilibc/src/main/native/cpp/hardware/rotation/Encoder.cpp index 047691b652..d87e1e2e4f 100644 --- a/wpilibc/src/main/native/cpp/hardware/rotation/Encoder.cpp +++ b/wpilibc/src/main/native/cpp/hardware/rotation/Encoder.cpp @@ -25,112 +25,112 @@ Encoder::Encoder(int aChannel, int bChannel, bool reverseDirection, int Encoder::Get() const { int32_t status = 0; int value = HAL_GetEncoder(m_encoder, &status); - FRC_CheckErrorStatus(status, "Get"); + WPILIB_CheckErrorStatus(status, "Get"); return value; } void Encoder::Reset() { int32_t status = 0; HAL_ResetEncoder(m_encoder, &status); - FRC_CheckErrorStatus(status, "Reset"); + WPILIB_CheckErrorStatus(status, "Reset"); } wpi::units::second_t Encoder::GetPeriod() const { int32_t status = 0; double value = HAL_GetEncoderPeriod(m_encoder, &status); - FRC_CheckErrorStatus(status, "GetPeriod"); + WPILIB_CheckErrorStatus(status, "GetPeriod"); return wpi::units::second_t{value}; } void Encoder::SetMaxPeriod(wpi::units::second_t maxPeriod) { int32_t status = 0; HAL_SetEncoderMaxPeriod(m_encoder, maxPeriod.value(), &status); - FRC_CheckErrorStatus(status, "SetMaxPeriod"); + WPILIB_CheckErrorStatus(status, "SetMaxPeriod"); } bool Encoder::GetStopped() const { int32_t status = 0; bool value = HAL_GetEncoderStopped(m_encoder, &status); - FRC_CheckErrorStatus(status, "GetStopped"); + WPILIB_CheckErrorStatus(status, "GetStopped"); return value; } bool Encoder::GetDirection() const { int32_t status = 0; bool value = HAL_GetEncoderDirection(m_encoder, &status); - FRC_CheckErrorStatus(status, "GetDirection"); + WPILIB_CheckErrorStatus(status, "GetDirection"); return value; } int Encoder::GetRaw() const { int32_t status = 0; int value = HAL_GetEncoderRaw(m_encoder, &status); - FRC_CheckErrorStatus(status, "GetRaw"); + WPILIB_CheckErrorStatus(status, "GetRaw"); return value; } int Encoder::GetEncodingScale() const { int32_t status = 0; int val = HAL_GetEncoderEncodingScale(m_encoder, &status); - FRC_CheckErrorStatus(status, "GetEncodingScale"); + WPILIB_CheckErrorStatus(status, "GetEncodingScale"); return val; } double Encoder::GetDistance() const { int32_t status = 0; double value = HAL_GetEncoderDistance(m_encoder, &status); - FRC_CheckErrorStatus(status, "GetDistance"); + WPILIB_CheckErrorStatus(status, "GetDistance"); return value; } double Encoder::GetRate() const { int32_t status = 0; double value = HAL_GetEncoderRate(m_encoder, &status); - FRC_CheckErrorStatus(status, "GetRate"); + WPILIB_CheckErrorStatus(status, "GetRate"); return value; } void Encoder::SetMinRate(double minRate) { int32_t status = 0; HAL_SetEncoderMinRate(m_encoder, minRate, &status); - FRC_CheckErrorStatus(status, "SetMinRate"); + WPILIB_CheckErrorStatus(status, "SetMinRate"); } void Encoder::SetDistancePerPulse(double distancePerPulse) { int32_t status = 0; HAL_SetEncoderDistancePerPulse(m_encoder, distancePerPulse, &status); - FRC_CheckErrorStatus(status, "SetDistancePerPulse"); + WPILIB_CheckErrorStatus(status, "SetDistancePerPulse"); } double Encoder::GetDistancePerPulse() const { int32_t status = 0; double distancePerPulse = HAL_GetEncoderDistancePerPulse(m_encoder, &status); - FRC_CheckErrorStatus(status, "GetDistancePerPulse"); + WPILIB_CheckErrorStatus(status, "GetDistancePerPulse"); return distancePerPulse; } void Encoder::SetReverseDirection(bool reverseDirection) { int32_t status = 0; HAL_SetEncoderReverseDirection(m_encoder, reverseDirection, &status); - FRC_CheckErrorStatus(status, "SetReverseDirection"); + WPILIB_CheckErrorStatus(status, "SetReverseDirection"); } void Encoder::SetSamplesToAverage(int samplesToAverage) { if (samplesToAverage < 1 || samplesToAverage > 127) { - throw FRC_MakeError( + throw WPILIB_MakeError( err::ParameterOutOfRange, "Average counter values must be between 1 and 127, got {}", samplesToAverage); } int32_t status = 0; HAL_SetEncoderSamplesToAverage(m_encoder, samplesToAverage, &status); - FRC_CheckErrorStatus(status, "SetSamplesToAverage"); + WPILIB_CheckErrorStatus(status, "SetSamplesToAverage"); } int Encoder::GetSamplesToAverage() const { int32_t status = 0; int result = HAL_GetEncoderSamplesToAverage(m_encoder, &status); - FRC_CheckErrorStatus(status, "GetSamplesToAverage"); + WPILIB_CheckErrorStatus(status, "GetSamplesToAverage"); return result; } @@ -141,14 +141,14 @@ void Encoder::SetSimDevice(HAL_SimDeviceHandle device) { int Encoder::GetFPGAIndex() const { int32_t status = 0; int val = HAL_GetEncoderFPGAIndex(m_encoder, &status); - FRC_CheckErrorStatus(status, "GetFPGAIndex"); + WPILIB_CheckErrorStatus(status, "GetFPGAIndex"); return val; } void Encoder::InitSendable(wpi::util::SendableBuilder& builder) { int32_t status = 0; HAL_EncoderEncodingType type = HAL_GetEncoderEncodingType(m_encoder, &status); - FRC_CheckErrorStatus(status, "GetEncodingType"); + WPILIB_CheckErrorStatus(status, "GetEncodingType"); if (type == HAL_EncoderEncodingType::HAL_Encoder_k4X) { builder.SetSmartDashboardType("Quadrature Encoder"); } else { @@ -169,7 +169,7 @@ void Encoder::InitEncoder(int aChannel, int bChannel, bool reverseDirection, m_encoder = HAL_InitializeEncoder( aChannel, bChannel, reverseDirection, static_cast(encodingType), &status); - FRC_CheckErrorStatus(status, "InitEncoder"); + WPILIB_CheckErrorStatus(status, "InitEncoder"); const char* type = "Encoder"; switch (encodingType) { @@ -190,6 +190,6 @@ void Encoder::InitEncoder(int aChannel, int bChannel, bool reverseDirection, double Encoder::DecodingScaleFactor() const { int32_t status = 0; double val = HAL_GetEncoderDecodingScaleFactor(m_encoder, &status); - FRC_CheckErrorStatus(status, "DecodingScaleFactor"); + WPILIB_CheckErrorStatus(status, "DecodingScaleFactor"); return val; } diff --git a/wpilibc/src/main/native/cpp/opmode/IterativeRobotBase.cpp b/wpilibc/src/main/native/cpp/opmode/IterativeRobotBase.cpp index a5ea49f9c5..90adb95ded 100644 --- a/wpilibc/src/main/native/cpp/opmode/IterativeRobotBase.cpp +++ b/wpilibc/src/main/native/cpp/opmode/IterativeRobotBase.cpp @@ -193,7 +193,7 @@ void IterativeRobotBase::LoopFunc() { } void IterativeRobotBase::PrintLoopOverrunMessage() { - FRC_ReportError(err::Error, "Loop time of {:.6f}s overrun", m_period.value()); + WPILIB_ReportError(err::Error, "Loop time of {:.6f}s overrun", m_period.value()); } void IterativeRobotBase::PrintWatchdogEpochs() { diff --git a/wpilibc/src/main/native/cpp/opmode/TimedRobot.cpp b/wpilibc/src/main/native/cpp/opmode/TimedRobot.cpp index 07bee23974..6880582710 100644 --- a/wpilibc/src/main/native/cpp/opmode/TimedRobot.cpp +++ b/wpilibc/src/main/native/cpp/opmode/TimedRobot.cpp @@ -35,7 +35,7 @@ void TimedRobot::StartCompetition() { int32_t status = 0; HAL_UpdateNotifierAlarm(m_notifier, callback.expirationTime.count(), &status); - FRC_CheckErrorStatus(status, "UpdateNotifierAlarm"); + WPILIB_CheckErrorStatus(status, "UpdateNotifierAlarm"); std::chrono::microseconds currentTime{ HAL_WaitForNotifierAlarm(m_notifier, &status)}; @@ -81,7 +81,7 @@ TimedRobot::TimedRobot(wpi::units::second_t period) : IterativeRobotBase(period) int32_t status = 0; m_notifier = HAL_InitializeNotifier(&status); - FRC_CheckErrorStatus(status, "InitializeNotifier"); + WPILIB_CheckErrorStatus(status, "InitializeNotifier"); HAL_SetNotifierName(m_notifier, "TimedRobot", &status); HAL_ReportUsage("Framework", "TimedRobot"); @@ -93,7 +93,7 @@ TimedRobot::~TimedRobot() { if (m_notifier != HAL_kInvalidHandle) { int32_t status = 0; HAL_StopNotifier(m_notifier, &status); - FRC_ReportError(status, "StopNotifier"); + WPILIB_ReportError(status, "StopNotifier"); } } diff --git a/wpilibc/src/main/native/cpp/opmode/TimesliceRobot.cpp b/wpilibc/src/main/native/cpp/opmode/TimesliceRobot.cpp index ab37fcda29..9594993db1 100644 --- a/wpilibc/src/main/native/cpp/opmode/TimesliceRobot.cpp +++ b/wpilibc/src/main/native/cpp/opmode/TimesliceRobot.cpp @@ -16,7 +16,7 @@ TimesliceRobot::TimesliceRobot(wpi::units::second_t robotPeriodicAllocation, void TimesliceRobot::Schedule(std::function func, wpi::units::second_t allocation) { if (m_nextOffset + allocation > m_controllerPeriod) { - throw FRC_MakeError(err::Error, + throw WPILIB_MakeError(err::Error, "Function scheduled at offset {} with allocation {} " "exceeded controller period of {}\n", m_nextOffset, allocation, m_controllerPeriod); diff --git a/wpilibc/src/main/native/cpp/simulation/PneumaticsBaseSim.cpp b/wpilibc/src/main/native/cpp/simulation/PneumaticsBaseSim.cpp index 9f245ebcc8..097865d32b 100644 --- a/wpilibc/src/main/native/cpp/simulation/PneumaticsBaseSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/PneumaticsBaseSim.cpp @@ -24,7 +24,7 @@ std::shared_ptr PneumaticsBaseSim::GetForType( return std::make_shared(module); default: - throw FRC_MakeError(err::InvalidParameter, "{}", + throw WPILIB_MakeError(err::InvalidParameter, "{}", static_cast(module)); } } diff --git a/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp b/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp index 47d0d7c8ab..a84d7b04bf 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp @@ -84,7 +84,7 @@ wpi::nt::NetworkTableEntry SmartDashboard::GetEntry(std::string_view key) { void SmartDashboard::PutData(std::string_view key, wpi::util::Sendable* data) { if (!data) { - throw FRC_MakeError(err::NullParameter, "value"); + throw WPILIB_MakeError(err::NullParameter, "value"); } if (!gReported) { HAL_ReportUsage("SmartDashboard", ""); @@ -108,7 +108,7 @@ void SmartDashboard::PutData(std::string_view key, wpi::util::Sendable* data) { void SmartDashboard::PutData(wpi::util::Sendable* value) { if (!value) { - throw FRC_MakeError(err::NullParameter, "value"); + throw WPILIB_MakeError(err::NullParameter, "value"); } auto name = wpi::util::SendableRegistry::GetName(value); if (!name.empty()) { @@ -121,7 +121,7 @@ wpi::util::Sendable* SmartDashboard::GetData(std::string_view key) { std::scoped_lock lock(inst.tablesToDataMutex); auto it = inst.tablesToData.find(key); if (it == inst.tablesToData.end()) { - throw FRC_MakeError(err::SmartDashboardMissingKey, "{}", key); + throw WPILIB_MakeError(err::SmartDashboardMissingKey, "{}", key); } return wpi::util::SendableRegistry::GetSendable(it->second); } diff --git a/wpilibc/src/main/native/cpp/system/DataLogManager.cpp b/wpilibc/src/main/native/cpp/system/DataLogManager.cpp index ccddad91fc..38014595d2 100644 --- a/wpilibc/src/main/native/cpp/system/DataLogManager.cpp +++ b/wpilibc/src/main/native/cpp/system/DataLogManager.cpp @@ -99,7 +99,7 @@ static std::string MakeLogFilename(std::string_view filenameOverride) { static std::mt19937 rng(dev()); std::uniform_int_distribution dist(0, 15); const char* v = "0123456789abcdef"; - std::string filename = "FRC_TBD_"; + std::string filename = "WPILIB_TBD_"; for (int i = 0; i < 16; i++) { filename += v[dist(rng)]; } @@ -122,7 +122,7 @@ Thread::~Thread() { } void Thread::Main() { - // based on free disk space, scan for "old" FRC_*.wpilog files and remove + // based on free disk space, scan for "old" WPILIB_*.wpilog files and remove { std::error_code ec; uintmax_t freeSpace; @@ -133,14 +133,14 @@ void Thread::Main() { freeSpace = UINTMAX_MAX; } if (freeSpace < kFreeSpaceThreshold) { - // Delete oldest FRC_*.wpilog files (ignore FRC_TBD_*.wpilog as we just + // Delete oldest WPILIB_*.wpilog files (ignore WPILIB_TBD_*.wpilog as we just // created one) std::vector entries; for (auto&& entry : fs::directory_iterator{m_logDir, ec}) { auto stem = entry.path().stem().string(); - if (wpi::util::starts_with(stem, "FRC_") && + if (wpi::util::starts_with(stem, "WPILIB_") && entry.path().extension() == ".wpilog" && - !wpi::util::starts_with(stem, "FRC_TBD_")) { + !wpi::util::starts_with(stem, "WPILIB_TBD_")) { entries.emplace_back(entry); } } @@ -157,7 +157,7 @@ void Thread::Main() { } auto size = entry.file_size(); if (fs::remove(entry.path(), ec)) { - FRC_ReportWarning("DataLogManager: Deleted {}", + WPILIB_ReportWarning("DataLogManager: Deleted {}", entry.path().string()); freeSpace += size; if (freeSpace >= kFreeSpaceThreshold) { @@ -169,7 +169,7 @@ void Thread::Main() { } } } else if (freeSpace < 2 * kFreeSpaceThreshold) { - FRC_ReportError( + WPILIB_ReportError( warn::Warning, "DataLogManager: Log storage device has {} MB of free space " "remaining! Logs will get deleted below {} MB of free space. " @@ -227,7 +227,7 @@ void Thread::Main() { if (RobotController::IsSystemTimeValid()) { std::time_t now = std::time(nullptr); auto tm = std::gmtime(&now); - m_log.SetFilename(fmt::format("FRC_{:%Y%m%d_%H%M%S}.wpilog", *tm)); + m_log.SetFilename(fmt::format("WPILIB_{:%Y%m%d_%H%M%S}.wpilog", *tm)); dsRenamed = true; } else { dsAttachCount = 0; // wait a bit and try again @@ -265,7 +265,7 @@ void Thread::Main() { } std::time_t now = std::time(nullptr); m_log.SetFilename( - fmt::format("FRC_{:%Y%m%d_%H%M%S}_{}_{}{}.wpilog", + fmt::format("WPILIB_{:%Y%m%d_%H%M%S}_{}_{}{}.wpilog", *std::gmtime(&now), DriverStation::GetEventName(), matchTypeChar, DriverStation::GetMatchNumber())); fmsRenamed = true; @@ -306,7 +306,7 @@ void Thread::StopNTLog() { void Thread::StartConsoleLog() { if (!m_consoleLoggerEnabled && RobotBase::IsReal()) { m_consoleLoggerEnabled = true; - m_consoleLogger = {"/home/systemcore/FRC_UserProgram.log", m_log, + m_consoleLogger = {"/home/systemcore/WPILIB_UserProgram.log", m_log, "console"}; } } @@ -320,13 +320,13 @@ void Thread::StopConsoleLog() { Instance::Instance(std::string_view dir, std::string_view filename, double period) { - // Delete all previously existing FRC_TBD_*.wpilog files. These only exist + // Delete all previously existing WPILIB_TBD_*.wpilog files. These only exist // when the robot never connects to the DS, so they are very unlikely to // have useful data and just clutter the filesystem. auto logDir = MakeLogDir(dir); std::error_code ec; for (auto&& entry : fs::directory_iterator{logDir, ec}) { - if (wpi::util::starts_with(entry.path().stem().string(), "FRC_TBD_") && + if (wpi::util::starts_with(entry.path().stem().string(), "WPILIB_TBD_") && entry.path().extension() == ".wpilog") { if (!fs::remove(entry, ec)) { wpi::util::print(stderr, "DataLogManager: could not delete {}\n", diff --git a/wpilibc/src/main/native/cpp/system/Notifier.cpp b/wpilibc/src/main/native/cpp/system/Notifier.cpp index 71ba570557..deb8f9774f 100644 --- a/wpilibc/src/main/native/cpp/system/Notifier.cpp +++ b/wpilibc/src/main/native/cpp/system/Notifier.cpp @@ -18,12 +18,12 @@ using namespace wpi; Notifier::Notifier(std::function callback) { if (!callback) { - throw FRC_MakeError(err::NullParameter, "callback"); + throw WPILIB_MakeError(err::NullParameter, "callback"); } m_callback = callback; int32_t status = 0; m_notifier = HAL_InitializeNotifier(&status); - FRC_CheckErrorStatus(status, "InitializeNotifier"); + WPILIB_CheckErrorStatus(status, "InitializeNotifier"); m_thread = std::thread([=, this] { for (;;) { @@ -60,12 +60,12 @@ Notifier::Notifier(std::function callback) { Notifier::Notifier(int priority, std::function callback) { if (!callback) { - throw FRC_MakeError(err::NullParameter, "callback"); + throw WPILIB_MakeError(err::NullParameter, "callback"); } m_callback = callback; int32_t status = 0; m_notifier = HAL_InitializeNotifier(&status); - FRC_CheckErrorStatus(status, "InitializeNotifier"); + WPILIB_CheckErrorStatus(status, "InitializeNotifier"); m_thread = std::thread([=, this] { int32_t status = 0; @@ -99,7 +99,7 @@ Notifier::Notifier(int priority, std::function callback) { callback(); } catch (const wpi::RuntimeError& e) { e.Report(); - FRC_ReportError( + WPILIB_ReportError( err::Error, "Error in Notifier thread." " The above stacktrace can help determine where the error " @@ -120,7 +120,7 @@ Notifier::~Notifier() { // atomically set handle to 0, then clean HAL_NotifierHandle handle = m_notifier.exchange(0); HAL_StopNotifier(handle, &status); - FRC_ReportError(status, "StopNotifier"); + WPILIB_ReportError(status, "StopNotifier"); // Join the thread to ensure the callback has exited. if (m_thread.joinable()) { @@ -190,7 +190,7 @@ void Notifier::Stop() { m_periodic = false; int32_t status = 0; HAL_CancelNotifierAlarm(m_notifier, &status); - FRC_CheckErrorStatus(status, "CancelNotifierAlarm"); + WPILIB_CheckErrorStatus(status, "CancelNotifierAlarm"); } void Notifier::UpdateAlarm(uint64_t triggerTime) { @@ -201,7 +201,7 @@ void Notifier::UpdateAlarm(uint64_t triggerTime) { return; } HAL_UpdateNotifierAlarm(notifier, triggerTime, &status); - FRC_CheckErrorStatus(status, "UpdateNotifierAlarm"); + WPILIB_CheckErrorStatus(status, "UpdateNotifierAlarm"); } void Notifier::UpdateAlarm() { diff --git a/wpilibc/src/main/native/cpp/system/Resource.cpp b/wpilibc/src/main/native/cpp/system/Resource.cpp index bc4e3aa17f..005dd6969b 100644 --- a/wpilibc/src/main/native/cpp/system/Resource.cpp +++ b/wpilibc/src/main/native/cpp/system/Resource.cpp @@ -38,16 +38,16 @@ uint32_t Resource::Allocate(const std::string& resourceDesc) { return i; } } - throw FRC_MakeError(err::NoAvailableResources, "{}", resourceDesc); + throw WPILIB_MakeError(err::NoAvailableResources, "{}", resourceDesc); } uint32_t Resource::Allocate(uint32_t index, const std::string& resourceDesc) { std::scoped_lock lock(m_allocateMutex); if (index >= m_isAllocated.size()) { - throw FRC_MakeError(err::ChannelIndexOutOfRange, "{}", resourceDesc); + throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "{}", resourceDesc); } if (m_isAllocated[index]) { - throw FRC_MakeError(err::ResourceAlreadyAllocated, "{}", resourceDesc); + throw WPILIB_MakeError(err::ResourceAlreadyAllocated, "{}", resourceDesc); } m_isAllocated[index] = true; return index; @@ -59,10 +59,10 @@ void Resource::Free(uint32_t index) { return; } if (index >= m_isAllocated.size()) { - throw FRC_MakeError(err::NotAllocated, "index {}", index); + throw WPILIB_MakeError(err::NotAllocated, "index {}", index); } if (!m_isAllocated[index]) { - throw FRC_MakeError(err::NotAllocated, "index {}", index); + throw WPILIB_MakeError(err::NotAllocated, "index {}", index); } m_isAllocated[index] = false; } diff --git a/wpilibc/src/main/native/cpp/system/RobotController.cpp b/wpilibc/src/main/native/cpp/system/RobotController.cpp index ca73275e09..ceb3a5c533 100644 --- a/wpilibc/src/main/native/cpp/system/RobotController.cpp +++ b/wpilibc/src/main/native/cpp/system/RobotController.cpp @@ -49,116 +49,116 @@ uint64_t RobotController::GetTime() { uint64_t RobotController::GetFPGATime() { int32_t status = 0; uint64_t time = HAL_GetFPGATime(&status); - FRC_CheckErrorStatus(status, "GetFPGATime"); + WPILIB_CheckErrorStatus(status, "GetFPGATime"); return time; } wpi::units::volt_t RobotController::GetBatteryVoltage() { int32_t status = 0; double retVal = HAL_GetVinVoltage(&status); - FRC_CheckErrorStatus(status, "GetBatteryVoltage"); + WPILIB_CheckErrorStatus(status, "GetBatteryVoltage"); return wpi::units::volt_t{retVal}; } bool RobotController::IsSysActive() { int32_t status = 0; bool retVal = HAL_GetSystemActive(&status); - FRC_CheckErrorStatus(status, "IsSysActive"); + WPILIB_CheckErrorStatus(status, "IsSysActive"); return retVal; } bool RobotController::IsBrownedOut() { int32_t status = 0; bool retVal = HAL_GetBrownedOut(&status); - FRC_CheckErrorStatus(status, "IsBrownedOut"); + WPILIB_CheckErrorStatus(status, "IsBrownedOut"); return retVal; } int RobotController::GetCommsDisableCount() { int32_t status = 0; int retVal = HAL_GetCommsDisableCount(&status); - FRC_CheckErrorStatus(status, "GetCommsDisableCount"); + WPILIB_CheckErrorStatus(status, "GetCommsDisableCount"); return retVal; } bool RobotController::GetRSLState() { int32_t status = 0; bool retVal = HAL_GetRSLState(&status); - FRC_CheckErrorStatus(status, "GetRSLState"); + WPILIB_CheckErrorStatus(status, "GetRSLState"); return retVal; } bool RobotController::IsSystemTimeValid() { int32_t status = 0; bool retVal = HAL_GetSystemTimeValid(&status); - FRC_CheckErrorStatus(status, "IsSystemTimeValid"); + WPILIB_CheckErrorStatus(status, "IsSystemTimeValid"); return retVal; } double RobotController::GetInputVoltage() { int32_t status = 0; double retVal = HAL_GetVinVoltage(&status); - FRC_CheckErrorStatus(status, "GetInputVoltage"); + WPILIB_CheckErrorStatus(status, "GetInputVoltage"); return retVal; } double RobotController::GetVoltage3V3() { int32_t status = 0; double retVal = HAL_GetUserVoltage3V3(&status); - FRC_CheckErrorStatus(status, "GetVoltage3V3"); + WPILIB_CheckErrorStatus(status, "GetVoltage3V3"); return retVal; } double RobotController::GetCurrent3V3() { int32_t status = 0; double retVal = HAL_GetUserCurrent3V3(&status); - FRC_CheckErrorStatus(status, "GetCurrent3V3"); + WPILIB_CheckErrorStatus(status, "GetCurrent3V3"); return retVal; } void RobotController::SetEnabled3V3(bool enabled) { int32_t status = 0; HAL_SetUserRailEnabled3V3(enabled, &status); - FRC_CheckErrorStatus(status, "SetEnabled3V3"); + WPILIB_CheckErrorStatus(status, "SetEnabled3V3"); } bool RobotController::GetEnabled3V3() { int32_t status = 0; bool retVal = HAL_GetUserActive3V3(&status); - FRC_CheckErrorStatus(status, "GetEnabled3V3"); + WPILIB_CheckErrorStatus(status, "GetEnabled3V3"); return retVal; } int RobotController::GetFaultCount3V3() { int32_t status = 0; int retVal = HAL_GetUserCurrentFaults3V3(&status); - FRC_CheckErrorStatus(status, "GetFaultCount3V3"); + WPILIB_CheckErrorStatus(status, "GetFaultCount3V3"); return retVal; } void RobotController::ResetRailFaultCounts() { int32_t status = 0; HAL_ResetUserCurrentFaults(&status); - FRC_CheckErrorStatus(status, "ResetRailFaultCounts"); + WPILIB_CheckErrorStatus(status, "ResetRailFaultCounts"); } wpi::units::volt_t RobotController::GetBrownoutVoltage() { int32_t status = 0; double retVal = HAL_GetBrownoutVoltage(&status); - FRC_CheckErrorStatus(status, "GetBrownoutVoltage"); + WPILIB_CheckErrorStatus(status, "GetBrownoutVoltage"); return wpi::units::volt_t{retVal}; } void RobotController::SetBrownoutVoltage(wpi::units::volt_t brownoutVoltage) { int32_t status = 0; HAL_SetBrownoutVoltage(brownoutVoltage.value(), &status); - FRC_CheckErrorStatus(status, "SetBrownoutVoltage"); + WPILIB_CheckErrorStatus(status, "SetBrownoutVoltage"); } wpi::units::celsius_t RobotController::GetCPUTemp() { int32_t status = 0; double retVal = HAL_GetCPUTemp(&status); - FRC_CheckErrorStatus(status, "GetCPUTemp"); + WPILIB_CheckErrorStatus(status, "GetCPUTemp"); return wpi::units::celsius_t{retVal}; } @@ -172,7 +172,7 @@ CANStatus RobotController::GetCANStatus(int busId) { HAL_CAN_GetCANStatus(busId, &percentBusUtilization, &busOffCount, &txFullCount, &receiveErrorCount, &transmitErrorCount, &status); - FRC_CheckErrorStatus(status, "GetCANStatus"); + WPILIB_CheckErrorStatus(status, "GetCANStatus"); return {percentBusUtilization, static_cast(busOffCount), static_cast(txFullCount), static_cast(receiveErrorCount), static_cast(transmitErrorCount)}; diff --git a/wpilibc/src/main/native/cpp/system/Threads.cpp b/wpilibc/src/main/native/cpp/system/Threads.cpp index 8a73c0c9f0..8c5309a88a 100644 --- a/wpilibc/src/main/native/cpp/system/Threads.cpp +++ b/wpilibc/src/main/native/cpp/system/Threads.cpp @@ -14,7 +14,7 @@ int GetThreadPriority(std::thread& thread, bool* isRealTime) { HAL_Bool rt = false; auto native = thread.native_handle(); auto ret = HAL_GetThreadPriority(&native, &rt, &status); - FRC_CheckErrorStatus(status, "GetThreadPriority"); + WPILIB_CheckErrorStatus(status, "GetThreadPriority"); *isRealTime = rt; return ret; } @@ -23,7 +23,7 @@ int GetCurrentThreadPriority(bool* isRealTime) { int32_t status = 0; HAL_Bool rt = false; auto ret = HAL_GetCurrentThreadPriority(&rt, &status); - FRC_CheckErrorStatus(status, "GetCurrentThreadPriority"); + WPILIB_CheckErrorStatus(status, "GetCurrentThreadPriority"); *isRealTime = rt; return ret; } @@ -32,14 +32,14 @@ bool SetThreadPriority(std::thread& thread, bool realTime, int priority) { int32_t status = 0; auto native = thread.native_handle(); auto ret = HAL_SetThreadPriority(&native, realTime, priority, &status); - FRC_CheckErrorStatus(status, "SetThreadPriority"); + WPILIB_CheckErrorStatus(status, "SetThreadPriority"); return ret; } bool SetCurrentThreadPriority(bool realTime, int priority) { int32_t status = 0; auto ret = HAL_SetCurrentThreadPriority(realTime, priority, &status); - FRC_CheckErrorStatus(status, "SetCurrentThreadPriority"); + WPILIB_CheckErrorStatus(status, "SetCurrentThreadPriority"); return ret; } diff --git a/wpilibc/src/main/native/cpp/system/Tracer.cpp b/wpilibc/src/main/native/cpp/system/Tracer.cpp index feefa21056..f63ebee245 100644 --- a/wpilibc/src/main/native/cpp/system/Tracer.cpp +++ b/wpilibc/src/main/native/cpp/system/Tracer.cpp @@ -36,7 +36,7 @@ void Tracer::PrintEpochs() { wpi::util::raw_svector_ostream os(buf); PrintEpochs(os); if (!buf.empty()) { - FRC_ReportWarning("{}", buf.c_str()); + WPILIB_ReportWarning("{}", buf.c_str()); } } diff --git a/wpilibc/src/main/native/cpp/system/Watchdog.cpp b/wpilibc/src/main/native/cpp/system/Watchdog.cpp index d83ce6e45b..2375df0eff 100644 --- a/wpilibc/src/main/native/cpp/system/Watchdog.cpp +++ b/wpilibc/src/main/native/cpp/system/Watchdog.cpp @@ -48,7 +48,7 @@ class Watchdog::Impl { Watchdog::Impl::Impl() { int32_t status = 0; m_notifier = HAL_InitializeNotifier(&status); - FRC_CheckErrorStatus(status, "starting watchdog notifier"); + WPILIB_CheckErrorStatus(status, "starting watchdog notifier"); HAL_SetNotifierName(m_notifier, "Watchdog", &status); m_thread = std::thread([=, this] { Main(); }); @@ -59,7 +59,7 @@ Watchdog::Impl::~Impl() { // atomically set handle to 0, then clean HAL_NotifierHandle handle = m_notifier.exchange(0); HAL_StopNotifier(handle, &status); - FRC_ReportError(status, "stopping watchdog notifier"); + WPILIB_ReportError(status, "stopping watchdog notifier"); // Join the thread to ensure the handler has exited. if (m_thread.joinable()) { @@ -85,7 +85,7 @@ void Watchdog::Impl::UpdateAlarm() { 1e6), &status); } - FRC_CheckErrorStatus(status, "updating watchdog notifier alarm"); + WPILIB_CheckErrorStatus(status, "updating watchdog notifier alarm"); } void Watchdog::Impl::Main() { @@ -114,7 +114,7 @@ void Watchdog::Impl::Main() { if (now - watchdog->m_lastTimeoutPrintTime > kMinPrintPeriod) { watchdog->m_lastTimeoutPrintTime = now; if (!watchdog->m_suppressTimeoutMessage) { - FRC_ReportWarning("Watchdog not fed within {:.6f}s", + WPILIB_ReportWarning("Watchdog not fed within {:.6f}s", watchdog->m_timeout.value()); } } diff --git a/wpilibc/src/main/native/cpp/util/Alert.cpp b/wpilibc/src/main/native/cpp/util/Alert.cpp index a1e4b4a07f..9b3cad111e 100644 --- a/wpilibc/src/main/native/cpp/util/Alert.cpp +++ b/wpilibc/src/main/native/cpp/util/Alert.cpp @@ -70,7 +70,7 @@ class Alert::SendableAlerts : public wpi::nt::NTSendable, case AlertType::kError: return m_alerts[static_cast(type)]; default: - throw FRC_MakeError(wpi::err::InvalidParameter, + throw WPILIB_MakeError(wpi::err::InvalidParameter, "Invalid Alert Type: {}", type); } } diff --git a/wpilibc/src/main/native/cppcs/RobotBase.cpp b/wpilibc/src/main/native/cppcs/RobotBase.cpp index 48651220f9..7892b5ed36 100644 --- a/wpilibc/src/main/native/cppcs/RobotBase.cpp +++ b/wpilibc/src/main/native/cppcs/RobotBase.cpp @@ -50,7 +50,7 @@ int wpi::RunHALInitialization() { HAL_ReportUsage("WPILibVersion", GetWPILibVersion()); if (!wpi::Notifier::SetHALThreadPriority(true, 40)) { - FRC_ReportWarning("Setting HAL Notifier RT priority to 40 failed\n"); + WPILIB_ReportWarning("Setting HAL Notifier RT priority to 40 failed\n"); } std::puts("\n********** Robot program starting **********"); diff --git a/wpilibc/src/main/native/include/wpi/opmode/RobotBase.hpp b/wpilibc/src/main/native/include/wpi/opmode/RobotBase.hpp index 2068118bf1..6d8b723b2e 100644 --- a/wpilibc/src/main/native/include/wpi/opmode/RobotBase.hpp +++ b/wpilibc/src/main/native/include/wpi/opmode/RobotBase.hpp @@ -38,7 +38,7 @@ void RunRobot(wpi::util::mutex& m, Robot** robot) { theRobot.StartCompetition(); } catch (const wpi::RuntimeError& e) { e.Report(); - FRC_ReportError( + WPILIB_ReportError( err::Error, "The robot program quit unexpectedly." " This is usually due to a code error.\n" diff --git a/wpilibc/src/main/native/include/wpi/smartdashboard/MechanismObject2d.hpp b/wpilibc/src/main/native/include/wpi/smartdashboard/MechanismObject2d.hpp index ccee666523..b3f521d2c7 100644 --- a/wpilibc/src/main/native/include/wpi/smartdashboard/MechanismObject2d.hpp +++ b/wpilibc/src/main/native/include/wpi/smartdashboard/MechanismObject2d.hpp @@ -67,7 +67,7 @@ class MechanismObject2d { std::scoped_lock lock(m_mutex); auto& obj = m_objects[name]; if (obj) { - throw FRC_MakeError( + throw WPILIB_MakeError( err::Error, "MechanismObject names must be unique! `{}` was inserted twice!", name); diff --git a/wpilibc/src/main/native/include/wpi/system/DataLogManager.hpp b/wpilibc/src/main/native/include/wpi/system/DataLogManager.hpp index ff21b5ee94..e3bc7d6a28 100644 --- a/wpilibc/src/main/native/include/wpi/system/DataLogManager.hpp +++ b/wpilibc/src/main/native/include/wpi/system/DataLogManager.hpp @@ -20,14 +20,14 @@ namespace wpi { * The data file will be saved to a USB flash drive in a folder named "logs" if * one is attached, or to /home/systemcore/logs otherwise. * - * Log files are initially named "FRC_TBD_{random}.wpilog" until the DS + * Log files are initially named "WPILIB_TBD_{random}.wpilog" until the DS * connects. After the DS connects, the log file is renamed to - * "FRC_yyyyMMdd_HHmmss.wpilog" (where the date/time is UTC). If the FMS is + * "WPILIB_yyyyMMdd_HHmmss.wpilog" (where the date/time is UTC). If the FMS is * connected and provides a match number, the log file is renamed to - * "FRC_yyyyMMdd_HHmmss_{event}_{match}.wpilog". + * "WPILIB_yyyyMMdd_HHmmss_{event}_{match}.wpilog". * - * On startup, all existing FRC_TBD log files are deleted. If there is less than - * 50 MB of free space on the target storage, FRC_ log files are deleted (oldest + * On startup, all existing WPILIB_TBD log files are deleted. If there is less than + * 50 MB of free space on the target storage, WPILIB_ log files are deleted (oldest * to newest) until there is 50 MB free OR there are 10 files remaining. * * By default, all NetworkTables value changes are stored to the data log. diff --git a/wpilibc/src/main/native/include/wpi/system/Errors.hpp b/wpilibc/src/main/native/include/wpi/system/Errors.hpp index 241a4fb3ec..6464fe7698 100644 --- a/wpilibc/src/main/native/include/wpi/system/Errors.hpp +++ b/wpilibc/src/main/native/include/wpi/system/Errors.hpp @@ -50,7 +50,7 @@ const char* GetErrorMessage(int32_t* code); /** * Reports an error to the driver station (using HAL_SendError). - * Generally the FRC_ReportError wrapper macro should be used instead. + * Generally the WPILIB_ReportError wrapper macro should be used instead. * * @param[out] status error code * @param[in] fileName source file name @@ -65,7 +65,7 @@ void ReportErrorV(int32_t status, const char* fileName, int lineNumber, /** * Reports an error to the driver station (using HAL_SendError). - * Generally the FRC_ReportError wrapper macro should be used instead. + * Generally the WPILIB_ReportError wrapper macro should be used instead. * * @param[out] status error code * @param[in] fileName source file name @@ -84,7 +84,7 @@ inline void ReportError(int32_t status, const char* fileName, int lineNumber, /** * Makes a runtime error exception object. This object should be thrown - * by the caller. Generally the FRC_MakeError wrapper macro should be used + * by the caller. Generally the WPILIB_MakeError wrapper macro should be used * instead. * * @param[out] status error code @@ -134,7 +134,7 @@ namespace warn { * @param[out] status error code * @param[in] format error message format */ -#define FRC_ReportError(status, format, ...) \ +#define WPILIB_ReportError(status, format, ...) \ do { \ if ((status) != 0) { \ ::wpi::ReportError(status, __FILE__, __LINE__, __FUNCTION__, \ @@ -147,7 +147,7 @@ namespace warn { * * @param[in] format error message format */ -#define FRC_ReportWarning(format, ...) \ +#define WPILIB_ReportWarning(format, ...) \ do { \ ::wpi::ReportError(::wpi::warn::Warning, __FILE__, __LINE__, __FUNCTION__, \ format __VA_OPT__(, ) __VA_ARGS__); \ @@ -161,7 +161,7 @@ namespace warn { * @param[in] format error message format * @return runtime error object */ -#define FRC_MakeError(status, format, ...) \ +#define WPILIB_MakeError(status, format, ...) \ ::wpi::MakeError(status, __FILE__, __LINE__, __FUNCTION__, \ format __VA_OPT__(, ) __VA_ARGS__) @@ -172,7 +172,7 @@ namespace warn { * @param[out] status error code * @param[in] format error message format */ -#define FRC_CheckErrorStatus(status, format, ...) \ +#define WPILIB_CheckErrorStatus(status, format, ...) \ do { \ if ((status) < 0) { \ throw ::wpi::MakeError(status, __FILE__, __LINE__, __FUNCTION__, \ @@ -183,7 +183,7 @@ namespace warn { } \ } while (0) -#define FRC_AssertMessage(condition, format, ...) \ +#define WPILIB_AssertMessage(condition, format, ...) \ do { \ if (!(condition)) { \ throw ::wpi::MakeError(::wpi::err::AssertionFailure, __FILE__, __LINE__, \ @@ -191,4 +191,4 @@ namespace warn { } \ } while (0) -#define FRC_Assert(condition) FRC_AssertMessage(condition, #condition) +#define WPILIB_Assert(condition) WPILIB_AssertMessage(condition, #condition) diff --git a/wpilibc/src/main/python/semiwrap/SmartDashboard.yml b/wpilibc/src/main/python/semiwrap/SmartDashboard.yml index e19d3155ab..b72e3ce980 100644 --- a/wpilibc/src/main/python/semiwrap/SmartDashboard.yml +++ b/wpilibc/src/main/python/semiwrap/SmartDashboard.yml @@ -20,7 +20,7 @@ classes: cpp_code: | [](py::str &key, std::shared_ptr data) { if (!data) { - throw FRC_MakeError(err::NullParameter, "{}", "value"); + throw WPILIB_MakeError(err::NullParameter, "{}", "value"); } // convert key to a raw string so that we can create a StringRef diff --git a/wpilibc/src/main/python/wpilib/src/rpy/Notifier.cpp b/wpilibc/src/main/python/wpilib/src/rpy/Notifier.cpp index e12173aa10..b84bd2ed28 100644 --- a/wpilibc/src/main/python/wpilib/src/rpy/Notifier.cpp +++ b/wpilibc/src/main/python/wpilib/src/rpy/Notifier.cpp @@ -33,12 +33,12 @@ static void _hang_thread_if_finalizing() { PyNotifier::PyNotifier(std::function handler) { if (!handler) { - throw FRC_MakeError(err::NullParameter, "handler"); + throw WPILIB_MakeError(err::NullParameter, "handler"); } m_handler = handler; int32_t status = 0; m_notifier = HAL_InitializeNotifier(&status); - FRC_CheckErrorStatus(status, "InitializeNotifier"); + WPILIB_CheckErrorStatus(status, "InitializeNotifier"); std::function target([this] { py::gil_scoped_release release; @@ -99,7 +99,7 @@ PyNotifier::~PyNotifier() { // atomically set handle to 0, then clean HAL_NotifierHandle handle = m_notifier.exchange(0); HAL_StopNotifier(handle, &status); - FRC_ReportError(status, "StopNotifier"); + WPILIB_ReportError(status, "StopNotifier"); // Join the thread to ensure the handler has exited. if (m_thread) { @@ -165,7 +165,7 @@ void PyNotifier::Stop() { m_periodic = false; int32_t status = 0; HAL_CancelNotifierAlarm(m_notifier, &status); - FRC_CheckErrorStatus(status, "CancelNotifierAlarm"); + WPILIB_CheckErrorStatus(status, "CancelNotifierAlarm"); } void PyNotifier::UpdateAlarm(uint64_t triggerTime) { @@ -176,7 +176,7 @@ void PyNotifier::UpdateAlarm(uint64_t triggerTime) { return; } HAL_UpdateNotifierAlarm(notifier, triggerTime, &status); - FRC_CheckErrorStatus(status, "UpdateNotifierAlarm"); + WPILIB_CheckErrorStatus(status, "UpdateNotifierAlarm"); } void PyNotifier::UpdateAlarm() { diff --git a/wpilibcExamples/CMakeLists.txt b/wpilibcExamples/CMakeLists.txt index 74474c846c..3e5f245734 100644 --- a/wpilibcExamples/CMakeLists.txt +++ b/wpilibcExamples/CMakeLists.txt @@ -39,7 +39,7 @@ foreach(example ${EXAMPLES}) src/main/cpp/examples/${example}/include src/test/cpp/examples/${example}/include ) - target_compile_definitions(Example_${example}_test PUBLIC RUNNING_FRC_TESTS) + target_compile_definitions(Example_${example}_test PUBLIC RUNNING_WPILIB_TESTS) target_link_libraries( Example_${example}_test apriltag diff --git a/wpilibcExamples/build.gradle b/wpilibcExamples/build.gradle index ba9526e68d..81c5a9b816 100644 --- a/wpilibcExamples/build.gradle +++ b/wpilibcExamples/build.gradle @@ -321,8 +321,8 @@ model { lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared' nativeUtils.useRequiredLibrary(it, 'opencv_shared') - it.cppCompiler.define('RUNNING_FRC_TESTS') - it.cCompiler.define('RUNNING_FRC_TESTS') + it.cppCompiler.define('RUNNING_WPILIB_TESTS') + it.cCompiler.define('RUNNING_WPILIB_TESTS') } } } diff --git a/wpilibcExamples/build_cpp_examples.bzl b/wpilibcExamples/build_cpp_examples.bzl index 538c7119f6..d07b6e658f 100644 --- a/wpilibcExamples/build_cpp_examples.bzl +++ b/wpilibcExamples/build_cpp_examples.bzl @@ -108,6 +108,6 @@ def build_tests(): ":{}-examples-headers".format(folder), "//thirdparty/googletest", ], - defines = ["RUNNING_FRC_TESTS=1"], + defines = ["RUNNING_WPILIB_TESTS=1"], tags = ["wpi-example", "no-tsan", "no-asan", "no-ubsan", "exclusive"], ) diff --git a/wpilibcExamples/src/main/cpp/examples/AddressableLED/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/AddressableLED/cpp/Robot.cpp index e2d3de4307..69349427c5 100644 --- a/wpilibcExamples/src/main/cpp/examples/AddressableLED/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/AddressableLED/cpp/Robot.cpp @@ -17,7 +17,7 @@ void Robot::RobotPeriodic() { m_led.SetData(m_ledBuffer); } -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/AprilTagsVision/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/AprilTagsVision/cpp/Robot.cpp index 0e071b248c..bfce06083a 100644 --- a/wpilibcExamples/src/main/cpp/examples/AprilTagsVision/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/AprilTagsVision/cpp/Robot.cpp @@ -162,7 +162,7 @@ class Robot : public wpi::TimedRobot { #endif }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp index d8509f4f42..df2fb9690b 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp @@ -36,7 +36,7 @@ class Robot : public wpi::TimedRobot { } }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp index 6b428ee01f..30bbcd68dc 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp @@ -39,7 +39,7 @@ class Robot : public wpi::TimedRobot { } }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp index ac3dfd9bff..ef04ceb39e 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp @@ -27,7 +27,7 @@ void Robot::DisabledInit() { m_arm.Stop(); } -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp index b68b7551c8..c123b73be9 100644 --- a/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp @@ -54,7 +54,7 @@ class Robot : public wpi::TimedRobot { wpi::PowerDistribution m_pdp{0}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Robot.cpp index 3564349923..37f366255d 100644 --- a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Robot.cpp @@ -42,7 +42,7 @@ class Robot : public wpi::TimedRobot { Drivetrain m_drive; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Robot.cpp index 18d3b31f4e..edab8635a6 100644 --- a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Robot.cpp @@ -46,7 +46,7 @@ class Robot : public wpi::TimedRobot { Drivetrain m_drive; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/DigitalCommunication/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/DigitalCommunication/cpp/Robot.cpp index 719104caa2..05ac9edf56 100644 --- a/wpilibcExamples/src/main/cpp/examples/DigitalCommunication/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/DigitalCommunication/cpp/Robot.cpp @@ -22,7 +22,7 @@ void Robot::RobotPeriodic() { m_alertOutput.Set(matchTime <= 30_s && matchTime >= 25_s); } -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp index 1b76bdb73d..85875e2ec3 100644 --- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp @@ -65,7 +65,7 @@ void Robot::TeleopPeriodic() {} */ void Robot::TestPeriodic() {} -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/DutyCycleEncoder/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/DutyCycleEncoder/cpp/Robot.cpp index eee460eb5f..a9ea1d0cc2 100644 --- a/wpilibcExamples/src/main/cpp/examples/DutyCycleEncoder/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/DutyCycleEncoder/cpp/Robot.cpp @@ -66,7 +66,7 @@ class Robot : public wpi::TimedRobot { } }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/DutyCycleInput/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/DutyCycleInput/cpp/Robot.cpp index 1faee99457..0d5345270b 100644 --- a/wpilibcExamples/src/main/cpp/examples/DutyCycleInput/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/DutyCycleInput/cpp/Robot.cpp @@ -26,7 +26,7 @@ class Robot : public wpi::TimedRobot { } }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialProfile/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialProfile/cpp/Robot.cpp index 6479442f82..694ef86691 100644 --- a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialProfile/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialProfile/cpp/Robot.cpp @@ -60,7 +60,7 @@ class Robot : public wpi::TimedRobot { wpi::math::ExponentialProfile::State m_setpoint; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/cpp/Robot.cpp index 82c64241d0..30ac839b98 100644 --- a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/cpp/Robot.cpp @@ -37,7 +37,7 @@ void Robot::DisabledInit() { m_elevator.Stop(); } -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorProfiledPID/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ElevatorProfiledPID/cpp/Robot.cpp index 58af891b13..45de8d4eed 100644 --- a/wpilibcExamples/src/main/cpp/examples/ElevatorProfiledPID/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ElevatorProfiledPID/cpp/Robot.cpp @@ -63,7 +63,7 @@ class Robot : public wpi::TimedRobot { wpi::math::ElevatorFeedforward m_feedforward{kS, kG, kV}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/Robot.cpp index a015d903e9..d71256a8ce 100644 --- a/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/Robot.cpp @@ -32,7 +32,7 @@ void Robot::DisabledInit() { m_elevator.Stop(); } -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp index 736df29e7e..eb5057c36f 100644 --- a/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp @@ -56,7 +56,7 @@ class Robot : public wpi::TimedRobot { wpi::math::TrapezoidProfile::State m_setpoint; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/Encoder/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Encoder/cpp/Robot.cpp index 4ceaa2348d..034a9d365d 100644 --- a/wpilibcExamples/src/main/cpp/examples/Encoder/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Encoder/cpp/Robot.cpp @@ -79,7 +79,7 @@ class Robot : public wpi::TimedRobot { wpi::Encoder m_encoder{1, 2, false, wpi::Encoder::k4X}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp index 0aa6895dc6..97ca016408 100644 --- a/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp @@ -94,7 +94,7 @@ class Robot : public wpi::TimedRobot { wpi::Joystick m_joystick{0}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/FlywheelBangBangController/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/FlywheelBangBangController/cpp/Robot.cpp index 281db535f7..888add7dfd 100644 --- a/wpilibcExamples/src/main/cpp/examples/FlywheelBangBangController/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/FlywheelBangBangController/cpp/Robot.cpp @@ -101,7 +101,7 @@ class Robot : public wpi::TimedRobot { wpi::sim::EncoderSim m_encoderSim{m_encoder}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp index b6ff8b6b7c..af2e9732d8 100644 --- a/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp @@ -59,7 +59,7 @@ class Robot : public wpi::TimedRobot { wpi::Timer m_timer; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp index 7dd6f510ae..f9404e730e 100644 --- a/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp @@ -57,7 +57,7 @@ class Robot : public wpi::TimedRobot { wpi::Joystick m_joystick{kJoystickPort}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp index 059b224af4..03f83320ad 100644 --- a/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp @@ -58,7 +58,7 @@ class Robot : public wpi::TimedRobot { wpi::Joystick m_joystick{kJoystickPort}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/Robot.cpp index f3a5693620..4d630d79f1 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/Robot.cpp @@ -74,7 +74,7 @@ void Robot::TeleopPeriodic() {} */ void Robot::TestPeriodic() {} -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp index f3a5693620..4d630d79f1 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp @@ -74,7 +74,7 @@ void Robot::TeleopPeriodic() {} */ void Robot::TestPeriodic() {} -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/HidRumble/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/HidRumble/cpp/Robot.cpp index 974f48b322..4b53b75dac 100644 --- a/wpilibcExamples/src/main/cpp/examples/HidRumble/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HidRumble/cpp/Robot.cpp @@ -26,7 +26,7 @@ class Robot : public wpi::TimedRobot { wpi::GenericHID m_hid{0}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/HttpCamera/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/HttpCamera/cpp/Robot.cpp index 29f92f85a0..f4873c8e2f 100644 --- a/wpilibcExamples/src/main/cpp/examples/HttpCamera/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HttpCamera/cpp/Robot.cpp @@ -60,7 +60,7 @@ class Robot : public wpi::TimedRobot { } }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/I2CCommunication/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/I2CCommunication/cpp/Robot.cpp index ff4c2a2e62..46798f8bb7 100644 --- a/wpilibcExamples/src/main/cpp/examples/I2CCommunication/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/I2CCommunication/cpp/Robot.cpp @@ -40,7 +40,7 @@ void Robot::RobotPeriodic() { arduino.WriteBulk(reinterpret_cast(string.data()), string.size()); } -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/IntermediateVision/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/IntermediateVision/cpp/Robot.cpp index 458dff7203..b32fea2ec3 100644 --- a/wpilibcExamples/src/main/cpp/examples/IntermediateVision/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/IntermediateVision/cpp/Robot.cpp @@ -70,7 +70,7 @@ class Robot : public wpi::TimedRobot { #endif }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Robot.cpp index eb5a574ed2..3f31658292 100644 --- a/wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Robot.cpp @@ -50,7 +50,7 @@ class Robot : public wpi::TimedRobot { } }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp index ccab39f64f..af96d23f33 100644 --- a/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp @@ -54,7 +54,7 @@ class Robot : public wpi::TimedRobot { wpi::Joystick m_stick{kJoystickChannel}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Robot.cpp index eb5a574ed2..3f31658292 100644 --- a/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Robot.cpp @@ -50,7 +50,7 @@ class Robot : public wpi::TimedRobot { } }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp index 25e5d7749a..de24e4ead9 100644 --- a/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp @@ -69,7 +69,7 @@ class Robot : public wpi::TimedRobot { "wrist", 0.5, 90_deg, 6, wpi::Color8Bit{wpi::Color::kPurple}); }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp index 77806a97ce..41b020bef5 100644 --- a/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp @@ -45,7 +45,7 @@ class Robot : public wpi::TimedRobot { wpi::Encoder m_encoder{0, 1}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/cpp/Robot.cpp index d1ad54c4c9..6ec41b4461 100644 --- a/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/cpp/Robot.cpp @@ -29,7 +29,7 @@ void Robot::TeleopPeriodic() { } } -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/QuickVision/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/QuickVision/cpp/Robot.cpp index b19c972486..ed816b2323 100644 --- a/wpilibcExamples/src/main/cpp/examples/QuickVision/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/QuickVision/cpp/Robot.cpp @@ -25,7 +25,7 @@ class Robot : public wpi::TimedRobot { } }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/Robot.cpp index 8bccf119a5..9f26a88743 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/Robot.cpp @@ -51,7 +51,7 @@ void Robot::TestInit() { void Robot::TestPeriodic() {} -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/Robot.cpp index 35984f0b9d..b69e86743c 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/Robot.cpp @@ -64,7 +64,7 @@ void Robot::TeleopPeriodic() {} */ void Robot::TestPeriodic() {} -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/Robot.cpp index 9e238c07f8..27d2e202fb 100644 --- a/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/Robot.cpp @@ -65,7 +65,7 @@ void Robot::TeleopPeriodic() {} */ void Robot::TestPeriodic() {} -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Robot.cpp index 7cafbd1491..04634a5caa 100644 --- a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Robot.cpp @@ -65,7 +65,7 @@ class Robot : public wpi::TimedRobot { wpi::Timer m_timer; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/Solenoid/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Solenoid/cpp/Robot.cpp index ae6df0d8d5..a74792d1e0 100644 --- a/wpilibcExamples/src/main/cpp/examples/Solenoid/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Solenoid/cpp/Robot.cpp @@ -87,7 +87,7 @@ void Robot::TeleopPeriodic() { } } -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp index 79eef8764a..c6f468a2a5 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp @@ -137,7 +137,7 @@ class Robot : public wpi::TimedRobot { } }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp index 29d5ebbcb7..57da50dc32 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp @@ -137,7 +137,7 @@ class Robot : public wpi::TimedRobot { } }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp index 3cca5bbe74..f0a4ef9532 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp @@ -114,7 +114,7 @@ class Robot : public wpi::TimedRobot { } }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp index 061cbc0978..55c92e7c83 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp @@ -114,7 +114,7 @@ class Robot : public wpi::TimedRobot { } }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/Robot.cpp index 1177303d88..9a340ae2b4 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/Robot.cpp @@ -54,7 +54,7 @@ class Robot : public wpi::TimedRobot { } }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Robot.cpp index e8956a6d2b..4cd7a4bf7a 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Robot.cpp @@ -50,7 +50,7 @@ class Robot : public wpi::TimedRobot { } }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/Robot.cpp index c1390561da..f92c8e2cd5 100644 --- a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/Robot.cpp @@ -48,7 +48,7 @@ void Robot::TestPeriodic() {} void Robot::TestExit() {} -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp index 5bd3cbfdd5..b1e84a3bda 100644 --- a/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp @@ -37,7 +37,7 @@ class Robot : public wpi::TimedRobot { } }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp index 667d40b2fa..2b0ee5b9cb 100644 --- a/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp @@ -37,7 +37,7 @@ class Robot : public wpi::TimedRobot { } }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/Robot.cpp index ee6d5fe86a..4c90aa5424 100644 --- a/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/Robot.cpp @@ -25,7 +25,7 @@ void Robot::TeleopPeriodic() { } } -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/Robot.cpp index 35984f0b9d..b69e86743c 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/Robot.cpp @@ -64,7 +64,7 @@ void Robot::TeleopPeriodic() {} */ void Robot::TestPeriodic() {} -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/snippets/ADXLAccelerometers/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/ADXLAccelerometers/cpp/Robot.cpp index f7dbfdc83d..1652500e7e 100644 --- a/wpilibcExamples/src/main/cpp/snippets/ADXLAccelerometers/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/ADXLAccelerometers/cpp/Robot.cpp @@ -31,7 +31,7 @@ class Robot : public wpi::TimedRobot { wpi::ADXL345_I2C::Range::kRange_8G}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/snippets/AccelerometerCollision/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/AccelerometerCollision/cpp/Robot.cpp index 59474f0a4e..3be3a61869 100644 --- a/wpilibcExamples/src/main/cpp/snippets/AccelerometerCollision/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/AccelerometerCollision/cpp/Robot.cpp @@ -33,7 +33,7 @@ class Robot : public wpi::TimedRobot { wpi::OnboardIMU m_accelerometer{wpi::OnboardIMU::MountOrientation::kFlat}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/snippets/AccelerometerFilter/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/AccelerometerFilter/cpp/Robot.cpp index 75917b31f2..d03768a4e7 100644 --- a/wpilibcExamples/src/main/cpp/snippets/AccelerometerFilter/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/AccelerometerFilter/cpp/Robot.cpp @@ -31,7 +31,7 @@ class Robot : public wpi::TimedRobot { wpi::math::LinearFilter::MovingAverage(10); }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/snippets/AnalogAccelerometer/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/AnalogAccelerometer/cpp/Robot.cpp index 5e5f0b14f6..2c381b457c 100644 --- a/wpilibcExamples/src/main/cpp/snippets/AnalogAccelerometer/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/AnalogAccelerometer/cpp/Robot.cpp @@ -29,7 +29,7 @@ class Robot : public wpi::TimedRobot { wpi::AnalogAccelerometer m_accelerometer{0}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/snippets/AnalogEncoder/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/AnalogEncoder/cpp/Robot.cpp index 35aa7a2f00..adce2d3f2a 100644 --- a/wpilibcExamples/src/main/cpp/snippets/AnalogEncoder/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/AnalogEncoder/cpp/Robot.cpp @@ -28,7 +28,7 @@ class Robot : public wpi::TimedRobot { wpi::AnalogEncoder m_encoderFR{0, 4.0, 2.0}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/snippets/AnalogInput/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/AnalogInput/cpp/Robot.cpp index 93a164ac26..c5963ea416 100644 --- a/wpilibcExamples/src/main/cpp/snippets/AnalogInput/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/AnalogInput/cpp/Robot.cpp @@ -47,7 +47,7 @@ class Robot : public wpi::TimedRobot { wpi::AnalogInput m_analog{0}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/snippets/AnalogPotentiometer/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/AnalogPotentiometer/cpp/Robot.cpp index 8129c73d40..120f51eb7b 100644 --- a/wpilibcExamples/src/main/cpp/snippets/AnalogPotentiometer/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/AnalogPotentiometer/cpp/Robot.cpp @@ -38,7 +38,7 @@ class Robot : public wpi::TimedRobot { wpi::AnalogPotentiometer m_pot1{&m_input, 180, 30}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/snippets/DigitalInput/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/DigitalInput/cpp/Robot.cpp index 7421952b94..fb5b2ee586 100644 --- a/wpilibcExamples/src/main/cpp/snippets/DigitalInput/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/DigitalInput/cpp/Robot.cpp @@ -22,7 +22,7 @@ class Robot : public wpi::TimedRobot { wpi::DigitalInput m_input{0}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/snippets/DutyCycleEncoder/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/DutyCycleEncoder/cpp/Robot.cpp index 8f4a601e5a..43b88b1277 100644 --- a/wpilibcExamples/src/main/cpp/snippets/DutyCycleEncoder/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/DutyCycleEncoder/cpp/Robot.cpp @@ -31,7 +31,7 @@ class Robot : public wpi::TimedRobot { wpi::DutyCycleEncoder m_encoderFR{0, 4.0, 2.0}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/snippets/Encoder/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/Encoder/cpp/Robot.cpp index ebf76d4cf4..fc94180e5e 100644 --- a/wpilibcExamples/src/main/cpp/snippets/Encoder/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/Encoder/cpp/Robot.cpp @@ -59,7 +59,7 @@ class Robot : public wpi::TimedRobot { wpi::Encoder m_encoder2x{0, 1, false, wpi::Encoder::EncodingType::k2X}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/snippets/EncoderDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/EncoderDrive/cpp/Robot.cpp index d00a3141ec..ac3f3f8371 100644 --- a/wpilibcExamples/src/main/cpp/snippets/EncoderDrive/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/EncoderDrive/cpp/Robot.cpp @@ -47,7 +47,7 @@ class Robot : public wpi::TimedRobot { [&](double output) { rightLeader.Set(output); }}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/snippets/EncoderHoming/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/EncoderHoming/cpp/Robot.cpp index d22b283fac..98b53210d1 100644 --- a/wpilibcExamples/src/main/cpp/snippets/EncoderHoming/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/EncoderHoming/cpp/Robot.cpp @@ -31,7 +31,7 @@ class Robot : public wpi::TimedRobot { wpi::DigitalInput m_limit{2}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/snippets/LimitSwitch/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/LimitSwitch/cpp/Robot.cpp index 68ed3e35a5..f391ca8358 100644 --- a/wpilibcExamples/src/main/cpp/snippets/LimitSwitch/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/LimitSwitch/cpp/Robot.cpp @@ -43,7 +43,7 @@ class Robot : public wpi::TimedRobot { wpi::Joystick m_joystick{0}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/snippets/OnboardIMU/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/OnboardIMU/cpp/Robot.cpp index 279091f43a..b6e346f350 100644 --- a/wpilibcExamples/src/main/cpp/snippets/OnboardIMU/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/OnboardIMU/cpp/Robot.cpp @@ -38,7 +38,7 @@ class Robot : public wpi::TimedRobot { wpi::OnboardIMU m_IMU{wpi::OnboardIMU::MountOrientation::kFlat}; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/snippets/ProfiledPIDFeedforward/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/ProfiledPIDFeedforward/cpp/Robot.cpp index 1d79c22253..113de7087e 100644 --- a/wpilibcExamples/src/main/cpp/snippets/ProfiledPIDFeedforward/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/ProfiledPIDFeedforward/cpp/Robot.cpp @@ -47,7 +47,7 @@ class Robot : public wpi::TimedRobot { wpi::units::meters_per_second_t m_lastSpeed = 0_mps; }; -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp index 0da6ef185a..f08a46dfdb 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp @@ -73,7 +73,7 @@ void Robot::SimulationInit() {} */ void Robot::SimulationPeriodic() {} -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/Robot.cpp index c1390561da..f92c8e2cd5 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/Robot.cpp @@ -48,7 +48,7 @@ void Robot::TestPeriodic() {} void Robot::TestExit() {} -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp index 5ea6e23547..d4b1d79a3c 100644 --- a/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp @@ -65,7 +65,7 @@ void Robot::EndCompetition() { m_exit = true; } -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp index 515fe84bc8..54270d8a5a 100644 --- a/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp @@ -71,7 +71,7 @@ void Robot::SimulationInit() {} void Robot::SimulationPeriodic() {} -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp index 0067b83b4c..49b37d776d 100644 --- a/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp @@ -22,7 +22,7 @@ void Robot::TestPeriodic() {} void Robot::SimulationInit() {} void Robot::SimulationPeriodic() {} -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/templates/timeslice/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/timeslice/cpp/Robot.cpp index 4beafe288b..f63bb06fcf 100644 --- a/wpilibcExamples/src/main/cpp/templates/timeslice/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/timeslice/cpp/Robot.cpp @@ -78,7 +78,7 @@ void Robot::TestInit() {} void Robot::TestPeriodic() {} -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/cpp/Robot.cpp index 10a6897371..bfc19469e1 100644 --- a/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/cpp/Robot.cpp @@ -31,7 +31,7 @@ void Robot::DisabledPeriodic() {} void Robot::TestInit() {} void Robot::TestPeriodic() {} -#ifndef RUNNING_FRC_TESTS +#ifndef RUNNING_WPILIB_TESTS int main() { return wpi::StartRobot(); } diff --git a/wpilibj/src/main/java/org/wpilib/system/DataLogManager.java b/wpilibj/src/main/java/org/wpilib/system/DataLogManager.java index e1d8bf8ab5..2c0eac2177 100644 --- a/wpilibj/src/main/java/org/wpilib/system/DataLogManager.java +++ b/wpilibj/src/main/java/org/wpilib/system/DataLogManager.java @@ -33,13 +33,13 @@ import org.wpilib.util.concurrent.Event; * available) competition match number. The data file will be saved to a USB flash drive in a folder * named "logs" if one is attached, or to /home/systemcore/logs otherwise. * - *

Log files are initially named "FRC_TBD_{random}.wpilog" until the DS connects. After the DS - * connects, the log file is renamed to "FRC_yyyyMMdd_HHmmss.wpilog" (where the date/time is UTC). + *

Log files are initially named "WPILIB_TBD_{random}.wpilog" until the DS connects. After the DS + * connects, the log file is renamed to "WPILIB_yyyyMMdd_HHmmss.wpilog" (where the date/time is UTC). * If the FMS is connected and provides a match number, the log file is renamed to - * "FRC_yyyyMMdd_HHmmss_{event}_{match}.wpilog". + * "WPILIB_yyyyMMdd_HHmmss_{event}_{match}.wpilog". * - *

On startup, all existing FRC_TBD log files are deleted. If there is less than 50 MB of free - * space on the target storage, FRC_ log files are deleted (oldest to newest) until there is 50 MB + *

On startup, all existing WPILIB_TBD log files are deleted. If there is less than 50 MB of free + * space on the target storage, WPILIB_ log files are deleted (oldest to newest) until there is 50 MB * free OR there are 10 files remaining. * *

By default, all NetworkTables value changes are stored to the data log. @@ -107,12 +107,12 @@ public final class DataLogManager { m_logDir = makeLogDir(dir); m_filenameOverride = !filename.isEmpty(); - // Delete all previously existing FRC_TBD_*.wpilog files. These only exist when the robot + // Delete all previously existing WPILIB_TBD_*.wpilog files. These only exist when the robot // never connects to the DS, so they are very unlikely to have useful data and just clutter // the filesystem. File[] files = new File(m_logDir) - .listFiles((d, name) -> name.startsWith("FRC_TBD_") && name.endsWith(".wpilog")); + .listFiles((d, name) -> name.startsWith("WPILIB_TBD_") && name.endsWith(".wpilog")); if (files != null) { for (File file : files) { if (!file.delete()) { @@ -272,7 +272,7 @@ public final class DataLogManager { } Random rnd = new Random(); StringBuilder filename = new StringBuilder(18); - filename.append("FRC_TBD_"); + filename.append("WPILIB_TBD_"); for (int i = 0; i < 4; i++) { filename.append(String.format("%04x", rnd.nextInt(0x10000))); } @@ -293,7 +293,7 @@ public final class DataLogManager { private static void startConsoleLog() { if (RobotBase.isReal()) { - m_consoleLogger = new FileLogger("/home/systemcore/FRC_UserProgram.log", m_log, "console"); + m_consoleLogger = new FileLogger("/home/systemcore/WPILIB_UserProgram.log", m_log, "console"); } } @@ -304,18 +304,18 @@ public final class DataLogManager { } private static void logMain() { - // based on free disk space, scan for "old" FRC_*.wpilog files and remove + // based on free disk space, scan for "old" WPILIB_*.wpilog files and remove { File logDir = new File(m_logDir); long freeSpace = logDir.getUsableSpace(); if (freeSpace < kFreeSpaceThreshold) { - // Delete oldest FRC_*.wpilog files (ignore FRC_TBD_*.wpilog as we just created one) + // Delete oldest WPILIB_*.wpilog files (ignore WPILIB_TBD_*.wpilog as we just created one) File[] files = logDir.listFiles( (dir, name) -> - name.startsWith("FRC_") + name.startsWith("WPILIB_") && name.endsWith(".wpilog") - && !name.startsWith("FRC_TBD_")); + && !name.startsWith("WPILIB_TBD_")); if (files != null) { Arrays.sort(files, Comparator.comparingLong(File::lastModified)); int count = files.length; @@ -398,7 +398,7 @@ public final class DataLogManager { if (dsAttachCount > 50) { // 1 second if (RobotController.isSystemTimeValid()) { LocalDateTime now = LocalDateTime.now(m_utc); - m_log.setFilename("FRC_" + m_timeFormatter.format(now) + ".wpilog"); + m_log.setFilename("WPILIB_" + m_timeFormatter.format(now) + ".wpilog"); dsRenamed = true; } else { dsAttachCount = 0; // wait a bit and try again @@ -427,7 +427,7 @@ public final class DataLogManager { default -> '_'; }; m_log.setFilename( - "FRC_" + "WPILIB_" + m_timeFormatter.format(LocalDateTime.now(m_utc)) + "_" + DriverStation.getEventName() diff --git a/xrpVendordep/src/main/native/cpp/xrp/XRPMotor.cpp b/xrpVendordep/src/main/native/cpp/xrp/XRPMotor.cpp index 2ad05cdb20..8a077d2820 100644 --- a/xrpVendordep/src/main/native/cpp/xrp/XRPMotor.cpp +++ b/xrpVendordep/src/main/native/cpp/xrp/XRPMotor.cpp @@ -19,12 +19,12 @@ std::set XRPMotor::s_registeredDevices = {}; void XRPMotor::CheckDeviceAllocation(int deviceNum) { if (s_simDeviceMap.count(deviceNum) == 0) { - throw FRC_MakeError(wpi::err::ChannelIndexOutOfRange, "Channel {}", + throw WPILIB_MakeError(wpi::err::ChannelIndexOutOfRange, "Channel {}", deviceNum); } if (s_registeredDevices.count(deviceNum) > 0) { - throw FRC_MakeError(wpi::err::ResourceAlreadyAllocated, "Channel {}", + throw WPILIB_MakeError(wpi::err::ResourceAlreadyAllocated, "Channel {}", deviceNum); } diff --git a/xrpVendordep/src/main/native/cpp/xrp/XRPServo.cpp b/xrpVendordep/src/main/native/cpp/xrp/XRPServo.cpp index 4cf0400c07..f22354ea32 100644 --- a/xrpVendordep/src/main/native/cpp/xrp/XRPServo.cpp +++ b/xrpVendordep/src/main/native/cpp/xrp/XRPServo.cpp @@ -21,12 +21,12 @@ std::set XRPServo::s_registeredDevices = {}; void XRPServo::CheckDeviceAllocation(int deviceNum) { if (s_simDeviceMap.count(deviceNum) == 0) { - throw FRC_MakeError(wpi::err::ChannelIndexOutOfRange, "Channel {}", + throw WPILIB_MakeError(wpi::err::ChannelIndexOutOfRange, "Channel {}", deviceNum); } if (s_registeredDevices.count(deviceNum) > 0) { - throw FRC_MakeError(wpi::err::ResourceAlreadyAllocated, "Channel {}", + throw WPILIB_MakeError(wpi::err::ResourceAlreadyAllocated, "Channel {}", deviceNum); }