diff --git a/.github/workflows/gradle.yml b/.github/workflows/gradle.yml index 839266ddeab..29893363ab9 100644 --- a/.github/workflows/gradle.yml +++ b/.github/workflows/gradle.yml @@ -51,13 +51,13 @@ jobs: fail-fast: false matrix: include: - - os: windows-2019 + - os: windows-2022 artifact-name: Win64Debug architecture: x64 task: "build" build-options: "-PciDebugOnly --max-workers 1" outputs: "build/allOutputs" - - os: windows-2019 + - os: windows-2022 artifact-name: Win64Release architecture: x64 build-options: "-PciReleaseOnly --max-workers 1" @@ -69,7 +69,7 @@ jobs: build-options: "-Pbuildalldesktop" task: "build" outputs: "build/allOutputs" - - os: windows-2019 + - os: windows-2022 artifact-name: Win32 architecture: x86 task: ":ntcoreffi:build" diff --git a/README.md b/README.md index cd2bf8e4306..54d23bb04a7 100644 --- a/README.md +++ b/README.md @@ -47,8 +47,8 @@ Using Gradle makes building WPILib very straightforward. It only has a few depen - On Windows, install the JDK 11 .msi from the link above - On macOS, install the JDK 11 .pkg from the link above - C++ compiler - - On Linux, install GCC 8 or greater - - On Windows, install [Visual Studio Community 2022 or 2019](https://visualstudio.microsoft.com/vs/community/) and select the C++ programming language during installation (Gradle can't use the build tools for Visual Studio) + - On Linux, install GCC 11 or greater + - On Windows, install [Visual Studio Community 2022](https://visualstudio.microsoft.com/vs/community/) and select the C++ programming language during installation (Gradle can't use the build tools for Visual Studio) - On macOS, install the Xcode command-line build tools via `xcode-select --install` - ARM compiler toolchain - Run `./gradlew installRoboRioToolchain` after cloning this repository diff --git a/ThirdPartyNotices.txt b/ThirdPartyNotices.txt index 74383b95d33..6fe514b6483 100644 --- a/ThirdPartyNotices.txt +++ b/ThirdPartyNotices.txt @@ -34,8 +34,6 @@ popper.js wpinet/src/main/native/resources/popper-* units wpimath/src/main/native/include/units/ Eigen wpimath/src/main/native/thirdparty/eigen/include/ StackWalker wpiutil/src/main/native/windows/StackWalker.* -TCB span wpiutil/src/main/native/thirdparty/include/wpi/span.h - wpiutil/src/test/native/cpp/span/ GHC filesystem wpiutil/src/main/native/thirdparty/include/wpi/ghc/ Team 254 Library wpilibj/src/main/java/edu/wpi/first/wpilibj/spline/SplineParameterizer.java wpilibj/src/main/java/edu/wpi/first/wpilibj/trajectory/TrajectoryParameterizer.java diff --git a/buildSrc/build.gradle b/buildSrc/build.gradle index 4cacc507a0c..2b9ba431e22 100644 --- a/buildSrc/build.gradle +++ b/buildSrc/build.gradle @@ -5,5 +5,5 @@ repositories { } } dependencies { - implementation "edu.wpi.first:native-utils:2023.2.4" + implementation "edu.wpi.first:native-utils:2023.2.7" } diff --git a/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp b/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp index 4fdfdb5da04..c6ecc3cb8c9 100644 --- a/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp +++ b/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp @@ -381,7 +381,7 @@ Instance::Instance() { // Listener for video events m_videoListener = cs::VideoListener{ - [=](const cs::VideoEvent& event) { + [=, this](const cs::VideoEvent& event) { std::scoped_lock lock(m_mutex); CS_Status status = 0; switch (event.kind) { @@ -511,7 +511,7 @@ cs::AxisCamera CameraServer::AddAxisCamera(const std::string& host) { return AddAxisCamera("Axis Camera", host); } -cs::AxisCamera CameraServer::AddAxisCamera(wpi::span hosts) { +cs::AxisCamera CameraServer::AddAxisCamera(std::span hosts) { return AddAxisCamera("Axis Camera", hosts); } @@ -543,7 +543,7 @@ cs::AxisCamera CameraServer::AddAxisCamera(std::string_view name, } cs::AxisCamera CameraServer::AddAxisCamera(std::string_view name, - wpi::span hosts) { + std::span hosts) { cs::AxisCamera camera{name, hosts}; StartAutomaticCapture(camera); auto csShared = GetCameraServerShared(); diff --git a/cameraserver/src/main/native/include/cameraserver/CameraServer.h b/cameraserver/src/main/native/include/cameraserver/CameraServer.h index ed953346e45..f47d8aa0720 100644 --- a/cameraserver/src/main/native/include/cameraserver/CameraServer.h +++ b/cameraserver/src/main/native/include/cameraserver/CameraServer.h @@ -6,11 +6,10 @@ #include +#include #include #include -#include - #include "cscore.h" #include "cscore_cv.h" @@ -110,7 +109,7 @@ class CameraServer { * * @param hosts Array of Camera host IPs/DNS names */ - static cs::AxisCamera AddAxisCamera(wpi::span hosts); + static cs::AxisCamera AddAxisCamera(std::span hosts); /** * Adds an Axis IP camera. @@ -155,7 +154,7 @@ class CameraServer { * @param hosts Array of Camera host IPs/DNS names */ static cs::AxisCamera AddAxisCamera(std::string_view name, - wpi::span hosts); + std::span hosts); /** * Adds an Axis IP camera. diff --git a/cscore/src/main/native/cpp/ConfigurableSourceImpl.cpp b/cscore/src/main/native/cpp/ConfigurableSourceImpl.cpp index 16452f1c742..48677a6319e 100644 --- a/cscore/src/main/native/cpp/ConfigurableSourceImpl.cpp +++ b/cscore/src/main/native/cpp/ConfigurableSourceImpl.cpp @@ -88,7 +88,7 @@ int ConfigurableSourceImpl::CreateProperty( } void ConfigurableSourceImpl::SetEnumPropertyChoices( - int property, wpi::span choices, CS_Status* status) { + int property, std::span choices, CS_Status* status) { std::scoped_lock lock(m_mutex); auto prop = GetProperty(property); if (!prop) { diff --git a/cscore/src/main/native/cpp/ConfigurableSourceImpl.h b/cscore/src/main/native/cpp/ConfigurableSourceImpl.h index bb9f3ed70fd..31236f53172 100644 --- a/cscore/src/main/native/cpp/ConfigurableSourceImpl.h +++ b/cscore/src/main/native/cpp/ConfigurableSourceImpl.h @@ -8,12 +8,11 @@ #include #include #include +#include #include #include #include -#include - #include "SourceImpl.h" namespace cs { @@ -42,7 +41,7 @@ class ConfigurableSourceImpl : public SourceImpl { int maximum, int step, int defaultValue, int value, std::function onChange); void SetEnumPropertyChoices(int property, - wpi::span choices, + std::span choices, CS_Status* status); private: diff --git a/cscore/src/main/native/cpp/CvSourceImpl.cpp b/cscore/src/main/native/cpp/CvSourceImpl.cpp index 7cd4fe03d73..511cf6ceb20 100644 --- a/cscore/src/main/native/cpp/CvSourceImpl.cpp +++ b/cscore/src/main/native/cpp/CvSourceImpl.cpp @@ -139,7 +139,7 @@ CS_Property CreateSourcePropertyCallback( } void SetSourceEnumPropertyChoices(CS_Source source, CS_Property property, - wpi::span choices, + std::span choices, CS_Status* status) { auto data = Instance::GetInstance().GetSource(source); if (!data || (data->kind & SourceMask) == 0) { diff --git a/cscore/src/main/native/cpp/HttpCameraImpl.cpp b/cscore/src/main/native/cpp/HttpCameraImpl.cpp index aa7f705a874..ca475f8bf8f 100644 --- a/cscore/src/main/native/cpp/HttpCameraImpl.cpp +++ b/cscore/src/main/native/cpp/HttpCameraImpl.cpp @@ -75,7 +75,7 @@ void HttpCameraImpl::MonitorThreadMain() { std::unique_lock lock(m_mutex); // sleep for 1 second between checks m_monitorCond.wait_for(lock, std::chrono::seconds(1), - [=] { return !m_active; }); + [=, this] { return !m_active; }); if (!m_active) { break; @@ -110,7 +110,8 @@ void HttpCameraImpl::StreamThreadMain() { m_streamConn->stream->close(); } // Wait for enable - m_sinkEnabledCond.wait(lock, [=] { return !m_active || IsEnabled(); }); + m_sinkEnabledCond.wait(lock, + [=, this] { return !m_active || IsEnabled(); }); if (!m_active) { return; } @@ -329,7 +330,7 @@ void HttpCameraImpl::SettingsThreadMain() { wpi::HttpRequest req; { std::unique_lock lock(m_mutex); - m_settingsCond.wait(lock, [=] { + m_settingsCond.wait(lock, [=, this] { return !m_active || (m_prefLocation != -1 && !m_settings.empty()); }); if (!m_active) { @@ -378,7 +379,7 @@ CS_HttpCameraKind HttpCameraImpl::GetKind() const { return m_kind; } -bool HttpCameraImpl::SetUrls(wpi::span urls, +bool HttpCameraImpl::SetUrls(std::span urls, CS_Status* status) { std::vector locations; for (const auto& url : urls) { @@ -572,14 +573,14 @@ CS_Source CreateHttpCamera(std::string_view name, std::string_view url, break; } std::string urlStr{url}; - if (!source->SetUrls(wpi::span{&urlStr, 1}, status)) { + if (!source->SetUrls(std::span{&urlStr, 1}, status)) { return 0; } return inst.CreateSource(CS_SOURCE_HTTP, source); } CS_Source CreateHttpCamera(std::string_view name, - wpi::span urls, + std::span urls, CS_HttpCameraKind kind, CS_Status* status) { auto& inst = Instance::GetInstance(); if (urls.empty()) { @@ -603,7 +604,7 @@ CS_HttpCameraKind GetHttpCameraKind(CS_Source source, CS_Status* status) { return static_cast(*data->source).GetKind(); } -void SetHttpCameraUrls(CS_Source source, wpi::span urls, +void SetHttpCameraUrls(CS_Source source, std::span urls, CS_Status* status) { if (urls.empty()) { *status = CS_EMPTY_VALUE; diff --git a/cscore/src/main/native/cpp/HttpCameraImpl.h b/cscore/src/main/native/cpp/HttpCameraImpl.h index c5646baa932..f224ad410e7 100644 --- a/cscore/src/main/native/cpp/HttpCameraImpl.h +++ b/cscore/src/main/native/cpp/HttpCameraImpl.h @@ -9,6 +9,7 @@ #include #include #include +#include #include #include #include @@ -18,7 +19,6 @@ #include #include #include -#include #include #include "SourceImpl.h" @@ -55,7 +55,7 @@ class HttpCameraImpl : public SourceImpl { void NumSinksEnabledChanged() override; CS_HttpCameraKind GetKind() const; - bool SetUrls(wpi::span urls, CS_Status* status); + bool SetUrls(std::span urls, CS_Status* status); std::vector GetUrls() const; // Property data diff --git a/cscore/src/main/native/cpp/Instance.h b/cscore/src/main/native/cpp/Instance.h index 323092fc026..c8ba81d8ad1 100644 --- a/cscore/src/main/native/cpp/Instance.h +++ b/cscore/src/main/native/cpp/Instance.h @@ -86,16 +86,16 @@ class Instance { void DestroySource(CS_Source handle); void DestroySink(CS_Sink handle); - wpi::span EnumerateSourceHandles( + std::span EnumerateSourceHandles( wpi::SmallVectorImpl& vec) { return m_sources.GetAll(vec); } - wpi::span EnumerateSinkHandles(wpi::SmallVectorImpl& vec) { + std::span EnumerateSinkHandles(wpi::SmallVectorImpl& vec) { return m_sinks.GetAll(vec); } - wpi::span EnumerateSourceSinks(CS_Source source, + std::span EnumerateSourceSinks(CS_Source source, wpi::SmallVectorImpl& vec) { vec.clear(); m_sinks.ForEach([&](CS_Sink sinkHandle, const SinkData& data) { diff --git a/cscore/src/main/native/cpp/PropertyContainer.cpp b/cscore/src/main/native/cpp/PropertyContainer.cpp index b1d3a6f7933..0b8474f7241 100644 --- a/cscore/src/main/native/cpp/PropertyContainer.cpp +++ b/cscore/src/main/native/cpp/PropertyContainer.cpp @@ -27,7 +27,7 @@ int PropertyContainer::GetPropertyIndex(std::string_view name) const { return ndx; } -wpi::span PropertyContainer::EnumerateProperties( +std::span PropertyContainer::EnumerateProperties( wpi::SmallVectorImpl& vec, CS_Status* status) const { if (!m_properties_cached && !CacheProperties(status)) { return {}; diff --git a/cscore/src/main/native/cpp/PropertyContainer.h b/cscore/src/main/native/cpp/PropertyContainer.h index a00c6752482..1f4ffc34bc6 100644 --- a/cscore/src/main/native/cpp/PropertyContainer.h +++ b/cscore/src/main/native/cpp/PropertyContainer.h @@ -8,13 +8,13 @@ #include #include #include +#include #include #include #include #include #include -#include #include "PropertyImpl.h" #include "cscore_cpp.h" @@ -33,7 +33,7 @@ class PropertyContainer { virtual ~PropertyContainer() = default; int GetPropertyIndex(std::string_view name) const; - wpi::span EnumerateProperties(wpi::SmallVectorImpl& vec, + std::span EnumerateProperties(wpi::SmallVectorImpl& vec, CS_Status* status) const; CS_PropertyKind GetPropertyKind(int property) const; std::string_view GetPropertyName(int property, diff --git a/cscore/src/main/native/cpp/SourceImpl.cpp b/cscore/src/main/native/cpp/SourceImpl.cpp index da5aa1d9f5b..7a02fcbd247 100644 --- a/cscore/src/main/native/cpp/SourceImpl.cpp +++ b/cscore/src/main/native/cpp/SourceImpl.cpp @@ -76,7 +76,7 @@ Frame SourceImpl::GetCurFrame() { Frame SourceImpl::GetNextFrame() { std::unique_lock lock{m_frameMutex}; auto oldTime = m_frame.GetTime(); - m_frameCv.wait(lock, [=] { return m_frame.GetTime() != oldTime; }); + m_frameCv.wait(lock, [=, this] { return m_frame.GetTime() != oldTime; }); return m_frame; } @@ -85,7 +85,7 @@ Frame SourceImpl::GetNextFrame(double timeout) { auto oldTime = m_frame.GetTime(); if (!m_frameCv.wait_for( lock, std::chrono::milliseconds(static_cast(timeout * 1000)), - [=] { return m_frame.GetTime() != oldTime; })) { + [=, this] { return m_frame.GetTime() != oldTime; })) { m_frame = Frame{*this, "timed out getting frame", wpi::Now()}; } return m_frame; diff --git a/cscore/src/main/native/cpp/UnlimitedHandleResource.h b/cscore/src/main/native/cpp/UnlimitedHandleResource.h index f7671ae4f59..3406dc93fc4 100644 --- a/cscore/src/main/native/cpp/UnlimitedHandleResource.h +++ b/cscore/src/main/native/cpp/UnlimitedHandleResource.h @@ -6,12 +6,12 @@ #define CSCORE_UNLIMITEDHANDLERESOURCE_H_ #include +#include #include #include #include #include -#include namespace cs { @@ -50,7 +50,7 @@ class UnlimitedHandleResource { std::shared_ptr Free(THandle handle); template - wpi::span GetAll(wpi::SmallVectorImpl& vec); + std::span GetAll(wpi::SmallVectorImpl& vec); std::vector> FreeAll(); @@ -151,7 +151,7 @@ UnlimitedHandleResource::Free( template template -inline wpi::span +inline std::span UnlimitedHandleResource::GetAll( wpi::SmallVectorImpl& vec) { ForEach([&](THandle handle, const TStruct& data) { vec.push_back(handle); }); diff --git a/cscore/src/main/native/cpp/cscore_cpp.cpp b/cscore/src/main/native/cpp/cscore_cpp.cpp index c497f5f0376..f81405bbf98 100644 --- a/cscore/src/main/native/cpp/cscore_cpp.cpp +++ b/cscore/src/main/native/cpp/cscore_cpp.cpp @@ -286,7 +286,7 @@ CS_Property GetSourceProperty(CS_Source source, std::string_view name, return Handle{source, property, Handle::kProperty}; } -wpi::span EnumerateSourceProperties( +std::span EnumerateSourceProperties( CS_Source source, wpi::SmallVectorImpl& vec, CS_Status* status) { auto data = Instance::GetInstance().GetSource(source); @@ -398,7 +398,7 @@ std::vector EnumerateSourceVideoModes(CS_Source source, return data->source->EnumerateVideoModes(status); } -wpi::span EnumerateSourceSinks(CS_Source source, +std::span EnumerateSourceSinks(CS_Source source, wpi::SmallVectorImpl& vec, CS_Status* status) { auto& inst = Instance::GetInstance(); @@ -583,7 +583,7 @@ CS_Property GetSinkProperty(CS_Sink sink, std::string_view name, return Handle{sink, property, Handle::kSinkProperty}; } -wpi::span EnumerateSinkProperties( +std::span EnumerateSinkProperties( CS_Sink sink, wpi::SmallVectorImpl& vec, CS_Status* status) { auto data = Instance::GetInstance().GetSink(sink); if (!data) { @@ -865,12 +865,12 @@ void Shutdown() { // Utility Functions // -wpi::span EnumerateSourceHandles( +std::span EnumerateSourceHandles( wpi::SmallVectorImpl& vec, CS_Status* status) { return Instance::GetInstance().EnumerateSourceHandles(vec); } -wpi::span EnumerateSinkHandles(wpi::SmallVectorImpl& vec, +std::span EnumerateSinkHandles(wpi::SmallVectorImpl& vec, CS_Status* status) { return Instance::GetInstance().EnumerateSinkHandles(vec); } diff --git a/cscore/src/main/native/cpp/jni/CameraServerJNI.cpp b/cscore/src/main/native/cpp/jni/CameraServerJNI.cpp index b99d3225998..4be7e57f479 100644 --- a/cscore/src/main/native/cpp/jni/CameraServerJNI.cpp +++ b/cscore/src/main/native/cpp/jni/CameraServerJNI.cpp @@ -3,12 +3,12 @@ // the WPILib BSD license file in the root directory of this project. #include +#include #include #include #include #include -#include #include "cscore_cpp.h" #include "cscore_cv.h" @@ -296,7 +296,7 @@ static jobject MakeJObject(JNIEnv* env, const cs::RawEvent& event) { } static jobjectArray MakeJObject(JNIEnv* env, - wpi::span arr) { + std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), videoEventCls, nullptr); if (!jarr) { return nullptr; diff --git a/cscore/src/main/native/include/cscore_cpp.h b/cscore/src/main/native/include/cscore_cpp.h index 8b1eab1788c..f20a0664b19 100644 --- a/cscore/src/main/native/include/cscore_cpp.h +++ b/cscore/src/main/native/include/cscore_cpp.h @@ -8,12 +8,12 @@ #include #include +#include #include #include #include #include -#include #include "cscore_c.h" @@ -203,7 +203,7 @@ CS_Source CreateUsbCameraPath(std::string_view name, std::string_view path, CS_Source CreateHttpCamera(std::string_view name, std::string_view url, CS_HttpCameraKind kind, CS_Status* status); CS_Source CreateHttpCamera(std::string_view name, - wpi::span urls, + std::span urls, CS_HttpCameraKind kind, CS_Status* status); CS_Source CreateCvSource(std::string_view name, const VideoMode& mode, CS_Status* status); @@ -230,7 +230,7 @@ bool IsSourceConnected(CS_Source source, CS_Status* status); bool IsSourceEnabled(CS_Source source, CS_Status* status); CS_Property GetSourceProperty(CS_Source source, std::string_view name, CS_Status* status); -wpi::span EnumerateSourceProperties( +std::span EnumerateSourceProperties( CS_Source source, wpi::SmallVectorImpl& vec, CS_Status* status); VideoMode GetSourceVideoMode(CS_Source source, CS_Status* status); @@ -249,7 +249,7 @@ std::string GetSourceConfigJson(CS_Source source, CS_Status* status); wpi::json GetSourceConfigJsonObject(CS_Source source, CS_Status* status); std::vector EnumerateSourceVideoModes(CS_Source source, CS_Status* status); -wpi::span EnumerateSourceSinks(CS_Source source, +std::span EnumerateSourceSinks(CS_Source source, wpi::SmallVectorImpl& vec, CS_Status* status); CS_Source CopySource(CS_Source source, CS_Status* status); @@ -285,7 +285,7 @@ UsbCameraInfo GetUsbCameraInfo(CS_Source source, CS_Status* status); * @{ */ CS_HttpCameraKind GetHttpCameraKind(CS_Source source, CS_Status* status); -void SetHttpCameraUrls(CS_Source source, wpi::span urls, +void SetHttpCameraUrls(CS_Source source, std::span urls, CS_Status* status); std::vector GetHttpCameraUrls(CS_Source source, CS_Status* status); /** @} */ @@ -304,7 +304,7 @@ CS_Property CreateSourceProperty(CS_Source source, std::string_view name, int step, int defaultValue, int value, CS_Status* status); void SetSourceEnumPropertyChoices(CS_Source source, CS_Property property, - wpi::span choices, + std::span choices, CS_Status* status); /** @} */ @@ -335,7 +335,7 @@ std::string_view GetSinkDescription(CS_Sink sink, CS_Status* status); CS_Property GetSinkProperty(CS_Sink sink, std::string_view name, CS_Status* status); -wpi::span EnumerateSinkProperties( +std::span EnumerateSinkProperties( CS_Sink sink, wpi::SmallVectorImpl& vec, CS_Status* status); void SetSinkSource(CS_Sink sink, CS_Source source, CS_Status* status); CS_Property GetSinkSourceProperty(CS_Sink sink, std::string_view name, @@ -430,9 +430,9 @@ void Shutdown(); */ std::vector EnumerateUsbCameras(CS_Status* status); -wpi::span EnumerateSourceHandles( +std::span EnumerateSourceHandles( wpi::SmallVectorImpl& vec, CS_Status* status); -wpi::span EnumerateSinkHandles(wpi::SmallVectorImpl& vec, +std::span EnumerateSinkHandles(wpi::SmallVectorImpl& vec, CS_Status* status); std::string GetHostname(); diff --git a/cscore/src/main/native/include/cscore_oo.h b/cscore/src/main/native/include/cscore_oo.h index 4fd1bff1762..f6fb1741a9c 100644 --- a/cscore/src/main/native/include/cscore_oo.h +++ b/cscore/src/main/native/include/cscore_oo.h @@ -6,13 +6,12 @@ #define CSCORE_CSCORE_OO_H_ #include +#include #include #include #include #include -#include - #include "cscore_cpp.h" namespace cs { @@ -516,7 +515,7 @@ class HttpCamera : public VideoCamera { * @param urls Array of Camera URLs * @param kind Camera kind (e.g. kAxis) */ - HttpCamera(std::string_view name, wpi::span urls, + HttpCamera(std::string_view name, std::span urls, HttpCameraKind kind = kUnknown); /** @@ -541,7 +540,7 @@ class HttpCamera : public VideoCamera { /** * Change the URLs used to connect to the camera. */ - void SetUrls(wpi::span urls); + void SetUrls(std::span urls); /** * Change the URLs used to connect to the camera. @@ -560,7 +559,7 @@ class HttpCamera : public VideoCamera { */ class AxisCamera : public HttpCamera { static std::string HostToUrl(std::string_view host); - static std::vector HostToUrl(wpi::span hosts); + static std::vector HostToUrl(std::span hosts); template static std::vector HostToUrl(std::initializer_list hosts); @@ -595,7 +594,7 @@ class AxisCamera : public HttpCamera { * @param name Source name (arbitrary unique identifier) * @param hosts Array of Camera host IPs/DNS names */ - AxisCamera(std::string_view name, wpi::span hosts); + AxisCamera(std::string_view name, std::span hosts); /** * Create a source for an Axis IP camera. @@ -696,7 +695,7 @@ class ImageSource : public VideoSource { * @param choices Choices */ void SetEnumPropertyChoices(const VideoProperty& property, - wpi::span choices); + std::span choices); /** * Configure enum property choices. diff --git a/cscore/src/main/native/include/cscore_oo.inc b/cscore/src/main/native/include/cscore_oo.inc index 5037d979828..ff3540d2aa6 100644 --- a/cscore/src/main/native/include/cscore_oo.inc +++ b/cscore/src/main/native/include/cscore_oo.inc @@ -302,7 +302,7 @@ inline HttpCamera::HttpCamera(std::string_view name, const std::string& url, : HttpCamera(name, std::string_view{url}, kind) {} inline HttpCamera::HttpCamera(std::string_view name, - wpi::span urls, + std::span urls, HttpCameraKind kind) { m_handle = CreateHttpCamera( name, urls, static_cast(static_cast(kind)), @@ -329,7 +329,7 @@ inline HttpCamera::HttpCameraKind HttpCamera::GetHttpCameraKind() const { static_cast(::cs::GetHttpCameraKind(m_handle, &m_status))); } -inline void HttpCamera::SetUrls(wpi::span urls) { +inline void HttpCamera::SetUrls(std::span urls) { m_status = 0; ::cs::SetHttpCameraUrls(m_handle, urls, &m_status); } @@ -351,7 +351,7 @@ inline std::vector HttpCamera::GetUrls() const { } inline std::vector AxisCamera::HostToUrl( - wpi::span hosts) { + std::span hosts) { std::vector rv; rv.reserve(hosts.size()); for (const auto& host : hosts) { @@ -381,7 +381,7 @@ inline AxisCamera::AxisCamera(std::string_view name, const std::string& host) : HttpCamera(name, HostToUrl(std::string_view{host}), kAxis) {} inline AxisCamera::AxisCamera(std::string_view name, - wpi::span hosts) + std::span hosts) : HttpCamera(name, HostToUrl(hosts), kAxis) {} template @@ -452,7 +452,7 @@ inline VideoProperty ImageSource::CreateStringProperty(std::string_view name, } inline void ImageSource::SetEnumPropertyChoices( - const VideoProperty& property, wpi::span choices) { + const VideoProperty& property, std::span choices) { m_status = 0; SetSourceEnumPropertyChoices(m_handle, property.m_handle, choices, &m_status); } diff --git a/datalogtool/src/main/native/cpp/DataLogThread.h b/datalogtool/src/main/native/cpp/DataLogThread.h index 0a273369ca2..267aa1fef8b 100644 --- a/datalogtool/src/main/native/cpp/DataLogThread.h +++ b/datalogtool/src/main/native/cpp/DataLogThread.h @@ -20,7 +20,7 @@ class DataLogThread { public: explicit DataLogThread(wpi::log::DataLogReader reader) - : m_reader{std::move(reader)}, m_thread{[=] { ReadMain(); }} {} + : m_reader{std::move(reader)}, m_thread{[=, this] { ReadMain(); }} {} ~DataLogThread(); bool IsDone() const { return m_done; } diff --git a/datalogtool/src/main/native/cpp/Exporter.cpp b/datalogtool/src/main/native/cpp/Exporter.cpp index 0a1c5e21126..f28545f56b1 100644 --- a/datalogtool/src/main/native/cpp/Exporter.cpp +++ b/datalogtool/src/main/native/cpp/Exporter.cpp @@ -107,7 +107,7 @@ static void RebuildEntryTree() { // get to leaf auto nodes = &gEntryTree; - for (auto part : wpi::drop_back(wpi::span{parts.begin(), parts.end()})) { + for (auto part : wpi::drop_back(std::span{parts.begin(), parts.end()})) { auto it = std::find_if(nodes->begin(), nodes->end(), [&](const auto& node) { return node.name == part; }); diff --git a/datalogtool/src/main/native/cpp/Sftp.cpp b/datalogtool/src/main/native/cpp/Sftp.cpp index f6e627c2bf6..3a33d13afe3 100644 --- a/datalogtool/src/main/native/cpp/Sftp.cpp +++ b/datalogtool/src/main/native/cpp/Sftp.cpp @@ -90,7 +90,7 @@ size_t File::AsyncRead(void* data, uint32_t len, AsyncId id) { return rv; } -size_t File::Write(wpi::span data) { +size_t File::Write(std::span data) { auto rv = sftp_write(m_handle, data.data(), data.size()); if (rv < 0) { throw Exception{m_handle->sftp}; diff --git a/datalogtool/src/main/native/cpp/Sftp.h b/datalogtool/src/main/native/cpp/Sftp.h index e57a747fad3..e6fec4ae909 100644 --- a/datalogtool/src/main/native/cpp/Sftp.h +++ b/datalogtool/src/main/native/cpp/Sftp.h @@ -7,13 +7,12 @@ #include #include +#include #include #include #include #include -#include - namespace sftp { struct Attributes { @@ -53,7 +52,7 @@ class File { size_t Read(void* buf, uint32_t count); AsyncId AsyncReadBegin(uint32_t len) const; size_t AsyncRead(void* data, uint32_t len, AsyncId id); - size_t Write(wpi::span data); + size_t Write(std::span data); void Seek(uint64_t offset); uint64_t Tell() const; diff --git a/docs/build.gradle b/docs/build.gradle index 691264cebc1..35935f69a7b 100644 --- a/docs/build.gradle +++ b/docs/build.gradle @@ -57,7 +57,6 @@ doxygen { if (project.hasProperty('docWarningsAsErrors')) { // C++20 shims exclude 'wpi/ghc/filesystem.hpp' - exclude 'wpi/span.h' // Drake exclude 'drake/common/**' diff --git a/fieldImages/CMakeLists.txt b/fieldImages/CMakeLists.txt index 577806debba..bf02505b224 100644 --- a/fieldImages/CMakeLists.txt +++ b/fieldImages/CMakeLists.txt @@ -29,7 +29,7 @@ add_library(fieldImages ${field_images_resources_src}) set_target_properties(fieldImages PROPERTIES DEBUG_POSTFIX "d") set_property(TARGET fieldImages PROPERTY FOLDER "libraries") -target_compile_features(fieldImages PUBLIC cxx_std_17) +target_compile_features(fieldImages PUBLIC cxx_std_20) if (MSVC) target_compile_options(fieldImages PUBLIC /bigobj) endif() diff --git a/glass/src/lib/native/cpp/Storage.cpp b/glass/src/lib/native/cpp/Storage.cpp index 28af20b6544..add62032171 100644 --- a/glass/src/lib/native/cpp/Storage.cpp +++ b/glass/src/lib/native/cpp/Storage.cpp @@ -254,7 +254,7 @@ Storage::Value& Storage::GetValue(std::string_view key) { } \ \ std::vector& Storage::Get##CapsName##Array( \ - std::string_view key, wpi::span defaultVal) { \ + std::string_view key, std::span defaultVal) { \ auto& valuePtr = m_values[key]; \ bool setValue = false; \ if (!valuePtr) { \ diff --git a/glass/src/lib/native/cpp/hardware/Gyro.cpp b/glass/src/lib/native/cpp/hardware/Gyro.cpp index 36a3525d668..607b251974f 100644 --- a/glass/src/lib/native/cpp/hardware/Gyro.cpp +++ b/glass/src/lib/native/cpp/hardware/Gyro.cpp @@ -10,7 +10,7 @@ #include #include -#include +#include #include "glass/Context.h" #include "glass/DataSource.h" @@ -54,7 +54,7 @@ void glass::DisplayGyro(GyroModel* m) { // Draw the spokes at every 5 degrees and a "major" spoke every 45 degrees. for (int i = -175; i <= 180; i += 5) { - double radians = i * 2 * wpi::numbers::pi / 360.0; + double radians = i * 2 * std::numbers::pi / 360.0; ImVec2 direction(std::sin(radians), -std::cos(radians)); bool major = i % 45 == 0; @@ -74,7 +74,7 @@ void glass::DisplayGyro(GyroModel* m) { draw->AddCircleFilled(center, radius * 0.075, secondaryColor, 50); - double radians = value * 2 * wpi::numbers::pi / 360.0; + double radians = value * 2 * std::numbers::pi / 360.0; draw->AddLine( center - ImVec2(1, 0), center + ImVec2(std::sin(radians), -std::cos(radians)) * radius * 0.95f, diff --git a/glass/src/lib/native/cpp/other/Drive.cpp b/glass/src/lib/native/cpp/other/Drive.cpp index a73c6de21f8..d54b2da825b 100644 --- a/glass/src/lib/native/cpp/other/Drive.cpp +++ b/glass/src/lib/native/cpp/other/Drive.cpp @@ -11,7 +11,7 @@ #include #include -#include +#include #include "glass/Context.h" #include "glass/DataSource.h" @@ -55,11 +55,11 @@ void glass::DisplayDrive(DriveModel* m) { draw->AddTriangleFilled( arrowPos, arrowPos + ImRotate(ImVec2(0.0f, 7.5f), - std::cos(angle + wpi::numbers::pi / 4), - std::sin(angle + wpi::numbers::pi / 4)), + std::cos(angle + std::numbers::pi / 4), + std::sin(angle + std::numbers::pi / 4)), arrowPos + ImRotate(ImVec2(0.0f, 7.5f), - std::cos(angle - wpi::numbers::pi / 4), - std::sin(angle - wpi::numbers::pi / 4)), + std::cos(angle - std::numbers::pi / 4), + std::sin(angle - std::numbers::pi / 4)), color); }; @@ -88,30 +88,30 @@ void glass::DisplayDrive(DriveModel* m) { if (rotation != 0) { float radius = 60.0f; double a1 = 0.0; - double a2 = wpi::numbers::pi / 2 * rotation; + double a2 = std::numbers::pi / 2 * rotation; // PathArcTo requires a_min <= a_max, and rotation can be negative if (a1 > a2) { draw->PathArcTo(center, radius, a2, a1, 20); draw->PathStroke(color, false); - draw->PathArcTo(center, radius, a2 + wpi::numbers::pi, - a1 + wpi::numbers::pi, 20); + draw->PathArcTo(center, radius, a2 + std::numbers::pi, + a1 + std::numbers::pi, 20); draw->PathStroke(color, false); } else { draw->PathArcTo(center, radius, a1, a2, 20); draw->PathStroke(color, false); - draw->PathArcTo(center, radius, a1 + wpi::numbers::pi, - a2 + wpi::numbers::pi, 20); + draw->PathArcTo(center, radius, a1 + std::numbers::pi, + a2 + std::numbers::pi, 20); draw->PathStroke(color, false); } - double adder = rotation < 0 ? wpi::numbers::pi : 0; + double adder = rotation < 0 ? std::numbers::pi : 0; auto arrowPos = center + ImVec2(radius * -std::cos(a2), radius * -std::sin(a2)); drawArrow(arrowPos, a2 + adder); - a2 += wpi::numbers::pi; + a2 += std::numbers::pi; arrowPos = center + ImVec2(radius * -std::cos(a2), radius * -std::sin(a2)); drawArrow(arrowPos, a2 + adder); } diff --git a/glass/src/lib/native/cpp/other/Field2D.cpp b/glass/src/lib/native/cpp/other/Field2D.cpp index c3ef86097f8..c320ac943b4 100644 --- a/glass/src/lib/native/cpp/other/Field2D.cpp +++ b/glass/src/lib/native/cpp/other/Field2D.cpp @@ -93,7 +93,7 @@ class PopupState { SelectedTargetInfo* GetTarget() { return &m_target; } FieldObjectModel* GetInsertModel() { return m_insertModel; } - wpi::span GetInsertPoses() const { return m_insertPoses; } + std::span GetInsertPoses() const { return m_insertPoses; } void Display(Field2DModel* model, const FieldFrameData& ffd); @@ -189,7 +189,7 @@ class ObjectInfo { DisplayOptions GetDisplayOptions() const; void DisplaySettings(); - void DrawLine(ImDrawList* drawList, wpi::span points) const; + void DrawLine(ImDrawList* drawList, std::span points) const; void LoadImage(); const gui::Texture& GetTexture() const { return m_texture; } @@ -617,7 +617,7 @@ void ObjectInfo::DisplaySettings() { } void ObjectInfo::DrawLine(ImDrawList* drawList, - wpi::span points) const { + std::span points) const { if (points.empty()) { return; } diff --git a/glass/src/lib/native/include/glass/Storage.h b/glass/src/lib/native/include/glass/Storage.h index 004b8b42521..7ebfa6d9b27 100644 --- a/glass/src/lib/native/include/glass/Storage.h +++ b/glass/src/lib/native/include/glass/Storage.h @@ -8,6 +8,7 @@ #include #include +#include #include #include #include @@ -15,7 +16,6 @@ #include #include -#include namespace wpi { class json; @@ -137,17 +137,17 @@ class Storage { std::string_view defaultVal = {}); std::vector& GetIntArray(std::string_view key, - wpi::span defaultVal = {}); + std::span defaultVal = {}); std::vector& GetInt64Array(std::string_view key, - wpi::span defaultVal = {}); + std::span defaultVal = {}); std::vector& GetBoolArray(std::string_view key, - wpi::span defaultVal = {}); + std::span defaultVal = {}); std::vector& GetFloatArray(std::string_view key, - wpi::span defaultVal = {}); + std::span defaultVal = {}); std::vector& GetDoubleArray(std::string_view key, - wpi::span defaultVal = {}); + std::span defaultVal = {}); std::vector& GetStringArray( - std::string_view key, wpi::span defaultVal = {}); + std::string_view key, std::span defaultVal = {}); std::vector>& GetChildArray(std::string_view key); Value* FindValue(std::string_view key); diff --git a/glass/src/lib/native/include/glass/hardware/LEDDisplay.h b/glass/src/lib/native/include/glass/hardware/LEDDisplay.h index ddd3c27ca0b..3aee6ae0f0e 100644 --- a/glass/src/lib/native/include/glass/hardware/LEDDisplay.h +++ b/glass/src/lib/native/include/glass/hardware/LEDDisplay.h @@ -4,8 +4,9 @@ #pragma once +#include + #include -#include #include "glass/Model.h" @@ -27,7 +28,7 @@ class LEDDisplayModel : public glass::Model { virtual bool IsRunning() = 0; - virtual wpi::span GetData(wpi::SmallVectorImpl& buf) = 0; + virtual std::span GetData(wpi::SmallVectorImpl& buf) = 0; }; class LEDDisplaysModel : public glass::Model { diff --git a/glass/src/lib/native/include/glass/other/Field2D.h b/glass/src/lib/native/include/glass/other/Field2D.h index 9399876ac5b..7b99292512a 100644 --- a/glass/src/lib/native/include/glass/other/Field2D.h +++ b/glass/src/lib/native/include/glass/other/Field2D.h @@ -4,6 +4,7 @@ #pragma once +#include #include #include @@ -11,7 +12,6 @@ #include #include #include -#include #include "glass/Model.h" #include "glass/View.h" @@ -22,8 +22,8 @@ class FieldObjectModel : public Model { public: virtual const char* GetName() const = 0; - virtual wpi::span GetPoses() = 0; - virtual void SetPoses(wpi::span poses) = 0; + virtual std::span GetPoses() = 0; + virtual void SetPoses(std::span poses) = 0; virtual void SetPose(size_t i, frc::Pose2d pose) = 0; virtual void SetPosition(size_t i, frc::Translation2d pos) = 0; virtual void SetRotation(size_t i, frc::Rotation2d rot) = 0; diff --git a/glass/src/lib/native/include/glass/other/StringChooser.h b/glass/src/lib/native/include/glass/other/StringChooser.h index f345585d701..066c44408a7 100644 --- a/glass/src/lib/native/include/glass/other/StringChooser.h +++ b/glass/src/lib/native/include/glass/other/StringChooser.h @@ -8,8 +8,6 @@ #include #include -#include - #include "glass/Model.h" namespace glass { diff --git a/glass/src/libnt/native/cpp/NTField2D.cpp b/glass/src/libnt/native/cpp/NTField2D.cpp index 79dd12c294d..60e9759773e 100644 --- a/glass/src/libnt/native/cpp/NTField2D.cpp +++ b/glass/src/libnt/native/cpp/NTField2D.cpp @@ -32,8 +32,8 @@ class NTField2DModel::ObjectModel : public FieldObjectModel { bool Exists() override { return m_topic.Exists(); } bool IsReadOnly() override { return false; } - wpi::span GetPoses() override { return m_poses; } - void SetPoses(wpi::span poses) override; + std::span GetPoses() override { return m_poses; } + void SetPoses(std::span poses) override; void SetPose(size_t i, frc::Pose2d pose) override; void SetPosition(size_t i, frc::Translation2d pos) override; void SetRotation(size_t i, frc::Rotation2d rot) override; @@ -78,7 +78,7 @@ void NTField2DModel::ObjectModel::UpdateNT() { m_pub.Set(arr); } -void NTField2DModel::ObjectModel::SetPoses(wpi::span poses) { +void NTField2DModel::ObjectModel::SetPoses(std::span poses) { m_poses.assign(poses.begin(), poses.end()); UpdateNT(); } diff --git a/glass/src/libnt/native/cpp/NetworkTables.cpp b/glass/src/libnt/native/cpp/NetworkTables.cpp index a8e7d6db501..966680798d6 100644 --- a/glass/src/libnt/native/cpp/NetworkTables.cpp +++ b/glass/src/libnt/native/cpp/NetworkTables.cpp @@ -9,6 +9,7 @@ #include #include #include +#include #include #include @@ -25,7 +26,6 @@ #include #include #include -#include #include "glass/Context.h" #include "glass/DataSource.h" @@ -58,7 +58,7 @@ static bool IsVisible(ShowCategory category, bool persistent, bool retained) { } } -static std::string BooleanArrayToString(wpi::span in) { +static std::string BooleanArrayToString(std::span in) { std::string rv; wpi::raw_string_ostream os{rv}; os << '['; @@ -78,17 +78,17 @@ static std::string BooleanArrayToString(wpi::span in) { return rv; } -static std::string IntegerArrayToString(wpi::span in) { +static std::string IntegerArrayToString(std::span in) { return fmt::format("[{:d}]", fmt::join(in, ",")); } template -static std::string FloatArrayToString(wpi::span in) { +static std::string FloatArrayToString(std::span in) { static_assert(std::is_same_v || std::is_same_v); return fmt::format("[{:.6f}]", fmt::join(in, ",")); } -static std::string StringArrayToString(wpi::span in) { +static std::string StringArrayToString(std::span in) { std::string rv; wpi::raw_string_ostream os{rv}; os << '['; @@ -528,7 +528,7 @@ void NetworkTablesModel::RebuildTreeImpl(std::vector* tree, // get to leaf auto nodes = tree; - for (auto part : wpi::drop_back(wpi::span{parts.begin(), parts.end()})) { + for (auto part : wpi::drop_back(std::span{parts.begin(), parts.end()})) { auto it = std::find_if(nodes->begin(), nodes->end(), [&](const auto& node) { return node.name == part; }); @@ -584,7 +584,7 @@ NetworkTablesModel::Entry* NetworkTablesModel::AddEntry(NT_Topic topic) { } void NetworkTablesModel::Client::UpdatePublishers( - wpi::span data) { + std::span data) { mpack_reader_t r; mpack_reader_init_data(&r, data); uint32_t numPub = mpack_expect_array_max(&r, 1000); @@ -639,7 +639,7 @@ static void DecodeSubscriberOptions( } void NetworkTablesModel::Client::UpdateSubscribers( - wpi::span data) { + std::span data) { mpack_reader_t r; mpack_reader_init_data(&r, data); uint32_t numSub = mpack_expect_array_max(&r, 1000); @@ -681,7 +681,7 @@ void NetworkTablesModel::Client::UpdateSubscribers( } } -void NetworkTablesModel::UpdateClients(wpi::span data) { +void NetworkTablesModel::UpdateClients(std::span data) { mpack_reader_t r; mpack_reader_init_data(&r, data); uint32_t numClients = mpack_expect_array_max(&r, 100); diff --git a/glass/src/libnt/native/include/glass/networktables/NetworkTables.h b/glass/src/libnt/native/include/glass/networktables/NetworkTables.h index 31f5ca3082f..2caa244ed4f 100644 --- a/glass/src/libnt/native/include/glass/networktables/NetworkTables.h +++ b/glass/src/libnt/native/include/glass/networktables/NetworkTables.h @@ -7,6 +7,7 @@ #include #include #include +#include #include #include #include @@ -143,8 +144,8 @@ class NetworkTablesModel : public Model { std::vector publishers; std::vector subscribers; - void UpdatePublishers(wpi::span data); - void UpdateSubscribers(wpi::span data); + void UpdatePublishers(std::span data); + void UpdateSubscribers(std::span data); }; NetworkTablesModel(); @@ -175,7 +176,7 @@ class NetworkTablesModel : public Model { private: void RebuildTree(); void RebuildTreeImpl(std::vector* tree, int category); - void UpdateClients(wpi::span data); + void UpdateClients(std::span data); nt::NetworkTableInstance m_inst; NT_MultiSubscriber m_subscriber; diff --git a/googletest/CMakeLists.txt b/googletest/CMakeLists.txt index b06e3266ed3..fdbf088ef52 100644 --- a/googletest/CMakeLists.txt +++ b/googletest/CMakeLists.txt @@ -23,5 +23,5 @@ add_subdirectory(${CMAKE_CURRENT_BINARY_DIR}/googletest-src ${CMAKE_CURRENT_BINARY_DIR}/googletest-build EXCLUDE_FROM_ALL) -target_compile_features(gtest PUBLIC cxx_std_17) -target_compile_features(gtest_main PUBLIC cxx_std_17) +target_compile_features(gtest PUBLIC cxx_std_20) +target_compile_features(gtest_main PUBLIC cxx_std_20) diff --git a/hal/src/main/native/cpp/jni/simulation/AddressableLEDDataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/AddressableLEDDataJNI.cpp index e888bd3ca9d..70b31ab2b39 100644 --- a/hal/src/main/native/cpp/jni/simulation/AddressableLEDDataJNI.cpp +++ b/hal/src/main/native/cpp/jni/simulation/AddressableLEDDataJNI.cpp @@ -257,7 +257,7 @@ Java_edu_wpi_first_hal_simulation_AddressableLEDDataJNI_getData std::make_unique(HAL_kAddressableLEDMaxLength); int32_t length = HALSIM_GetAddressableLEDData(index, data.get()); return MakeJByteArray( - env, wpi::span(reinterpret_cast(data.get()), length * 4)); + env, std::span(reinterpret_cast(data.get()), length * 4)); } /* diff --git a/hal/src/main/native/cpp/jni/simulation/SimDeviceDataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/SimDeviceDataJNI.cpp index 60ce0f7a770..cd8091ff304 100644 --- a/hal/src/main/native/cpp/jni/simulation/SimDeviceDataJNI.cpp +++ b/hal/src/main/native/cpp/jni/simulation/SimDeviceDataJNI.cpp @@ -668,7 +668,7 @@ Java_edu_wpi_first_hal_simulation_SimDeviceDataJNI_getSimValueEnumDoubleValues { int32_t numElems = 0; const double* elems = HALSIM_GetSimValueEnumDoubleValues(handle, &numElems); - return MakeJDoubleArray(env, wpi::span(elems, numElems)); + return MakeJDoubleArray(env, std::span(elems, numElems)); } /* diff --git a/hal/src/main/native/cpp/jni/simulation/SpiReadAutoReceiveBufferCallbackStore.cpp b/hal/src/main/native/cpp/jni/simulation/SpiReadAutoReceiveBufferCallbackStore.cpp index c20f60729f2..bf7242d3078 100644 --- a/hal/src/main/native/cpp/jni/simulation/SpiReadAutoReceiveBufferCallbackStore.cpp +++ b/hal/src/main/native/cpp/jni/simulation/SpiReadAutoReceiveBufferCallbackStore.cpp @@ -59,7 +59,7 @@ int32_t SpiReadAutoReceiveBufferCallbackStore::performCallback( } auto toCallbackArr = MakeJIntArray( - env, wpi::span{buffer, static_cast(numToRead)}); + env, std::span{buffer, static_cast(numToRead)}); jint ret = env->CallIntMethod(m_call, sim::GetBufferCallback(), MakeJString(env, name), toCallbackArr, diff --git a/hal/src/main/native/include/hal/SimDevice.h b/hal/src/main/native/include/hal/SimDevice.h index 7c0cf2d336c..f90cb9bb5b4 100644 --- a/hal/src/main/native/include/hal/SimDevice.h +++ b/hal/src/main/native/include/hal/SimDevice.h @@ -8,8 +8,7 @@ #ifdef __cplusplus #include - -#include +#include #endif #include "hal/Types.h" @@ -832,7 +831,7 @@ class SimDevice { * @return simulated enum value object */ SimEnum CreateEnum(const char* name, int32_t direction, - wpi::span options, + std::span options, int32_t initialValue) { return HAL_CreateSimValueEnum(m_handle, name, direction, options.size(), const_cast(options.data()), @@ -885,8 +884,8 @@ class SimDevice { * @return simulated enum value object */ SimEnum CreateEnumDouble(const char* name, int32_t direction, - wpi::span options, - wpi::span optionValues, + std::span options, + std::span optionValues, int32_t initialValue) { if (options.size() != optionValues.size()) { return {}; diff --git a/hal/src/main/native/include/hal/cpp/UnsafeDIO.h b/hal/src/main/native/include/hal/cpp/UnsafeDIO.h index eb7f2313010..c849fd08d9f 100644 --- a/hal/src/main/native/include/hal/cpp/UnsafeDIO.h +++ b/hal/src/main/native/include/hal/cpp/UnsafeDIO.h @@ -18,6 +18,16 @@ namespace hal { * outside of the UnsafeManipulateDIO callback. */ struct DIOSetProxy { + DIOSetProxy(tDIO::tOutputEnable setOutputDirReg, + tDIO::tOutputEnable unsetOutputDirReg, + tDIO::tDO setOutputStateReg, tDIO::tDO unsetOutputStateReg, + tDIO* dio) + : m_setOutputDirReg{setOutputDirReg}, + m_unsetOutputDirReg{unsetOutputDirReg}, + m_setOutputStateReg{setOutputStateReg}, + m_unsetOutputStateReg{unsetOutputStateReg}, + m_dio{dio} {} + DIOSetProxy(const DIOSetProxy&) = delete; DIOSetProxy(DIOSetProxy&&) = delete; DIOSetProxy& operator=(const DIOSetProxy&) = delete; diff --git a/imgui/CMakeLists.txt b/imgui/CMakeLists.txt index 9f2ac742497..6b4e9ed6166 100644 --- a/imgui/CMakeLists.txt +++ b/imgui/CMakeLists.txt @@ -71,4 +71,4 @@ target_link_libraries(imgui PUBLIC gl3w glfw) target_include_directories(imgui PUBLIC "$" "$" "$" "$" "$" "$") set_property(TARGET imgui PROPERTY POSITION_INDEPENDENT_CODE ON) -target_compile_features(imgui PUBLIC cxx_std_17) +target_compile_features(imgui PUBLIC cxx_std_20) diff --git a/ntcore/CMakeLists.txt b/ntcore/CMakeLists.txt index df25b57f5f0..2491edd5cb0 100644 --- a/ntcore/CMakeLists.txt +++ b/ntcore/CMakeLists.txt @@ -28,7 +28,7 @@ target_include_directories(ntcore $ $) wpilib_target_warnings(ntcore) -target_compile_features(ntcore PUBLIC cxx_std_17) +target_compile_features(ntcore PUBLIC cxx_std_20) target_link_libraries(ntcore PUBLIC wpinet wpiutil) set_property(TARGET ntcore PROPERTY FOLDER "libraries") diff --git a/ntcore/src/generate/cpp/jni/types_jni.cpp.jinja b/ntcore/src/generate/cpp/jni/types_jni.cpp.jinja index 6c26463b7d1..a1052784dcf 100644 --- a/ntcore/src/generate/cpp/jni/types_jni.cpp.jinja +++ b/ntcore/src/generate/cpp/jni/types_jni.cpp.jinja @@ -74,7 +74,7 @@ static std::vector FromJavaBooleanArray(JNIEnv* env, jbooleanArray jarr) { if (!ref) { return {}; } - wpi::span elements{ref}; + std::span elements{ref}; size_t len = elements.size(); std::vector arr; arr.reserve(len); @@ -118,7 +118,7 @@ static jobject MakeJObject(JNIEnv* env, nt::Timestamped{{ t.TypeName }} value) { {% endfor %} {%- for t in types %} static jobjectArray MakeJObject(JNIEnv* env, - wpi::span arr) { + std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), timestamped{{ t.TypeName }}Cls, nullptr); if (!jarr) { @@ -133,7 +133,7 @@ static jobjectArray MakeJObject(JNIEnv* env, {% endfor %} {%- for t in types %} {%- if t.jni.ToJavaArray == "MakeJObjectArray" %} -static jobjectArray MakeJObjectArray(JNIEnv* env, wpi::span arr) { +static jobjectArray MakeJObjectArray(JNIEnv* env, std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), {{ t.jni.jtype }}Cls, nullptr); if (!jarr) { diff --git a/ntcore/src/generate/cpp/ntcore_c_types.cpp.jinja b/ntcore/src/generate/cpp/ntcore_c_types.cpp.jinja index 342d444ceee..e74e5cf776c 100644 --- a/ntcore/src/generate/cpp/ntcore_c_types.cpp.jinja +++ b/ntcore/src/generate/cpp/ntcore_c_types.cpp.jinja @@ -10,7 +10,7 @@ using namespace nt; template -static inline wpi::span ConvertFromC(const T* arr, size_t size) { +static inline std::span ConvertFromC(const T* arr, size_t size) { return {arr, size}; } diff --git a/ntcore/src/generate/include/networktables/Topic.h.jinja b/ntcore/src/generate/include/networktables/Topic.h.jinja index d367de5fa1e..0b251e56884 100644 --- a/ntcore/src/generate/include/networktables/Topic.h.jinja +++ b/ntcore/src/generate/include/networktables/Topic.h.jinja @@ -7,11 +7,10 @@ #include {{ cpp.INCLUDES }} +#include #include #include -#include - #include "networktables/Topic.h" namespace wpi { @@ -312,7 +311,7 @@ class {{ TypeName }}Topic final : public Topic { [[nodiscard]] SubscriberType Subscribe( {% if not TypeString %}std::string_view typeString, {% endif %}ParamType defaultValue, - wpi::span options = {}); + std::span options = {}); {%- if TypeString %} /** * Create a new subscriber to the topic, with specific type string. @@ -333,7 +332,7 @@ class {{ TypeName }}Topic final : public Topic { [[nodiscard]] SubscriberType SubscribeEx( std::string_view typeString, ParamType defaultValue, - wpi::span options = {}); + std::span options = {}); {% endif %} /** * Create a new publisher to the topic. @@ -354,7 +353,7 @@ class {{ TypeName }}Topic final : public Topic { * @return publisher */ [[nodiscard]] - PublisherType Publish({% if not TypeString %}std::string_view typeString, {% endif %}wpi::span options = {}); + PublisherType Publish({% if not TypeString %}std::string_view typeString, {% endif %}std::span options = {}); /** * Create a new publisher to the topic, with type string and initial @@ -376,7 +375,7 @@ class {{ TypeName }}Topic final : public Topic { */ [[nodiscard]] PublisherType PublishEx(std::string_view typeString, - const wpi::json& properties, wpi::span options = {}); + const wpi::json& properties, std::span options = {}); /** * Create a new entry for the topic. @@ -403,7 +402,7 @@ class {{ TypeName }}Topic final : public Topic { */ [[nodiscard]] EntryType GetEntry({% if not TypeString %}std::string_view typeString, {% endif %}ParamType defaultValue, - wpi::span options = {}); + std::span options = {}); {%- if TypeString %} /** * Create a new entry for the topic, with specific type string. @@ -428,7 +427,7 @@ class {{ TypeName }}Topic final : public Topic { */ [[nodiscard]] EntryType GetEntryEx(std::string_view typeString, ParamType defaultValue, - wpi::span options = {}); + std::span options = {}); {% endif %} }; diff --git a/ntcore/src/generate/include/networktables/Topic.inc.jinja b/ntcore/src/generate/include/networktables/Topic.inc.jinja index e996ed39caf..17d250e5a0e 100644 --- a/ntcore/src/generate/include/networktables/Topic.inc.jinja +++ b/ntcore/src/generate/include/networktables/Topic.inc.jinja @@ -89,7 +89,7 @@ inline void {{ TypeName }}Entry::Unpublish() { inline {{ TypeName }}Subscriber {{ TypeName }}Topic::Subscribe( {% if not TypeString %}std::string_view typeString, {% endif %}{{ cpp.ParamType }} defaultValue, - wpi::span options) { + std::span options) { return {{ TypeName }}Subscriber{ ::nt::Subscribe(m_handle, NT_{{ cpp.TYPE_NAME }}, {{ TypeString|default('typeString') }}, options), defaultValue}; @@ -97,28 +97,28 @@ inline {{ TypeName }}Subscriber {{ TypeName }}Topic::Subscribe( {%- if TypeString %} inline {{ TypeName }}Subscriber {{ TypeName }}Topic::SubscribeEx( std::string_view typeString, {{ cpp.ParamType }} defaultValue, - wpi::span options) { + std::span options) { return {{ TypeName }}Subscriber{ ::nt::Subscribe(m_handle, NT_{{ cpp.TYPE_NAME }}, typeString, options), defaultValue}; } {% endif %} inline {{ TypeName }}Publisher {{ TypeName }}Topic::Publish( - {% if not TypeString %}std::string_view typeString, {% endif %}wpi::span options) { + {% if not TypeString %}std::string_view typeString, {% endif %}std::span options) { return {{ TypeName }}Publisher{ ::nt::Publish(m_handle, NT_{{ cpp.TYPE_NAME }}, {{ TypeString|default('typeString') }}, options)}; } inline {{ TypeName }}Publisher {{ TypeName }}Topic::PublishEx( std::string_view typeString, - const wpi::json& properties, wpi::span options) { + const wpi::json& properties, std::span options) { return {{ TypeName }}Publisher{ ::nt::PublishEx(m_handle, NT_{{ cpp.TYPE_NAME }}, typeString, properties, options)}; } inline {{ TypeName }}Entry {{ TypeName }}Topic::GetEntry( {% if not TypeString %}std::string_view typeString, {% endif %}{{ cpp.ParamType }} defaultValue, - wpi::span options) { + std::span options) { return {{ TypeName }}Entry{ ::nt::GetEntry(m_handle, NT_{{ cpp.TYPE_NAME }}, {{ TypeString|default('typeString') }}, options), defaultValue}; @@ -126,7 +126,7 @@ inline {{ TypeName }}Entry {{ TypeName }}Topic::GetEntry( {%- if TypeString %} inline {{ TypeName }}Entry {{ TypeName }}Topic::GetEntryEx( std::string_view typeString, {{ cpp.ParamType }} defaultValue, - wpi::span options) { + std::span options) { return {{ TypeName }}Entry{ ::nt::GetEntry(m_handle, NT_{{ cpp.TYPE_NAME }}, typeString, options), defaultValue}; diff --git a/ntcore/src/generate/include/ntcore_cpp_types.h.jinja b/ntcore/src/generate/include/ntcore_cpp_types.h.jinja index 8ca926e7e02..e987186aa6b 100644 --- a/ntcore/src/generate/include/ntcore_cpp_types.h.jinja +++ b/ntcore/src/generate/include/ntcore_cpp_types.h.jinja @@ -6,13 +6,12 @@ #include +#include #include #include #include #include -#include - #include "ntcore_c.h" namespace wpi { diff --git a/ntcore/src/generate/types.json b/ntcore/src/generate/types.json index 6248fdf0238..31a71b3b126 100644 --- a/ntcore/src/generate/types.json +++ b/ntcore/src/generate/types.json @@ -167,11 +167,11 @@ }, "cpp": { "ValueType": "std::vector", - "ParamType": "wpi::span", + "ParamType": "std::span", "DefaultValueCopy": "defaultValue.begin(), defaultValue.end()", "TYPE_NAME": "RAW", "INCLUDES": "#include ", - "SmallRetType": "wpi::span", + "SmallRetType": "std::span", "SmallElemType": "uint8_t" }, "java": { @@ -201,11 +201,11 @@ }, "cpp": { "ValueType": "std::vector", - "ParamType": "wpi::span", + "ParamType": "std::span", "DefaultValueCopy": "defaultValue.begin(), defaultValue.end()", "TYPE_NAME": "BOOLEAN_ARRAY", "INCLUDES": "#include ", - "SmallRetType": "wpi::span", + "SmallRetType": "std::span", "SmallElemType": "int" }, "java": { @@ -236,11 +236,11 @@ }, "cpp": { "ValueType": "std::vector", - "ParamType": "wpi::span", + "ParamType": "std::span", "DefaultValueCopy": "defaultValue.begin(), defaultValue.end()", "TYPE_NAME": "INTEGER_ARRAY", "INCLUDES": "#include ", - "SmallRetType": "wpi::span", + "SmallRetType": "std::span", "SmallElemType": "int64_t" }, "java": { @@ -271,11 +271,11 @@ }, "cpp": { "ValueType": "std::vector", - "ParamType": "wpi::span", + "ParamType": "std::span", "DefaultValueCopy": "defaultValue.begin(), defaultValue.end()", "TYPE_NAME": "FLOAT_ARRAY", "INCLUDES": "#include ", - "SmallRetType": "wpi::span", + "SmallRetType": "std::span", "SmallElemType": "float" }, "java": { @@ -306,11 +306,11 @@ }, "cpp": { "ValueType": "std::vector", - "ParamType": "wpi::span", + "ParamType": "std::span", "DefaultValueCopy": "defaultValue.begin(), defaultValue.end()", "TYPE_NAME": "DOUBLE_ARRAY", "INCLUDES": "#include ", - "SmallRetType": "wpi::span", + "SmallRetType": "std::span", "SmallElemType": "double" }, "java": { @@ -341,7 +341,7 @@ }, "cpp": { "ValueType": "std::vector", - "ParamType": "wpi::span", + "ParamType": "std::span", "DefaultValueCopy": "defaultValue.begin(), defaultValue.end()", "TYPE_NAME": "STRING_ARRAY", "INCLUDES": "#include " diff --git a/ntcore/src/main/native/cpp/INetworkClient.h b/ntcore/src/main/native/cpp/INetworkClient.h index ac90f7baf52..2c14a1bbaa4 100644 --- a/ntcore/src/main/native/cpp/INetworkClient.h +++ b/ntcore/src/main/native/cpp/INetworkClient.h @@ -4,13 +4,12 @@ #pragma once +#include #include #include #include #include -#include - #include "ntcore_cpp.h" namespace nt { @@ -20,7 +19,7 @@ class INetworkClient { virtual ~INetworkClient() = default; virtual void SetServers( - wpi::span> servers) = 0; + std::span> servers) = 0; virtual void StartDSClient(unsigned int port) = 0; virtual void StopDSClient() = 0; diff --git a/ntcore/src/main/native/cpp/LocalStorage.cpp b/ntcore/src/main/native/cpp/LocalStorage.cpp index 8866ef848bd..ac3505dec2e 100644 --- a/ntcore/src/main/native/cpp/LocalStorage.cpp +++ b/ntcore/src/main/native/cpp/LocalStorage.cpp @@ -98,7 +98,7 @@ struct TopicData { struct PubSubConfig : public PubSubOptions { PubSubConfig() = default; PubSubConfig(NT_Type type, std::string_view typeStr, - wpi::span options) + std::span options) : PubSubOptions{options}, type{type}, typeStr{typeStr} {} NT_Type type{NT_UNASSIGNED}; @@ -167,7 +167,7 @@ struct MultiSubscriberData { static constexpr auto kType = Handle::kMultiSubscriber; MultiSubscriberData(NT_MultiSubscriber handle, - wpi::span prefixes, + std::span prefixes, PubSubOptions options) : handle{handle}, options{std::move(options)} { this->options.prefixMatch = true; @@ -208,7 +208,7 @@ struct TopicListenerData { eventMask{eventMask & ~NT_TOPIC_NOTIFY_IMMEDIATE} {} TopicListenerData(NT_TopicListener handle, TopicListenerPollerData* poller, MultiSubscriberData* multiSubscriber, - wpi::span prefixes, + std::span prefixes, unsigned int eventMask) : handle{handle}, poller{poller}, @@ -385,7 +385,7 @@ struct LSImpl { std::unique_ptr RemoveEntry(NT_Entry entryHandle); MultiSubscriberData* AddMultiSubscriber( - wpi::span prefixes, const PubSubOptions& options); + std::span prefixes, const PubSubOptions& options); std::unique_ptr RemoveMultiSubscriber( NT_MultiSubscriber subHandle); @@ -403,9 +403,9 @@ struct LSImpl { unsigned int eventMask); TopicListenerData* AddTopicListenerImpl( TopicListenerPollerData* poller, - wpi::span prefixes, unsigned int eventMask); + std::span prefixes, unsigned int eventMask); NT_TopicListener AddTopicListener( - wpi::span prefixes, unsigned int mask, + std::span prefixes, unsigned int mask, std::function callback); NT_TopicListener AddTopicListenerHandle(TopicListenerPollerData* poller, NT_Handle handle, unsigned int mask); @@ -1053,7 +1053,7 @@ std::unique_ptr LSImpl::RemoveEntry(NT_Entry entryHandle) { } MultiSubscriberData* LSImpl::AddMultiSubscriber( - wpi::span prefixes, const PubSubOptions& options) { + std::span prefixes, const PubSubOptions& options) { auto subscriber = m_multiSubscribers.Add(m_inst, prefixes, options); // subscribe to any already existing topics for (auto&& topic : m_topics) { @@ -1158,7 +1158,7 @@ TopicListenerData* LSImpl::AddTopicListenerImpl(TopicListenerPollerData* poller, } TopicListenerData* LSImpl::AddTopicListenerImpl( - TopicListenerPollerData* poller, wpi::span prefixes, + TopicListenerPollerData* poller, std::span prefixes, unsigned int eventMask) { // subscribe to make sure topic updates are received PubSubOptions options; @@ -1171,7 +1171,7 @@ TopicListenerData* LSImpl::AddTopicListenerImpl( } NT_TopicListener LSImpl::AddTopicListener( - wpi::span prefixes, unsigned int mask, + std::span prefixes, unsigned int mask, std::function callback) { if (!m_topicListenerThread) { m_topicListenerThread.Start(AddTopicListenerPoller()); @@ -1640,7 +1640,7 @@ static void ForEachTopic(T& topics, std::string_view prefix, unsigned int types, template static void ForEachTopic(T& topics, std::string_view prefix, - wpi::span types, F func) { + std::span types, F func) { for (auto&& topic : topics) { if (!topic->Exists()) { continue; @@ -1674,7 +1674,7 @@ std::vector LocalStorage::GetTopics(std::string_view prefix, } std::vector LocalStorage::GetTopics( - std::string_view prefix, wpi::span types) { + std::string_view prefix, std::span types) { std::scoped_lock lock(m_mutex); std::vector rv; ForEachTopic(m_impl->m_topics, prefix, types, @@ -1693,7 +1693,7 @@ std::vector LocalStorage::GetTopicInfo(std::string_view prefix, } std::vector LocalStorage::GetTopicInfo( - std::string_view prefix, wpi::span types) { + std::string_view prefix, std::span types) { std::scoped_lock lock(m_mutex); std::vector rv; ForEachTopic(m_impl->m_topics, prefix, types, [&](TopicData& topic) { @@ -1845,7 +1845,7 @@ TopicInfo LocalStorage::GetTopicInfo(NT_Topic topicHandle) { NT_Subscriber LocalStorage::Subscribe(NT_Topic topicHandle, NT_Type type, std::string_view typeStr, - wpi::span options) { + std::span options) { std::scoped_lock lock{m_mutex}; // Get the topic @@ -1865,8 +1865,8 @@ void LocalStorage::Unsubscribe(NT_Subscriber subHandle) { } NT_MultiSubscriber LocalStorage::SubscribeMultiple( - wpi::span prefixes, - wpi::span options) { + std::span prefixes, + std::span options) { std::scoped_lock lock{m_mutex}; PubSubOptions opts{options}; opts.prefixMatch = true; @@ -1881,7 +1881,7 @@ void LocalStorage::UnsubscribeMultiple(NT_MultiSubscriber subHandle) { NT_Publisher LocalStorage::Publish(NT_Topic topicHandle, NT_Type type, std::string_view typeStr, const wpi::json& properties, - wpi::span options) { + std::span options) { std::scoped_lock lock{m_mutex}; // Get the topic @@ -1923,7 +1923,7 @@ void LocalStorage::Unpublish(NT_Handle pubentryHandle) { NT_Entry LocalStorage::GetEntry(NT_Topic topicHandle, NT_Type type, std::string_view typeStr, - wpi::span options) { + std::span options) { std::scoped_lock lock{m_mutex}; // Get the topic @@ -2038,7 +2038,7 @@ static T GetAtomicNumber(Value* value, U defaultValue) { } template -static T GetAtomicNumberArray(Value* value, wpi::span defaultValue) { +static T GetAtomicNumberArray(Value* value, std::span defaultValue) { if (value && value->type() == NT_INTEGER_ARRAY) { auto arr = value->GetIntegerArray(); return {value->time(), value->server_time(), {arr.begin(), arr.end()}}; @@ -2055,7 +2055,7 @@ static T GetAtomicNumberArray(Value* value, wpi::span defaultValue) { template static T GetAtomicNumberArray(Value* value, wpi::SmallVectorImpl& buf, - wpi::span defaultValue) { + std::span defaultValue) { if (value && value->type() == NT_INTEGER_ARRAY) { auto str = value->GetIntegerArray(); buf.assign(str.begin(), str.end()); @@ -2083,7 +2083,7 @@ static T GetAtomicNumberArray(Value* value, wpi::SmallVectorImpl& buf, } \ \ Timestamped##Name##Array LocalStorage::GetAtomic##Name##Array( \ - NT_Handle subentry, wpi::span defaultValue) { \ + NT_Handle subentry, std::span defaultValue) { \ std::scoped_lock lock{m_mutex}; \ return GetAtomicNumberArray( \ m_impl->GetSubEntryValue(subentry), defaultValue); \ @@ -2091,7 +2091,7 @@ static T GetAtomicNumberArray(Value* value, wpi::SmallVectorImpl& buf, \ Timestamped##Name##ArrayView LocalStorage::GetAtomic##Name##Array( \ NT_Handle subentry, wpi::SmallVectorImpl& buf, \ - wpi::span defaultValue) { \ + std::span defaultValue) { \ std::scoped_lock lock{m_mutex}; \ return GetAtomicNumberArray( \ m_impl->GetSubEntryValue(subentry), buf, defaultValue); \ @@ -2103,7 +2103,7 @@ GET_ATOMIC_NUMBER(Double, double) #define GET_ATOMIC_ARRAY(Name, dtype) \ Timestamped##Name LocalStorage::GetAtomic##Name( \ - NT_Handle subentry, wpi::span defaultValue) { \ + NT_Handle subentry, std::span defaultValue) { \ std::scoped_lock lock{m_mutex}; \ Value* value = m_impl->GetSubEntryValue(subentry); \ if (value && value->Is##Name()) { \ @@ -2121,7 +2121,7 @@ GET_ATOMIC_ARRAY(StringArray, std::string) #define GET_ATOMIC_SMALL_ARRAY(Name, dtype) \ Timestamped##Name##View LocalStorage::GetAtomic##Name( \ NT_Handle subentry, wpi::SmallVectorImpl& buf, \ - wpi::span defaultValue) { \ + std::span defaultValue) { \ std::scoped_lock lock{m_mutex}; \ Value* value = m_impl->GetSubEntryValue(subentry); \ if (value && value->Is##Name()) { \ @@ -2349,7 +2349,7 @@ int64_t LocalStorage::GetEntryLastChange(NT_Handle subentryHandle) { } NT_TopicListener LocalStorage::AddTopicListener( - wpi::span prefixes, unsigned int mask, + std::span prefixes, unsigned int mask, std::function callback) { std::scoped_lock lock{m_mutex}; return m_impl->AddTopicListener(prefixes, mask, std::move(callback)); @@ -2375,7 +2375,7 @@ void LocalStorage::DestroyTopicListenerPoller( NT_TopicListener LocalStorage::AddPolledTopicListener( NT_TopicListenerPoller pollerHandle, - wpi::span prefixes, unsigned int mask) { + std::span prefixes, unsigned int mask) { std::scoped_lock lock{m_mutex}; if (auto poller = m_impl->m_topicListenerPollers.Get(pollerHandle)) { return m_impl->AddTopicListenerImpl(poller, prefixes, mask)->handle; diff --git a/ntcore/src/main/native/cpp/LocalStorage.h b/ntcore/src/main/native/cpp/LocalStorage.h index df786bcccd9..32c4dfb111c 100644 --- a/ntcore/src/main/native/cpp/LocalStorage.h +++ b/ntcore/src/main/native/cpp/LocalStorage.h @@ -8,13 +8,13 @@ #include #include +#include #include #include #include #include #include -#include #include "net/NetworkInterface.h" #include "ntcore_cpp.h" @@ -50,12 +50,12 @@ class LocalStorage final : public net::ILocalStorage { std::vector GetTopics(std::string_view prefix, unsigned int types); std::vector GetTopics(std::string_view prefix, - wpi::span types); + std::span types); std::vector GetTopicInfo(std::string_view prefix, unsigned int types); std::vector GetTopicInfo(std::string_view prefix, - wpi::span types); + std::span types); NT_Topic GetTopic(std::string_view name); @@ -90,24 +90,24 @@ class LocalStorage final : public net::ILocalStorage { NT_Subscriber Subscribe(NT_Topic topic, NT_Type type, std::string_view typeStr, - wpi::span options); + std::span options); void Unsubscribe(NT_Subscriber sub); NT_MultiSubscriber SubscribeMultiple( - wpi::span prefixes, - wpi::span options); + std::span prefixes, + std::span options); void UnsubscribeMultiple(NT_MultiSubscriber subHandle); NT_Publisher Publish(NT_Topic topic, NT_Type type, std::string_view typeStr, const wpi::json& properties, - wpi::span options); + std::span options); void Unpublish(NT_Handle pubentry); NT_Entry GetEntry(NT_Topic topic, NT_Type type, std::string_view typeStr, - wpi::span options); + std::span options); void ReleaseEntry(NT_Entry entry); @@ -126,36 +126,36 @@ class LocalStorage final : public net::ILocalStorage { TimestampedString GetAtomicString(NT_Handle subentry, std::string_view defaultValue); TimestampedRaw GetAtomicRaw(NT_Handle subentry, - wpi::span defaultValue); + std::span defaultValue); TimestampedBooleanArray GetAtomicBooleanArray( - NT_Handle subentry, wpi::span defaultValue); + NT_Handle subentry, std::span defaultValue); TimestampedIntegerArray GetAtomicIntegerArray( - NT_Handle subentry, wpi::span defaultValue); + NT_Handle subentry, std::span defaultValue); TimestampedFloatArray GetAtomicFloatArray( - NT_Handle subentry, wpi::span defaultValue); + NT_Handle subentry, std::span defaultValue); TimestampedDoubleArray GetAtomicDoubleArray( - NT_Handle subentry, wpi::span defaultValue); + NT_Handle subentry, std::span defaultValue); TimestampedStringArray GetAtomicStringArray( - NT_Handle subentry, wpi::span defaultValue); + NT_Handle subentry, std::span defaultValue); TimestampedStringView GetAtomicString(NT_Handle subentry, wpi::SmallVectorImpl& buf, std::string_view defaultValue); TimestampedRawView GetAtomicRaw(NT_Handle subentry, wpi::SmallVectorImpl& buf, - wpi::span defaultValue); + std::span defaultValue); TimestampedBooleanArrayView GetAtomicBooleanArray( NT_Handle subentry, wpi::SmallVectorImpl& buf, - wpi::span defaultValue); + std::span defaultValue); TimestampedIntegerArrayView GetAtomicIntegerArray( NT_Handle subentry, wpi::SmallVectorImpl& buf, - wpi::span defaultValue); + std::span defaultValue); TimestampedFloatArrayView GetAtomicFloatArray( NT_Handle subentry, wpi::SmallVectorImpl& buf, - wpi::span defaultValue); + std::span defaultValue); TimestampedDoubleArrayView GetAtomicDoubleArray( NT_Handle subentry, wpi::SmallVectorImpl& buf, - wpi::span defaultValue); + std::span defaultValue); std::vector ReadQueueValue(NT_Handle subentry); @@ -193,7 +193,7 @@ class LocalStorage final : public net::ILocalStorage { // NT_TopicListener AddTopicListener( - wpi::span prefixes, unsigned int mask, + std::span prefixes, unsigned int mask, std::function callback); NT_TopicListener AddTopicListener( NT_Handle handle, unsigned int mask, @@ -203,7 +203,7 @@ class LocalStorage final : public net::ILocalStorage { void DestroyTopicListenerPoller(NT_TopicListenerPoller poller); NT_TopicListener AddPolledTopicListener( - NT_TopicListenerPoller poller, wpi::span prefixes, + NT_TopicListenerPoller poller, std::span prefixes, unsigned int mask); NT_TopicListener AddPolledTopicListener(NT_TopicListenerPoller poller, NT_Handle handle, unsigned int mask); diff --git a/ntcore/src/main/native/cpp/NetworkClient.cpp b/ntcore/src/main/native/cpp/NetworkClient.cpp index 3295c2438a2..1fb3d00b2db 100644 --- a/ntcore/src/main/native/cpp/NetworkClient.cpp +++ b/ntcore/src/main/native/cpp/NetworkClient.cpp @@ -48,7 +48,7 @@ class NCImpl { virtual ~NCImpl() = default; // user-facing functions - void SetServers(wpi::span> servers, + void SetServers(std::span> servers, unsigned int defaultPort); void StartDSClient(unsigned int port); void StopDSClient(); @@ -135,7 +135,7 @@ NCImpl::NCImpl(int inst, std::string_view id, net::ILocalStorage& localStorage, } void NCImpl::SetServers( - wpi::span> servers, + std::span> servers, unsigned int defaultPort) { std::vector> serversCopy; serversCopy.reserve(servers.size()); @@ -154,7 +154,7 @@ void NCImpl::SetServers( } void NCImpl::StartDSClient(unsigned int port) { - m_loopRunner.ExecAsync([=](uv::Loop& loop) { + m_loopRunner.ExecAsync([=, this](uv::Loop& loop) { if (m_dsClient) { return; } @@ -432,7 +432,7 @@ void NCImpl4::WsConnected(wpi::WebSocket& ws, uv::Tcp& tcp) { ws.text.connect([this](std::string_view data, bool) { m_clientImpl->ProcessIncomingText(data); }); - ws.binary.connect([this](wpi::span data, bool) { + ws.binary.connect([this](std::span data, bool) { m_clientImpl->ProcessIncomingBinary(data); }); } @@ -463,7 +463,7 @@ NetworkClient::~NetworkClient() { } void NetworkClient::SetServers( - wpi::span> servers) { + std::span> servers) { m_impl->SetServers(servers, NT_DEFAULT_PORT4); } @@ -505,7 +505,7 @@ NetworkClient3::~NetworkClient3() { } void NetworkClient3::SetServers( - wpi::span> servers) { + std::span> servers) { m_impl->SetServers(servers, NT_DEFAULT_PORT3); } diff --git a/ntcore/src/main/native/cpp/NetworkClient.h b/ntcore/src/main/native/cpp/NetworkClient.h index d360c716e7a..af42f9854de 100644 --- a/ntcore/src/main/native/cpp/NetworkClient.h +++ b/ntcore/src/main/native/cpp/NetworkClient.h @@ -5,6 +5,7 @@ #pragma once #include +#include #include #include #include @@ -31,7 +32,7 @@ class NetworkClient final : public INetworkClient { ~NetworkClient() final; void SetServers( - wpi::span> servers) final; + std::span> servers) final; void StartDSClient(unsigned int port) final; void StopDSClient() final; @@ -52,7 +53,7 @@ class NetworkClient3 final : public INetworkClient { ~NetworkClient3() final; void SetServers( - wpi::span> servers) final; + std::span> servers) final; void StartDSClient(unsigned int port) final; void StopDSClient() final; diff --git a/ntcore/src/main/native/cpp/NetworkServer.cpp b/ntcore/src/main/native/cpp/NetworkServer.cpp index 11932286071..c9708d75ece 100644 --- a/ntcore/src/main/native/cpp/NetworkServer.cpp +++ b/ntcore/src/main/native/cpp/NetworkServer.cpp @@ -7,6 +7,7 @@ #include #include +#include #include #include @@ -256,7 +257,7 @@ void ServerConnection4::ProcessWsUpgrade() { m_websocket->text.connect([this](std::string_view data, bool) { m_server.m_serverImpl.ProcessIncomingText(m_clientId, data); }); - m_websocket->binary.connect([this](wpi::span data, bool) { + m_websocket->binary.connect([this](std::span data, bool) { m_server.m_serverImpl.ProcessIncomingBinary(m_clientId, data); }); @@ -327,7 +328,7 @@ NSImpl::NSImpl(std::string_view persistentFilename, m_localQueue{logger}, m_loop(*m_loopRunner.GetLoop()) { m_localMsgs.reserve(net::NetworkLoopQueue::kInitialQueueSize); - m_loopRunner.ExecAsync([=](uv::Loop& loop) { + m_loopRunner.ExecAsync([=, this](uv::Loop& loop) { // connect local storage to server { net::ServerStartup startup{m_serverImpl}; diff --git a/ntcore/src/main/native/cpp/PubSubOptions.cpp b/ntcore/src/main/native/cpp/PubSubOptions.cpp index d180bc3720f..0af0d4d4dfd 100644 --- a/ntcore/src/main/native/cpp/PubSubOptions.cpp +++ b/ntcore/src/main/native/cpp/PubSubOptions.cpp @@ -8,7 +8,7 @@ using namespace nt; -nt::PubSubOptions::PubSubOptions(wpi::span options) { +nt::PubSubOptions::PubSubOptions(std::span options) { for (auto&& option : options) { switch (option.type) { case NT_PUBSUB_PERIODIC: diff --git a/ntcore/src/main/native/cpp/PubSubOptions.h b/ntcore/src/main/native/cpp/PubSubOptions.h index 4df53643681..ab3db4d7e18 100644 --- a/ntcore/src/main/native/cpp/PubSubOptions.h +++ b/ntcore/src/main/native/cpp/PubSubOptions.h @@ -4,7 +4,7 @@ #pragma once -#include +#include #include "ntcore_cpp.h" @@ -14,7 +14,7 @@ namespace nt { class PubSubOptions { public: PubSubOptions() = default; - explicit PubSubOptions(wpi::span options); + explicit PubSubOptions(std::span options); double periodic = 0.1; size_t pollStorageSize = 1; diff --git a/ntcore/src/main/native/cpp/Value.cpp b/ntcore/src/main/native/cpp/Value.cpp index e30c085cfb1..d02fb3d39ac 100644 --- a/ntcore/src/main/native/cpp/Value.cpp +++ b/ntcore/src/main/native/cpp/Value.cpp @@ -5,6 +5,7 @@ #include #include +#include #include #include @@ -17,7 +18,7 @@ using namespace nt; namespace { struct StringArrayStorage { - explicit StringArrayStorage(wpi::span value) + explicit StringArrayStorage(std::span value) : strings{value.begin(), value.end()} { InitNtStrings(); } @@ -68,7 +69,7 @@ Value::Value(NT_Type type, int64_t time, int64_t serverTime, } } -Value Value::MakeBooleanArray(wpi::span value, int64_t time) { +Value Value::MakeBooleanArray(std::span value, int64_t time) { Value val{NT_BOOLEAN_ARRAY, time, private_init{}}; auto data = std::make_shared>(value.begin(), value.end()); // data->reserve(value.size()); @@ -79,7 +80,7 @@ Value Value::MakeBooleanArray(wpi::span value, int64_t time) { return val; } -Value Value::MakeBooleanArray(wpi::span value, int64_t time) { +Value Value::MakeBooleanArray(std::span value, int64_t time) { Value val{NT_BOOLEAN_ARRAY, time, private_init{}}; auto data = std::make_shared>(value.begin(), value.end()); val.m_val.data.arr_boolean.arr = data->data(); @@ -88,7 +89,7 @@ Value Value::MakeBooleanArray(wpi::span value, int64_t time) { return val; } -Value Value::MakeIntegerArray(wpi::span value, int64_t time) { +Value Value::MakeIntegerArray(std::span value, int64_t time) { Value val{NT_INTEGER_ARRAY, time, private_init{}}; auto data = std::make_shared>(value.begin(), value.end()); @@ -98,7 +99,7 @@ Value Value::MakeIntegerArray(wpi::span value, int64_t time) { return val; } -Value Value::MakeFloatArray(wpi::span value, int64_t time) { +Value Value::MakeFloatArray(std::span value, int64_t time) { Value val{NT_FLOAT_ARRAY, time, private_init{}}; auto data = std::make_shared>(value.begin(), value.end()); val.m_val.data.arr_float.arr = data->data(); @@ -107,7 +108,7 @@ Value Value::MakeFloatArray(wpi::span value, int64_t time) { return val; } -Value Value::MakeDoubleArray(wpi::span value, int64_t time) { +Value Value::MakeDoubleArray(std::span value, int64_t time) { Value val{NT_DOUBLE_ARRAY, time, private_init{}}; auto data = std::make_shared>(value.begin(), value.end()); val.m_val.data.arr_double.arr = data->data(); @@ -116,7 +117,7 @@ Value Value::MakeDoubleArray(wpi::span value, int64_t time) { return val; } -Value Value::MakeStringArray(wpi::span value, int64_t time) { +Value Value::MakeStringArray(std::span value, int64_t time) { Value val{NT_STRING_ARRAY, time, private_init{}}; auto data = std::make_shared(value); val.m_val.data.arr_string.arr = data->ntStrings.data(); @@ -226,19 +227,19 @@ Value nt::ConvertFromC(const NT_Value& value) { value.last_change); case NT_BOOLEAN_ARRAY: return Value::MakeBooleanArray( - wpi::span(value.data.arr_boolean.arr, value.data.arr_boolean.size), + std::span(value.data.arr_boolean.arr, value.data.arr_boolean.size), value.last_change); case NT_INTEGER_ARRAY: return Value::MakeIntegerArray( - wpi::span(value.data.arr_int.arr, value.data.arr_int.size), + std::span(value.data.arr_int.arr, value.data.arr_int.size), value.last_change); case NT_FLOAT_ARRAY: return Value::MakeFloatArray( - wpi::span(value.data.arr_float.arr, value.data.arr_float.size), + std::span(value.data.arr_float.arr, value.data.arr_float.size), value.last_change); case NT_DOUBLE_ARRAY: return Value::MakeDoubleArray( - wpi::span(value.data.arr_double.arr, value.data.arr_double.size), + std::span(value.data.arr_double.arr, value.data.arr_double.size), value.last_change); case NT_STRING_ARRAY: { std::vector v; diff --git a/ntcore/src/main/native/cpp/jni/NetworkTablesJNI.cpp b/ntcore/src/main/native/cpp/jni/NetworkTablesJNI.cpp index c7786f91271..a5b028a4697 100644 --- a/ntcore/src/main/native/cpp/jni/NetworkTablesJNI.cpp +++ b/ntcore/src/main/native/cpp/jni/NetworkTablesJNI.cpp @@ -120,7 +120,7 @@ JNIEXPORT void JNICALL JNI_OnUnload(JavaVM* vm, void* reserved) { // Conversions from Java objects to C++ // -static wpi::span FromJavaPubSubOptions( +static std::span FromJavaPubSubOptions( JNIEnv* env, jintArray optionTypes, jdoubleArray optionValues, wpi::SmallVectorImpl& arr) { JIntArrayRef types{env, optionTypes}; @@ -281,7 +281,7 @@ static jobject MakeJObject(JNIEnv* env, jobject inst, static_cast(notification.flags)); } -static jobjectArray MakeJObject(JNIEnv* env, wpi::span arr) { +static jobjectArray MakeJObject(JNIEnv* env, std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), valueCls, nullptr); if (!jarr) { return nullptr; @@ -295,7 +295,7 @@ static jobjectArray MakeJObject(JNIEnv* env, wpi::span arr) { static jobjectArray MakeJObject( JNIEnv* env, jobject inst, - wpi::span arr) { + std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), connectionNotificationCls, nullptr); if (!jarr) { @@ -309,7 +309,7 @@ static jobjectArray MakeJObject( } static jobjectArray MakeJObject(JNIEnv* env, jobject inst, - wpi::span arr) { + std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), logMessageCls, nullptr); if (!jarr) { return nullptr; @@ -322,7 +322,7 @@ static jobjectArray MakeJObject(JNIEnv* env, jobject inst, } static jobjectArray MakeJObject(JNIEnv* env, jobject inst, - wpi::span arr) { + std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), topicNotificationCls, nullptr); if (!jarr) { @@ -336,7 +336,7 @@ static jobjectArray MakeJObject(JNIEnv* env, jobject inst, } static jobjectArray MakeJObject(JNIEnv* env, jobject inst, - wpi::span arr) { + std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), valueNotificationCls, nullptr); if (!jarr) { diff --git a/ntcore/src/main/native/cpp/net/ClientImpl.cpp b/ntcore/src/main/native/cpp/net/ClientImpl.cpp index 54feea1cc81..cab08011cc8 100644 --- a/ntcore/src/main/native/cpp/net/ClientImpl.cpp +++ b/ntcore/src/main/native/cpp/net/ClientImpl.cpp @@ -52,9 +52,9 @@ class CImpl : public ServerMessageHandler { CImpl(uint64_t curTimeMs, int inst, WireConnection& wire, wpi::Logger& logger, std::function setPeriodic); - void ProcessIncomingBinary(wpi::span data); + void ProcessIncomingBinary(std::span data); void HandleLocal(std::vector&& msgs); - void SendOutgoing(wpi::span msgs); + void SendOutgoing(std::span msgs); bool SendControl(uint64_t curTimeMs); void SendValues(uint64_t curTimeMs); bool CheckNetworkReady(); @@ -120,7 +120,7 @@ CImpl::CImpl(uint64_t curTimeMs, int inst, WireConnection& wire, m_setPeriodic(m_periodMs); } -void CImpl::ProcessIncomingBinary(wpi::span data) { +void CImpl::ProcessIncomingBinary(std::span data) { for (;;) { if (data.empty()) { break; @@ -419,7 +419,7 @@ void ClientImpl::ProcessIncomingText(std::string_view data) { WireDecodeText(data, *m_impl, m_impl->m_logger); } -void ClientImpl::ProcessIncomingBinary(wpi::span data) { +void ClientImpl::ProcessIncomingBinary(std::span data) { m_impl->ProcessIncomingBinary(data); } @@ -463,7 +463,7 @@ void ClientStartup::Publish(NT_Publisher pubHandle, NT_Topic topicHandle, } void ClientStartup::Subscribe(NT_Subscriber subHandle, - wpi::span prefixes, + std::span prefixes, const PubSubOptions& options) { WPI_DEBUG4(m_client.m_impl->m_logger, "StartupSubscribe({})", subHandle); WireEncodeSubscribe(m_textWriter.Add(), Handle{subHandle}.GetIndex(), diff --git a/ntcore/src/main/native/cpp/net/ClientImpl.h b/ntcore/src/main/native/cpp/net/ClientImpl.h index ac51a2045e1..a429a2edf63 100644 --- a/ntcore/src/main/native/cpp/net/ClientImpl.h +++ b/ntcore/src/main/native/cpp/net/ClientImpl.h @@ -8,12 +8,11 @@ #include #include +#include #include #include #include -#include - #include "NetworkInterface.h" #include "WireConnection.h" @@ -42,7 +41,7 @@ class ClientImpl { ~ClientImpl(); void ProcessIncomingText(std::string_view data); - void ProcessIncomingBinary(wpi::span data); + void ProcessIncomingBinary(std::span data); void HandleLocal(std::vector&& msgs); void SendControl(uint64_t curTimeMs); @@ -66,7 +65,7 @@ class ClientStartup final : public NetworkStartupInterface { void Publish(NT_Publisher pubHandle, NT_Topic topicHandle, std::string_view name, std::string_view typeStr, const wpi::json& properties, const PubSubOptions& options) final; - void Subscribe(NT_Subscriber subHandle, wpi::span prefixes, + void Subscribe(NT_Subscriber subHandle, std::span prefixes, const PubSubOptions& options) final; void SetValue(NT_Publisher pubHandle, const Value& value) final; diff --git a/ntcore/src/main/native/cpp/net/NetworkInterface.h b/ntcore/src/main/native/cpp/net/NetworkInterface.h index bbe98992c0d..29bedeb3a94 100644 --- a/ntcore/src/main/native/cpp/net/NetworkInterface.h +++ b/ntcore/src/main/native/cpp/net/NetworkInterface.h @@ -4,11 +4,10 @@ #pragma once +#include #include #include -#include - #include "ntcore_cpp.h" namespace wpi { @@ -45,7 +44,7 @@ class NetworkStartupInterface { const wpi::json& properties, const PubSubOptions& options) = 0; virtual void Subscribe(NT_Subscriber subHandle, - wpi::span topicNames, + std::span topicNames, const PubSubOptions& options) = 0; virtual void SetValue(NT_Publisher pubHandle, const Value& value) = 0; }; diff --git a/ntcore/src/main/native/cpp/net/NetworkLoopQueue.h b/ntcore/src/main/native/cpp/net/NetworkLoopQueue.h index b0b59e6aa37..3ff3324bcd2 100644 --- a/ntcore/src/main/native/cpp/net/NetworkLoopQueue.h +++ b/ntcore/src/main/native/cpp/net/NetworkLoopQueue.h @@ -4,6 +4,7 @@ #pragma once +#include #include #include @@ -37,7 +38,7 @@ class NetworkLoopQueue : public NetworkInterface { void SetProperties(NT_Topic topicHandle, std::string_view name, const wpi::json& update) final; void Subscribe(NT_Subscriber subHandle, - wpi::span topicNames, + std::span topicNames, const PubSubOptions& options) final; void Unsubscribe(NT_Subscriber subHandle) final; void SetValue(NT_Publisher pubHandle, const Value& value) final; diff --git a/ntcore/src/main/native/cpp/net/NetworkLoopQueue.inc b/ntcore/src/main/native/cpp/net/NetworkLoopQueue.inc index 8bdfc2e5bb6..1f039ad39a9 100644 --- a/ntcore/src/main/native/cpp/net/NetworkLoopQueue.inc +++ b/ntcore/src/main/native/cpp/net/NetworkLoopQueue.inc @@ -4,6 +4,7 @@ #pragma once +#include #include #include @@ -55,7 +56,7 @@ inline void NetworkLoopQueue::SetProperties(NT_Topic topicHandle, } inline void NetworkLoopQueue::Subscribe(NT_Subscriber subHandle, - wpi::span topicNames, + std::span topicNames, const PubSubOptions& options) { std::scoped_lock lock{m_mutex}; m_queue.emplace_back(ClientMessage{SubscribeMsg{ diff --git a/ntcore/src/main/native/cpp/net/ServerImpl.cpp b/ntcore/src/main/native/cpp/net/ServerImpl.cpp index 785c4034830..7738c670afb 100644 --- a/ntcore/src/main/native/cpp/net/ServerImpl.cpp +++ b/ntcore/src/main/native/cpp/net/ServerImpl.cpp @@ -91,7 +91,7 @@ class ClientData { virtual ~ClientData() = default; virtual void ProcessIncomingText(std::string_view data) = 0; - virtual void ProcessIncomingBinary(wpi::span data) = 0; + virtual void ProcessIncomingBinary(std::span data) = 0; enum SendMode { kSendDisabled = 0, kSendAll, kSendNormal, kSendImmNoFlush }; @@ -151,7 +151,7 @@ class ClientData4Base : public ClientData, protected ClientMessageHandler { void ClientUnpublish(int64_t pubuid) final; void ClientSetProperties(std::string_view name, const wpi::json& update) final; - void ClientSubscribe(int64_t subuid, wpi::span topicNames, + void ClientSubscribe(int64_t subuid, std::span topicNames, const PubSubOptions& options) final; void ClientUnsubscribe(int64_t subuid) final; @@ -168,7 +168,7 @@ class ClientDataLocal final : public ClientData4Base { : ClientData4Base{"", "", true, [](uint32_t) {}, server, id, logger} {} void ProcessIncomingText(std::string_view data) final {} - void ProcessIncomingBinary(wpi::span data) final {} + void ProcessIncomingBinary(std::span data) final {} void SendValue(TopicData* topic, const Value& value, SendMode mode) final; void SendAnnounce(TopicData* topic, std::optional pubuid) final; @@ -178,7 +178,7 @@ class ClientDataLocal final : public ClientData4Base { void SendOutgoing(uint64_t curTimeMs) final {} void Flush() final {} - void HandleLocal(wpi::span msgs); + void HandleLocal(std::span msgs); }; class ClientData4 final : public ClientData4Base { @@ -190,7 +190,7 @@ class ClientData4 final : public ClientData4Base { m_wire{wire} {} void ProcessIncomingText(std::string_view data) final; - void ProcessIncomingBinary(wpi::span data) final; + void ProcessIncomingBinary(std::span data) final; void SendValue(TopicData* topic, const Value& value, SendMode mode) final; void SendAnnounce(TopicData* topic, std::optional pubuid) final; @@ -245,7 +245,7 @@ class ClientData3 final : public ClientData, private net3::MessageHandler3 { m_decoder{*this} {} void ProcessIncomingText(std::string_view data) final {} - void ProcessIncomingBinary(wpi::span data) final; + void ProcessIncomingBinary(std::span data) final; void SendValue(TopicData* topic, const Value& value, SendMode mode) final; void SendAnnounce(TopicData* topic, std::optional pubuid) final; @@ -272,9 +272,9 @@ class ClientData3 final : public ClientData, private net3::MessageHandler3 { void FlagsUpdate(unsigned int id, unsigned int flags) final; void EntryDelete(unsigned int id) final; void ExecuteRpc(unsigned int id, unsigned int uid, - wpi::span params) final {} + std::span params) final {} void RpcResponse(unsigned int id, unsigned int uid, - wpi::span result) final {} + std::span result) final {} ServerImpl::Connected3Func m_connected; net3::WireConnection3& m_wire; @@ -350,7 +350,7 @@ struct PublisherData { }; struct SubscriberData { - SubscriberData(ClientData* client, wpi::span topicNames, + SubscriberData(ClientData* client, std::span topicNames, int64_t subuid, const PubSubOptions& options) : client{client}, topicNames{topicNames.begin(), topicNames.end()}, @@ -362,7 +362,7 @@ struct SubscriberData { } } - void Update(wpi::span topicNames_, + void Update(std::span topicNames_, const PubSubOptions& options_) { topicNames = {topicNames_.begin(), topicNames_.end()}; options = options_; @@ -599,7 +599,7 @@ void ClientData4Base::ClientSetProperties(std::string_view name, } void ClientData4Base::ClientSubscribe(int64_t subuid, - wpi::span topicNames, + std::span topicNames, const PubSubOptions& options) { DEBUG4("ClientSubscribe({}, ({}), {})", m_id, fmt::join(topicNames, ","), subuid); @@ -757,7 +757,7 @@ void ClientDataLocal::SendPropertiesUpdate(TopicData* topic, } } -void ClientDataLocal::HandleLocal(wpi::span msgs) { +void ClientDataLocal::HandleLocal(std::span msgs) { DEBUG4("{}", "HandleLocal()"); // just map as a normal client into client=0 calls for (const auto& elem : msgs) { // NOLINT @@ -782,7 +782,7 @@ void ClientData4::ProcessIncomingText(std::string_view data) { WireDecodeText(data, *this, m_logger); } -void ClientData4::ProcessIncomingBinary(wpi::span data) { +void ClientData4::ProcessIncomingBinary(std::span data) { for (;;) { if (data.empty()) { break; @@ -947,7 +947,7 @@ bool ClientData3::TopicData3::UpdateFlags(TopicData* topic) { return updated; } -void ClientData3::ProcessIncomingBinary(wpi::span data) { +void ClientData3::ProcessIncomingBinary(std::span data) { if (!m_decoder.Execute(&data)) { m_wire.Disconnect(m_decoder.GetError()); } @@ -1199,7 +1199,7 @@ void ClientData3::ClientHello(std::string_view self_id, PubSubOptions options; options.prefixMatch = true; sub = std::make_unique( - this, wpi::span{{prefix}}, 0, options); + this, std::span{{prefix}}, 0, options); m_periodMs = std::gcd(m_periodMs, sub->periodMs); if (m_periodMs < kMinPeriodMs) { m_periodMs = kMinPeriodMs; @@ -2253,7 +2253,7 @@ void ServerImpl::SendValues(int clientId, uint64_t curTimeMs) { client->Flush(); } -void ServerImpl::HandleLocal(wpi::span msgs) { +void ServerImpl::HandleLocal(std::span msgs) { // just map as a normal client into client=0 calls m_impl->m_localClient->HandleLocal(msgs); } @@ -2278,7 +2278,7 @@ void ServerImpl::ProcessIncomingText(int clientId, std::string_view data) { } void ServerImpl::ProcessIncomingBinary(int clientId, - wpi::span data) { + std::span data) { m_impl->m_clients[clientId]->ProcessIncomingBinary(data); } @@ -2329,7 +2329,7 @@ void ServerStartup::Publish(NT_Publisher pubHandle, NT_Topic topicHandle, } void ServerStartup::Subscribe(NT_Subscriber subHandle, - wpi::span topicNames, + std::span topicNames, const PubSubOptions& options) { m_server.m_impl->m_localClient->ClientSubscribe(subHandle, topicNames, options); diff --git a/ntcore/src/main/native/cpp/net/ServerImpl.h b/ntcore/src/main/native/cpp/net/ServerImpl.h index 18669c1d6af..a1f7b892184 100644 --- a/ntcore/src/main/native/cpp/net/ServerImpl.h +++ b/ntcore/src/main/native/cpp/net/ServerImpl.h @@ -8,12 +8,11 @@ #include #include +#include #include #include #include -#include - #include "NetworkInterface.h" #include "net3/WireConnection3.h" @@ -46,11 +45,11 @@ class ServerImpl final { void SendControl(uint64_t curTimeMs); void SendValues(int clientId, uint64_t curTimeMs); - void HandleLocal(wpi::span msgs); + void HandleLocal(std::span msgs); void SetLocal(LocalInterface* local); void ProcessIncomingText(int clientId, std::string_view data); - void ProcessIncomingBinary(int clientId, wpi::span data); + void ProcessIncomingBinary(int clientId, std::span data); // Returns -1 if cannot add client (e.g. due to duplicate name). // Caller must ensure WireConnection lifetime lasts until RemoveClient() call. @@ -83,7 +82,7 @@ class ServerStartup final : public NetworkStartupInterface { std::string_view name, std::string_view typeStr, const wpi::json& properties, const PubSubOptions& options) final; void Subscribe(NT_Subscriber subHandle, - wpi::span topicNames, + std::span topicNames, const PubSubOptions& options) final; void SetValue(NT_Publisher pubHandle, const Value& value) final; diff --git a/ntcore/src/main/native/cpp/net/WebSocketConnection.cpp b/ntcore/src/main/native/cpp/net/WebSocketConnection.cpp index 921b8cd829f..0301d9a5fe5 100644 --- a/ntcore/src/main/native/cpp/net/WebSocketConnection.cpp +++ b/ntcore/src/main/native/cpp/net/WebSocketConnection.cpp @@ -4,6 +4,8 @@ #include "WebSocketConnection.h" +#include + #include #include @@ -37,7 +39,7 @@ void WebSocketConnection::Flush() { m_ws_frames.reserve(m_frames.size()); for (auto&& frame : m_frames) { m_ws_frames.emplace_back(frame.opcode, - wpi::span{frame.bufs->begin() + frame.start, + std::span{frame.bufs->begin() + frame.start, frame.bufs->begin() + frame.end}); } diff --git a/ntcore/src/main/native/cpp/net/WireDecoder.cpp b/ntcore/src/main/native/cpp/net/WireDecoder.cpp index 9321adf49da..abaa80ed766 100644 --- a/ntcore/src/main/native/cpp/net/WireDecoder.cpp +++ b/ntcore/src/main/native/cpp/net/WireDecoder.cpp @@ -418,7 +418,7 @@ void nt::net::WireDecodeText(std::string_view in, ServerMessageHandler& out, ::WireDecodeTextImpl(in, out, logger); } -bool nt::net::WireDecodeBinary(wpi::span* in, int64_t* outId, +bool nt::net::WireDecodeBinary(std::span* in, int64_t* outId, Value* outValue, std::string* error, int64_t localTimeOffset) { mpack_reader_t reader; diff --git a/ntcore/src/main/native/cpp/net/WireDecoder.h b/ntcore/src/main/native/cpp/net/WireDecoder.h index c1cbddaac2d..dd472e81c5b 100644 --- a/ntcore/src/main/native/cpp/net/WireDecoder.h +++ b/ntcore/src/main/native/cpp/net/WireDecoder.h @@ -7,11 +7,10 @@ #include #include +#include #include #include -#include - namespace wpi { class Logger; class json; @@ -35,7 +34,7 @@ class ClientMessageHandler { virtual void ClientSetProperties(std::string_view name, const wpi::json& update) = 0; virtual void ClientSubscribe(int64_t subuid, - wpi::span topicNames, + std::span topicNames, const PubSubOptions& options) = 0; virtual void ClientUnsubscribe(int64_t subuid) = 0; }; @@ -58,7 +57,7 @@ void WireDecodeText(std::string_view in, ServerMessageHandler& out, wpi::Logger& logger); // returns true if successfully decoded a message -bool WireDecodeBinary(wpi::span* in, int64_t* outId, +bool WireDecodeBinary(std::span* in, int64_t* outId, Value* outValue, std::string* error, int64_t localTimeOffset); diff --git a/ntcore/src/main/native/cpp/net/WireEncoder.cpp b/ntcore/src/main/native/cpp/net/WireEncoder.cpp index d0edc2f1aeb..2ef6bdf75d8 100644 --- a/ntcore/src/main/native/cpp/net/WireEncoder.cpp +++ b/ntcore/src/main/native/cpp/net/WireEncoder.cpp @@ -56,7 +56,7 @@ void nt::net::WireEncodeSetProperties(wpi::raw_ostream& os, } template -static void EncodePrefixes(wpi::raw_ostream& os, wpi::span topicNames, +static void EncodePrefixes(wpi::raw_ostream& os, std::span topicNames, wpi::json::serializer& s) { os << '['; bool first = true; @@ -75,7 +75,7 @@ static void EncodePrefixes(wpi::raw_ostream& os, wpi::span topicNames, template static void WireEncodeSubscribeImpl(wpi::raw_ostream& os, int64_t subuid, - wpi::span topicNames, + std::span topicNames, const PubSubOptions& options) { wpi::json::serializer s{os, ' ', 0}; os << "{\"method\":\"" << SubscribeMsg::kMethodStr << "\",\"params\":{"; @@ -114,13 +114,13 @@ static void WireEncodeSubscribeImpl(wpi::raw_ostream& os, int64_t subuid, } void nt::net::WireEncodeSubscribe(wpi::raw_ostream& os, int64_t subuid, - wpi::span topicNames, + std::span topicNames, const PubSubOptions& options) { WireEncodeSubscribeImpl(os, subuid, topicNames, options); } void nt::net::WireEncodeSubscribe(wpi::raw_ostream& os, int64_t subuid, - wpi::span topicNames, + std::span topicNames, const PubSubOptions& options) { WireEncodeSubscribeImpl(os, subuid, topicNames, options); } diff --git a/ntcore/src/main/native/cpp/net/WireEncoder.h b/ntcore/src/main/native/cpp/net/WireEncoder.h index 6ea4fea9d28..63f8b362b52 100644 --- a/ntcore/src/main/native/cpp/net/WireEncoder.h +++ b/ntcore/src/main/native/cpp/net/WireEncoder.h @@ -5,11 +5,10 @@ #pragma once #include +#include #include #include -#include - namespace wpi { class json; class raw_ostream; @@ -33,10 +32,10 @@ void WireEncodeUnpublish(wpi::raw_ostream& os, int64_t pubuid); void WireEncodeSetProperties(wpi::raw_ostream& os, std::string_view name, const wpi::json& update); void WireEncodeSubscribe(wpi::raw_ostream& os, int64_t subuid, - wpi::span topicNames, + std::span topicNames, const PubSubOptions& options); void WireEncodeSubscribe(wpi::raw_ostream& os, int64_t subuid, - wpi::span topicNames, + std::span topicNames, const PubSubOptions& options); void WireEncodeUnsubscribe(wpi::raw_ostream& os, int64_t subuid); diff --git a/ntcore/src/main/native/cpp/net3/ClientImpl3.cpp b/ntcore/src/main/native/cpp/net3/ClientImpl3.cpp index 13f6aee83bb..891184392ad 100644 --- a/ntcore/src/main/native/cpp/net3/ClientImpl3.cpp +++ b/ntcore/src/main/native/cpp/net3/ClientImpl3.cpp @@ -89,8 +89,8 @@ class CImpl : public MessageHandler3 { wpi::Logger& logger, std::function setPeriodic); - void ProcessIncoming(wpi::span data); - void HandleLocal(wpi::span msgs); + void ProcessIncoming(std::span data); + void HandleLocal(std::span msgs); void SendPeriodic(uint64_t curTimeMs, bool initial); void SendValue(Writer& out, Entry* entry, const Value& value); bool CheckNetworkReady(); @@ -119,9 +119,9 @@ class CImpl : public MessageHandler3 { void FlagsUpdate(unsigned int id, unsigned int flags) final; void EntryDelete(unsigned int id) final; void ExecuteRpc(unsigned int id, unsigned int uid, - wpi::span params) final {} + std::span params) final {} void RpcResponse(unsigned int id, unsigned int uid, - wpi::span result) final {} + std::span result) final {} enum State { kStateInitial, @@ -200,14 +200,14 @@ CImpl::CImpl(uint64_t curTimeMs, int inst, WireConnection3& wire, m_nextKeepAliveTimeMs{curTimeMs + kKeepAliveIntervalMs}, m_decoder{*this} {} -void CImpl::ProcessIncoming(wpi::span data) { +void CImpl::ProcessIncoming(std::span data) { DEBUG4("received {} bytes", data.size()); if (!m_decoder.Execute(&data)) { m_wire.Disconnect(m_decoder.GetError()); } } -void CImpl::HandleLocal(wpi::span msgs) { +void CImpl::HandleLocal(std::span msgs) { for (const auto& elem : msgs) { // NOLINT // common case is value if (auto msg = std::get_if(&elem.contents)) { @@ -624,11 +624,11 @@ void ClientImpl3::Start(std::string_view selfId, m_impl->m_state = CImpl::kStateHelloSent; } -void ClientImpl3::ProcessIncoming(wpi::span data) { +void ClientImpl3::ProcessIncoming(std::span data) { m_impl->ProcessIncoming(data); } -void ClientImpl3::HandleLocal(wpi::span msgs) { +void ClientImpl3::HandleLocal(std::span msgs) { m_impl->HandleLocal(msgs); } @@ -655,7 +655,7 @@ void ClientStartup3::Publish(NT_Publisher pubHandle, NT_Topic topicHandle, } void ClientStartup3::Subscribe(NT_Subscriber subHandle, - wpi::span prefixes, + std::span prefixes, const PubSubOptions& options) { // NT3 ignores subscribes, so no action required } diff --git a/ntcore/src/main/native/cpp/net3/ClientImpl3.h b/ntcore/src/main/native/cpp/net3/ClientImpl3.h index 6d6bab2e835..5b30a463ab4 100644 --- a/ntcore/src/main/native/cpp/net3/ClientImpl3.h +++ b/ntcore/src/main/native/cpp/net3/ClientImpl3.h @@ -8,11 +8,10 @@ #include #include +#include #include #include -#include - #include "net/NetworkInterface.h" namespace wpi { @@ -39,8 +38,8 @@ class ClientImpl3 { ~ClientImpl3(); void Start(std::string_view selfId, std::function succeeded); - void ProcessIncoming(wpi::span data); - void HandleLocal(wpi::span msgs); + void ProcessIncoming(std::span data); + void HandleLocal(std::span msgs); void SendPeriodic(uint64_t curTimeMs); @@ -62,7 +61,7 @@ class ClientStartup3 final : public net::NetworkStartupInterface { void Publish(NT_Publisher pubHandle, NT_Topic topicHandle, std::string_view name, std::string_view typeStr, const wpi::json& properties, const PubSubOptions& options) final; - void Subscribe(NT_Subscriber subHandle, wpi::span prefixes, + void Subscribe(NT_Subscriber subHandle, std::span prefixes, const PubSubOptions& options) final; void SetValue(NT_Publisher pubHandle, const Value& value) final; diff --git a/ntcore/src/main/native/cpp/net3/Message3.h b/ntcore/src/main/native/cpp/net3/Message3.h index 433219680d6..ebac75f9662 100644 --- a/ntcore/src/main/native/cpp/net3/Message3.h +++ b/ntcore/src/main/native/cpp/net3/Message3.h @@ -6,6 +6,7 @@ #include +#include #include #include "networktables/NetworkTableValue.h" @@ -57,7 +58,7 @@ class Message3 { // Message data accessors. Callers are responsible for knowing what data is // actually provided for a particular message. std::string_view str() const { return m_str; } - wpi::span bytes() const { + std::span bytes() const { return {reinterpret_cast(m_str.data()), m_str.size()}; } const Value& value() const { return m_value; } @@ -123,7 +124,7 @@ class Message3 { return msg; } static Message3 ExecuteRpc(unsigned int id, unsigned int uid, - wpi::span params) { + std::span params) { Message3 msg{kExecuteRpc, {}}; msg.m_str.assign(reinterpret_cast(params.data()), params.size()); @@ -132,7 +133,7 @@ class Message3 { return msg; } static Message3 RpcResponse(unsigned int id, unsigned int uid, - wpi::span result) { + std::span result) { Message3 msg{kRpcResponse, {}}; msg.m_str.assign(reinterpret_cast(result.data()), result.size()); diff --git a/ntcore/src/main/native/cpp/net3/WireDecoder3.cpp b/ntcore/src/main/native/cpp/net3/WireDecoder3.cpp index 9e14724c0a6..ea08358ec12 100644 --- a/ntcore/src/main/native/cpp/net3/WireDecoder3.cpp +++ b/ntcore/src/main/native/cpp/net3/WireDecoder3.cpp @@ -23,10 +23,10 @@ namespace { class SimpleValueReader { public: - std::optional Read16(wpi::span* in); - std::optional Read32(wpi::span* in); - std::optional Read64(wpi::span* in); - std::optional ReadDouble(wpi::span* in); + std::optional Read16(std::span* in); + std::optional Read32(std::span* in); + std::optional Read64(std::span* in); + std::optional ReadDouble(std::span* in); private: uint64_t m_value = 0; @@ -123,7 +123,7 @@ struct WDImpl { unsigned int m_flags{0}; unsigned int m_seq_num_uid{0}; - void Execute(wpi::span* in); + void Execute(std::span* in); std::nullopt_t EmitError(std::string_view msg) { m_state = kError; @@ -131,22 +131,22 @@ struct WDImpl { return std::nullopt; } - std::optional ReadString(wpi::span* in); - std::optional> ReadRaw(wpi::span* in); - std::optional ReadType(wpi::span* in); - std::optional ReadValue(wpi::span* in); + std::optional ReadString(std::span* in); + std::optional> ReadRaw(std::span* in); + std::optional ReadType(std::span* in); + std::optional ReadValue(std::span* in); }; } // namespace -static uint8_t Read8(wpi::span* in) { +static uint8_t Read8(std::span* in) { uint8_t val = in->front(); *in = wpi::drop_front(*in); return val; } std::optional SimpleValueReader::Read16( - wpi::span* in) { + std::span* in) { while (!in->empty()) { m_value <<= 8; m_value |= in->front() & 0xff; @@ -162,7 +162,7 @@ std::optional SimpleValueReader::Read16( } std::optional SimpleValueReader::Read32( - wpi::span* in) { + std::span* in) { while (!in->empty()) { m_value <<= 8; m_value |= in->front() & 0xff; @@ -178,7 +178,7 @@ std::optional SimpleValueReader::Read32( } std::optional SimpleValueReader::Read64( - wpi::span* in) { + std::span* in) { while (!in->empty()) { m_value <<= 8; m_value |= in->front() & 0xff; @@ -194,7 +194,7 @@ std::optional SimpleValueReader::Read64( } std::optional SimpleValueReader::ReadDouble( - wpi::span* in) { + std::span* in) { if (auto val = Read64(in)) { return wpi::BitsToDouble(val.value()); } else { @@ -202,7 +202,7 @@ std::optional SimpleValueReader::ReadDouble( } } -void WDImpl::Execute(wpi::span* in) { +void WDImpl::Execute(std::span* in) { while (!in->empty()) { switch (m_state) { case kStart: { @@ -417,7 +417,7 @@ void WDImpl::Execute(wpi::span* in) { } } -std::optional WDImpl::ReadString(wpi::span* in) { +std::optional WDImpl::ReadString(std::span* in) { // string length if (!m_stringReader.len) { if (auto val = m_ulebReader.ReadOne(in)) { @@ -443,7 +443,7 @@ std::optional WDImpl::ReadString(wpi::span* in) { } std::optional> WDImpl::ReadRaw( - wpi::span* in) { + std::span* in) { // string length if (!m_rawReader.len) { if (auto val = m_ulebReader.ReadOne(in)) { @@ -468,7 +468,7 @@ std::optional> WDImpl::ReadRaw( return std::nullopt; } -std::optional WDImpl::ReadType(wpi::span* in) { +std::optional WDImpl::ReadType(std::span* in) { // Convert from byte value to enum switch (Read8(in)) { case Message3::kBoolean: @@ -492,7 +492,7 @@ std::optional WDImpl::ReadType(wpi::span* in) { } } -std::optional WDImpl::ReadValue(wpi::span* in) { +std::optional WDImpl::ReadValue(std::span* in) { while (!in->empty()) { switch (m_valueReader.type) { case NT_BOOLEAN: @@ -586,7 +586,7 @@ WireDecoder3::WireDecoder3(MessageHandler3& out) : m_impl{new Impl{out}} {} WireDecoder3::~WireDecoder3() = default; -bool WireDecoder3::Execute(wpi::span* in) { +bool WireDecoder3::Execute(std::span* in) { m_impl->Execute(in); return m_impl->m_state != Impl::kError; } diff --git a/ntcore/src/main/native/cpp/net3/WireDecoder3.h b/ntcore/src/main/native/cpp/net3/WireDecoder3.h index f062eee59e7..e877833fca9 100644 --- a/ntcore/src/main/native/cpp/net3/WireDecoder3.h +++ b/ntcore/src/main/native/cpp/net3/WireDecoder3.h @@ -7,10 +7,9 @@ #include #include +#include #include -#include - namespace nt { class Value; } // namespace nt @@ -35,9 +34,9 @@ class MessageHandler3 { virtual void FlagsUpdate(unsigned int id, unsigned int flags) = 0; virtual void EntryDelete(unsigned int id) = 0; virtual void ExecuteRpc(unsigned int id, unsigned int uid, - wpi::span params) = 0; + std::span params) = 0; virtual void RpcResponse(unsigned int id, unsigned int uid, - wpi::span result) = 0; + std::span result) = 0; }; /* Decodes NT3 protocol into native representation. */ @@ -52,7 +51,7 @@ class WireDecoder3 { * @param in input data (updated during parse) * @return false if error occurred */ - bool Execute(wpi::span* in); + bool Execute(std::span* in); void SetError(std::string_view message); std::string GetError() const; diff --git a/ntcore/src/main/native/cpp/net3/WireEncoder3.cpp b/ntcore/src/main/native/cpp/net3/WireEncoder3.cpp index 41bd7ddc680..6bf3435f8df 100644 --- a/ntcore/src/main/native/cpp/net3/WireEncoder3.cpp +++ b/ntcore/src/main/native/cpp/net3/WireEncoder3.cpp @@ -8,7 +8,6 @@ #include #include #include -#include #include "Message3.h" @@ -20,12 +19,12 @@ static void Write8(wpi::raw_ostream& os, uint8_t val) { } static void Write16(wpi::raw_ostream& os, uint16_t val) { - os << wpi::span{{static_cast((val >> 8) & 0xff), + os << std::span{{static_cast((val >> 8) & 0xff), static_cast(val & 0xff)}}; } static void Write32(wpi::raw_ostream& os, uint32_t val) { - os << wpi::span{{static_cast((val >> 24) & 0xff), + os << std::span{{static_cast((val >> 24) & 0xff), static_cast((val >> 16) & 0xff), static_cast((val >> 8) & 0xff), static_cast(val & 0xff)}}; @@ -34,7 +33,7 @@ static void Write32(wpi::raw_ostream& os, uint32_t val) { static void WriteDouble(wpi::raw_ostream& os, double val) { // The highest performance way to do this, albeit non-portable. uint64_t v = wpi::DoubleToBits(val); - os << wpi::span{{static_cast((v >> 56) & 0xff), + os << std::span{{static_cast((v >> 56) & 0xff), static_cast((v >> 48) & 0xff), static_cast((v >> 40) & 0xff), static_cast((v >> 32) & 0xff), @@ -49,7 +48,7 @@ static void WriteString(wpi::raw_ostream& os, std::string_view str) { os << str; } -static void WriteRaw(wpi::raw_ostream& os, wpi::span str) { +static void WriteRaw(wpi::raw_ostream& os, std::span str) { wpi::WriteUleb128(os, str.size()); os << str; } @@ -261,7 +260,7 @@ void nt::net3::WireEncodeEntryDelete(wpi::raw_ostream& os, unsigned int id) { void nt::net3::WireEncodeExecuteRpc(wpi::raw_ostream& os, unsigned int id, unsigned int uid, - wpi::span params) { + std::span params) { Write8(os, Message3::kExecuteRpc); Write16(os, id); Write16(os, uid); @@ -270,7 +269,7 @@ void nt::net3::WireEncodeExecuteRpc(wpi::raw_ostream& os, unsigned int id, void nt::net3::WireEncodeRpcResponse(wpi::raw_ostream& os, unsigned int id, unsigned int uid, - wpi::span result) { + std::span result) { Write8(os, Message3::kRpcResponse); Write16(os, id); Write16(os, uid); diff --git a/ntcore/src/main/native/cpp/net3/WireEncoder3.h b/ntcore/src/main/native/cpp/net3/WireEncoder3.h index 4163d6b83bc..66be9aedd4d 100644 --- a/ntcore/src/main/native/cpp/net3/WireEncoder3.h +++ b/ntcore/src/main/native/cpp/net3/WireEncoder3.h @@ -6,10 +6,9 @@ #include +#include #include -#include - namespace wpi { class raw_ostream; } // namespace wpi @@ -41,9 +40,9 @@ void WireEncodeFlagsUpdate(wpi::raw_ostream& os, unsigned int id, unsigned int flags); void WireEncodeEntryDelete(wpi::raw_ostream& os, unsigned int id); void WireEncodeExecuteRpc(wpi::raw_ostream& os, unsigned int id, - unsigned int uid, wpi::span params); + unsigned int uid, std::span params); void WireEncodeRpcResponse(wpi::raw_ostream& os, unsigned int id, - unsigned int uid, wpi::span result); + unsigned int uid, std::span result); bool WireEncode(wpi::raw_ostream& os, const Message3& msg); diff --git a/ntcore/src/main/native/cpp/networktables/NetworkTable.cpp b/ntcore/src/main/native/cpp/networktables/NetworkTable.cpp index f5d9bc39b2c..9e75c3a85c5 100644 --- a/ntcore/src/main/native/cpp/networktables/NetworkTable.cpp +++ b/ntcore/src/main/native/cpp/networktables/NetworkTable.cpp @@ -287,62 +287,62 @@ bool NetworkTable::GetBoolean(std::string_view key, bool defaultValue) const { } bool NetworkTable::PutBooleanArray(std::string_view key, - wpi::span value) { + std::span value) { return GetEntry(key).SetBooleanArray(value); } bool NetworkTable::SetDefaultBooleanArray(std::string_view key, - wpi::span defaultValue) { + std::span defaultValue) { return GetEntry(key).SetDefaultBooleanArray(defaultValue); } std::vector NetworkTable::GetBooleanArray( - std::string_view key, wpi::span defaultValue) const { + std::string_view key, std::span defaultValue) const { return GetEntry(key).GetBooleanArray(defaultValue); } bool NetworkTable::PutNumberArray(std::string_view key, - wpi::span value) { + std::span value) { return GetEntry(key).SetDoubleArray(value); } bool NetworkTable::SetDefaultNumberArray(std::string_view key, - wpi::span defaultValue) { + std::span defaultValue) { return GetEntry(key).SetDefaultDoubleArray(defaultValue); } std::vector NetworkTable::GetNumberArray( - std::string_view key, wpi::span defaultValue) const { + std::string_view key, std::span defaultValue) const { return GetEntry(key).GetDoubleArray(defaultValue); } bool NetworkTable::PutStringArray(std::string_view key, - wpi::span value) { + std::span value) { return GetEntry(key).SetStringArray(value); } bool NetworkTable::SetDefaultStringArray( - std::string_view key, wpi::span defaultValue) { + std::string_view key, std::span defaultValue) { return GetEntry(key).SetDefaultStringArray(defaultValue); } std::vector NetworkTable::GetStringArray( - std::string_view key, wpi::span defaultValue) const { + std::string_view key, std::span defaultValue) const { return GetEntry(key).GetStringArray(defaultValue); } bool NetworkTable::PutRaw(std::string_view key, - wpi::span value) { + std::span value) { return GetEntry(key).SetRaw(value); } bool NetworkTable::SetDefaultRaw(std::string_view key, - wpi::span defaultValue) { + std::span defaultValue) { return GetEntry(key).SetDefaultRaw(defaultValue); } std::vector NetworkTable::GetRaw( - std::string_view key, wpi::span defaultValue) const { + std::string_view key, std::span defaultValue) const { return GetEntry(key).GetRaw(defaultValue); } diff --git a/ntcore/src/main/native/cpp/networktables/NetworkTableInstance.cpp b/ntcore/src/main/native/cpp/networktables/NetworkTableInstance.cpp index 07963a9b4eb..a82bf30039a 100644 --- a/ntcore/src/main/native/cpp/networktables/NetworkTableInstance.cpp +++ b/ntcore/src/main/native/cpp/networktables/NetworkTableInstance.cpp @@ -90,7 +90,7 @@ std::shared_ptr NetworkTableInstance::GetTable( } } -void NetworkTableInstance::SetServer(wpi::span servers, +void NetworkTableInstance::SetServer(std::span servers, unsigned int port) { std::vector> serversArr; serversArr.reserve(servers.size()); diff --git a/ntcore/src/main/native/cpp/networktables/Topic.cpp b/ntcore/src/main/native/cpp/networktables/Topic.cpp index 8d73e06230f..d37057ceb5f 100644 --- a/ntcore/src/main/native/cpp/networktables/Topic.cpp +++ b/ntcore/src/main/native/cpp/networktables/Topic.cpp @@ -23,36 +23,36 @@ wpi::json Topic::GetProperties() const { } GenericSubscriber Topic::GenericSubscribe( - wpi::span options) { + std::span options) { return GenericSubscribe("", options); } GenericSubscriber Topic::GenericSubscribe( - std::string_view typeString, wpi::span options) { + std::string_view typeString, std::span options) { return GenericSubscriber{::nt::Subscribe( m_handle, ::nt::GetTypeFromString(typeString), typeString, options)}; } GenericPublisher Topic::GenericPublish(std::string_view typeString, - wpi::span options) { + std::span options) { return GenericPublisher{::nt::Publish( m_handle, ::nt::GetTypeFromString(typeString), typeString, options)}; } GenericPublisher Topic::GenericPublishEx( std::string_view typeString, const wpi::json& properties, - wpi::span options) { + std::span options) { return GenericPublisher{::nt::PublishEx(m_handle, ::nt::GetTypeFromString(typeString), typeString, properties, options)}; } -GenericEntry Topic::GetGenericEntry(wpi::span options) { +GenericEntry Topic::GetGenericEntry(std::span options) { return GetGenericEntry("", options); } GenericEntry Topic::GetGenericEntry(std::string_view typeString, - wpi::span options) { + std::span options) { return GenericEntry{::nt::GetEntry( m_handle, ::nt::GetTypeFromString(typeString), typeString, options)}; } diff --git a/ntcore/src/main/native/cpp/ntcore_cpp.cpp b/ntcore/src/main/native/cpp/ntcore_cpp.cpp index 97c94fea5af..b626ed3db52 100644 --- a/ntcore/src/main/native/cpp/ntcore_cpp.cpp +++ b/ntcore/src/main/native/cpp/ntcore_cpp.cpp @@ -157,7 +157,7 @@ std::vector GetTopics(NT_Inst inst, std::string_view prefix, } std::vector GetTopics(NT_Inst inst, std::string_view prefix, - wpi::span types) { + std::span types) { if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) { return ii->localStorage.GetTopics(prefix, types); } else { @@ -175,7 +175,7 @@ std::vector GetTopicInfo(NT_Inst inst, std::string_view prefix, } std::vector GetTopicInfo(NT_Inst inst, std::string_view prefix, - wpi::span types) { + std::span types) { if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) { return ii->localStorage.GetTopicInfo(prefix, types); } else { @@ -302,7 +302,7 @@ bool SetTopicProperties(NT_Topic topic, const wpi::json& properties) { } NT_Subscriber Subscribe(NT_Topic topic, NT_Type type, std::string_view typeStr, - wpi::span options) { + std::span options) { if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) { return ii->localStorage.Subscribe(topic, type, typeStr, options); } else { @@ -317,13 +317,13 @@ void Unsubscribe(NT_Subscriber sub) { } NT_Publisher Publish(NT_Topic topic, NT_Type type, std::string_view typeStr, - wpi::span options) { + std::span options) { return PublishEx(topic, type, typeStr, wpi::json::object(), options); } NT_Publisher PublishEx(NT_Topic topic, NT_Type type, std::string_view typeStr, const wpi::json& properties, - wpi::span options) { + std::span options) { if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) { return ii->localStorage.Publish(topic, type, typeStr, properties, options); } else { @@ -338,7 +338,7 @@ void Unpublish(NT_Handle pubentry) { } NT_Entry GetEntry(NT_Topic topic, NT_Type type, std::string_view typeStr, - wpi::span options) { + std::span options) { if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) { return ii->localStorage.GetEntry(topic, type, typeStr, options); } else { @@ -367,8 +367,8 @@ NT_Topic GetTopicFromHandle(NT_Handle pubsubentry) { } NT_MultiSubscriber SubscribeMultiple(NT_Inst inst, - wpi::span prefixes, - wpi::span options) { + std::span prefixes, + std::span options) { if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) { return ii->localStorage.SubscribeMultiple(prefixes, options); } else { @@ -387,7 +387,7 @@ void UnsubscribeMultiple(NT_MultiSubscriber sub) { */ NT_TopicListener AddTopicListener( - NT_Inst inst, wpi::span prefixes, unsigned int mask, + NT_Inst inst, std::span prefixes, unsigned int mask, std::function callback) { if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) { return ii->localStorage.AddTopicListener(prefixes, mask, @@ -422,7 +422,7 @@ void DestroyTopicListenerPoller(NT_TopicListenerPoller poller) { } NT_TopicListener AddPolledTopicListener( - NT_TopicListenerPoller poller, wpi::span prefixes, + NT_TopicListenerPoller poller, std::span prefixes, unsigned int mask) { if (auto ii = InstanceImpl::GetTyped(poller, Handle::kTopicListenerPoller)) { return ii->localStorage.AddPolledTopicListener(poller, prefixes, mask); @@ -688,7 +688,7 @@ void SetServer(NT_Inst inst, const char* server_name, unsigned int port) { void SetServer( NT_Inst inst, - wpi::span> servers) { + std::span> servers) { if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) { if (auto client = ii->GetClient()) { std::vector> serversCopy; diff --git a/ntcore/src/main/native/include/networktables/ConnectionListener.h b/ntcore/src/main/native/include/networktables/ConnectionListener.h index 191d910c1da..f31e770ab69 100644 --- a/ntcore/src/main/native/include/networktables/ConnectionListener.h +++ b/ntcore/src/main/native/include/networktables/ConnectionListener.h @@ -7,8 +7,6 @@ #include #include -#include - #include "ntcore_cpp.h" namespace nt { diff --git a/ntcore/src/main/native/include/networktables/ConnectionListener.inc b/ntcore/src/main/native/include/networktables/ConnectionListener.inc index 8f652b05e30..3295a942a32 100644 --- a/ntcore/src/main/native/include/networktables/ConnectionListener.inc +++ b/ntcore/src/main/native/include/networktables/ConnectionListener.inc @@ -7,8 +7,6 @@ #include #include -#include - #include "networktables/ConnectionListener.h" #include "networktables/NetworkTableInstance.h" #include "ntcore_cpp.h" diff --git a/ntcore/src/main/native/include/networktables/GenericEntry.h b/ntcore/src/main/native/include/networktables/GenericEntry.h index 792e6fdd07f..6c7fee4fe82 100644 --- a/ntcore/src/main/native/include/networktables/GenericEntry.h +++ b/ntcore/src/main/native/include/networktables/GenericEntry.h @@ -6,6 +6,7 @@ #include +#include #include #include #include @@ -97,7 +98,7 @@ class GenericSubscriber : public Subscriber { * @param defaultValue the value to be returned if no value is found * @return the entry's value or the given default value */ - std::vector GetRaw(wpi::span defaultValue) const; + std::vector GetRaw(std::span defaultValue) const; /** * Gets the entry's value as a boolean array. If the entry does not exist @@ -113,7 +114,7 @@ class GenericSubscriber : public Subscriber { * because std::vector is special-cased in C++. 0 is false, any * non-zero value is true. */ - std::vector GetBooleanArray(wpi::span defaultValue) const; + std::vector GetBooleanArray(std::span defaultValue) const; /** * Gets the entry's value as a integer array. If the entry does not exist @@ -126,7 +127,7 @@ class GenericSubscriber : public Subscriber { * concern, use GetValue() instead. */ std::vector GetIntegerArray( - wpi::span defaultValue) const; + std::span defaultValue) const; /** * Gets the entry's value as a float array. If the entry does not exist @@ -138,7 +139,7 @@ class GenericSubscriber : public Subscriber { * @note This makes a copy of the array. If the overhead of this is a * concern, use GetValue() instead. */ - std::vector GetFloatArray(wpi::span defaultValue) const; + std::vector GetFloatArray(std::span defaultValue) const; /** * Gets the entry's value as a double array. If the entry does not exist @@ -151,7 +152,7 @@ class GenericSubscriber : public Subscriber { * concern, use GetValue() instead. */ std::vector GetDoubleArray( - wpi::span defaultValue) const; + std::span defaultValue) const; /** * Gets the entry's value as a string array. If the entry does not exist @@ -164,7 +165,7 @@ class GenericSubscriber : public Subscriber { * concern, use GetValue() instead. */ std::vector GetStringArray( - wpi::span defaultValue) const; + std::span defaultValue) const; /** * Get an array of all value changes since the last call to ReadQueue. @@ -265,7 +266,7 @@ class GenericPublisher : public Publisher { * @param time the timestamp to set (0 = nt::Now()) * @return False if the entry exists with a different type */ - bool SetRaw(wpi::span value, int64_t time = 0); + bool SetRaw(std::span value, int64_t time = 0); /** * Sets the entry's value. @@ -274,7 +275,7 @@ class GenericPublisher : public Publisher { * @param time the timestamp to set (0 = nt::Now()) * @return False if the entry exists with a different type */ - bool SetBooleanArray(wpi::span value, int64_t time = 0); + bool SetBooleanArray(std::span value, int64_t time = 0); /** * Sets the entry's value. @@ -283,7 +284,7 @@ class GenericPublisher : public Publisher { * @param time the timestamp to set (0 = nt::Now()) * @return False if the entry exists with a different type */ - bool SetBooleanArray(wpi::span value, int64_t time = 0); + bool SetBooleanArray(std::span value, int64_t time = 0); /** * Sets the entry's value. @@ -292,7 +293,7 @@ class GenericPublisher : public Publisher { * @param time the timestamp to set (0 = nt::Now()) * @return False if the entry exists with a different type */ - bool SetIntegerArray(wpi::span value, int64_t time = 0); + bool SetIntegerArray(std::span value, int64_t time = 0); /** * Sets the entry's value. @@ -301,7 +302,7 @@ class GenericPublisher : public Publisher { * @param time the timestamp to set (0 = nt::Now()) * @return False if the entry exists with a different type */ - bool SetFloatArray(wpi::span value, int64_t time = 0); + bool SetFloatArray(std::span value, int64_t time = 0); /** * Sets the entry's value. @@ -310,7 +311,7 @@ class GenericPublisher : public Publisher { * @param time the timestamp to set (0 = nt::Now()) * @return False if the entry exists with a different type */ - bool SetDoubleArray(wpi::span value, int64_t time = 0); + bool SetDoubleArray(std::span value, int64_t time = 0); /** * Sets the entry's value. @@ -319,7 +320,7 @@ class GenericPublisher : public Publisher { * @param time the timestamp to set (0 = nt::Now()) * @return False if the entry exists with a different type */ - bool SetStringArray(wpi::span value, int64_t time = 0); + bool SetStringArray(std::span value, int64_t time = 0); /** * Publish a default value. @@ -376,7 +377,7 @@ class GenericPublisher : public Publisher { * @param defaultValue the default value to set * @return False if the entry exists with a different type */ - bool SetDefaultRaw(wpi::span defaultValue); + bool SetDefaultRaw(std::span defaultValue); /** * Sets the entry's value if it does not exist. @@ -384,7 +385,7 @@ class GenericPublisher : public Publisher { * @param defaultValue the default value to set * @return False if the entry exists with a different type */ - bool SetDefaultBooleanArray(wpi::span defaultValue); + bool SetDefaultBooleanArray(std::span defaultValue); /** * Sets the entry's value if it does not exist. @@ -392,7 +393,7 @@ class GenericPublisher : public Publisher { * @param defaultValue the default value to set * @return False if the entry exists with a different type */ - bool SetDefaultIntegerArray(wpi::span defaultValue); + bool SetDefaultIntegerArray(std::span defaultValue); /** * Sets the entry's value if it does not exist. @@ -400,7 +401,7 @@ class GenericPublisher : public Publisher { * @param defaultValue the default value to set * @return False if the entry exists with a different type */ - bool SetDefaultFloatArray(wpi::span defaultValue); + bool SetDefaultFloatArray(std::span defaultValue); /** * Sets the entry's value if it does not exist. @@ -408,7 +409,7 @@ class GenericPublisher : public Publisher { * @param defaultValue the default value to set * @return False if the entry exists with a different type */ - bool SetDefaultDoubleArray(wpi::span defaultValue); + bool SetDefaultDoubleArray(std::span defaultValue); /** * Sets the entry's value if it does not exist. @@ -416,7 +417,7 @@ class GenericPublisher : public Publisher { * @param defaultValue the default value to set * @return False if the entry exists with a different type */ - bool SetDefaultStringArray(wpi::span defaultValue); + bool SetDefaultStringArray(std::span defaultValue); /** * Get the corresponding topic. diff --git a/ntcore/src/main/native/include/networktables/GenericEntry.inc b/ntcore/src/main/native/include/networktables/GenericEntry.inc index afb4eccff51..f3d996707bc 100644 --- a/ntcore/src/main/native/include/networktables/GenericEntry.inc +++ b/ntcore/src/main/native/include/networktables/GenericEntry.inc @@ -4,6 +4,7 @@ #pragma once +#include #include #include #include @@ -43,32 +44,32 @@ inline std::string GenericSubscriber::GetString( } inline std::vector GenericSubscriber::GetRaw( - wpi::span defaultValue) const { + std::span defaultValue) const { return ::nt::GetRaw(m_subHandle, defaultValue); } inline std::vector GenericSubscriber::GetBooleanArray( - wpi::span defaultValue) const { + std::span defaultValue) const { return ::nt::GetBooleanArray(m_subHandle, defaultValue); } inline std::vector GenericSubscriber::GetIntegerArray( - wpi::span defaultValue) const { + std::span defaultValue) const { return ::nt::GetIntegerArray(m_subHandle, defaultValue); } inline std::vector GenericSubscriber::GetFloatArray( - wpi::span defaultValue) const { + std::span defaultValue) const { return ::nt::GetFloatArray(m_subHandle, defaultValue); } inline std::vector GenericSubscriber::GetDoubleArray( - wpi::span defaultValue) const { + std::span defaultValue) const { return ::nt::GetDoubleArray(m_subHandle, defaultValue); } inline std::vector GenericSubscriber::GetStringArray( - wpi::span defaultValue) const { + std::span defaultValue) const { return ::nt::GetStringArray(m_subHandle, defaultValue); } @@ -107,37 +108,37 @@ inline bool GenericPublisher::SetString(std::string_view value, int64_t time) { return nt::SetString(m_pubHandle, value, time); } -inline bool GenericPublisher::SetRaw(wpi::span value, +inline bool GenericPublisher::SetRaw(std::span value, int64_t time) { return nt::SetRaw(m_pubHandle, value, time); } -inline bool GenericPublisher::SetBooleanArray(wpi::span value, +inline bool GenericPublisher::SetBooleanArray(std::span value, int64_t time) { return SetEntryValue(m_pubHandle, Value::MakeBooleanArray(value, time)); } -inline bool GenericPublisher::SetBooleanArray(wpi::span value, +inline bool GenericPublisher::SetBooleanArray(std::span value, int64_t time) { return nt::SetBooleanArray(m_pubHandle, value, time); } -inline bool GenericPublisher::SetIntegerArray(wpi::span value, +inline bool GenericPublisher::SetIntegerArray(std::span value, int64_t time) { return nt::SetIntegerArray(m_pubHandle, value, time); } -inline bool GenericPublisher::SetFloatArray(wpi::span value, +inline bool GenericPublisher::SetFloatArray(std::span value, int64_t time) { return nt::SetFloatArray(m_pubHandle, value, time); } -inline bool GenericPublisher::SetDoubleArray(wpi::span value, +inline bool GenericPublisher::SetDoubleArray(std::span value, int64_t time) { return nt::SetDoubleArray(m_pubHandle, value, time); } -inline bool GenericPublisher::SetStringArray(wpi::span value, +inline bool GenericPublisher::SetStringArray(std::span value, int64_t time) { return nt::SetStringArray(m_pubHandle, value, time); } @@ -167,32 +168,32 @@ inline bool GenericPublisher::SetDefaultString(std::string_view defaultValue) { } inline bool GenericPublisher::SetDefaultRaw( - wpi::span defaultValue) { + std::span defaultValue) { return nt::SetDefaultRaw(m_pubHandle, defaultValue); } inline bool GenericPublisher::SetDefaultBooleanArray( - wpi::span defaultValue) { + std::span defaultValue) { return nt::SetDefaultBooleanArray(m_pubHandle, defaultValue); } inline bool GenericPublisher::SetDefaultIntegerArray( - wpi::span defaultValue) { + std::span defaultValue) { return nt::SetDefaultIntegerArray(m_pubHandle, defaultValue); } inline bool GenericPublisher::SetDefaultFloatArray( - wpi::span defaultValue) { + std::span defaultValue) { return nt::SetDefaultFloatArray(m_pubHandle, defaultValue); } inline bool GenericPublisher::SetDefaultDoubleArray( - wpi::span defaultValue) { + std::span defaultValue) { return nt::SetDefaultDoubleArray(m_pubHandle, defaultValue); } inline bool GenericPublisher::SetDefaultStringArray( - wpi::span defaultValue) { + std::span defaultValue) { return nt::SetDefaultStringArray(m_pubHandle, defaultValue); } diff --git a/ntcore/src/main/native/include/networktables/MultiSubscriber.h b/ntcore/src/main/native/include/networktables/MultiSubscriber.h index face5bc9602..69c286c1ac1 100644 --- a/ntcore/src/main/native/include/networktables/MultiSubscriber.h +++ b/ntcore/src/main/native/include/networktables/MultiSubscriber.h @@ -4,10 +4,9 @@ #pragma once +#include #include -#include - #include "networktables/NetworkTableInstance.h" #include "ntcore_cpp.h" @@ -30,8 +29,8 @@ class MultiSubscriber final { * @param options subscriber options */ MultiSubscriber(NetworkTableInstance inst, - wpi::span prefixes, - wpi::span options = {}); + std::span prefixes, + std::span options = {}); MultiSubscriber(const MultiSubscriber&) = delete; MultiSubscriber& operator=(const MultiSubscriber&) = delete; diff --git a/ntcore/src/main/native/include/networktables/MultiSubscriber.inc b/ntcore/src/main/native/include/networktables/MultiSubscriber.inc index 2c2bbb28e03..25aed502ce6 100644 --- a/ntcore/src/main/native/include/networktables/MultiSubscriber.inc +++ b/ntcore/src/main/native/include/networktables/MultiSubscriber.inc @@ -9,8 +9,8 @@ namespace nt { inline MultiSubscriber::MultiSubscriber( - NetworkTableInstance inst, wpi::span prefixes, - wpi::span options) + NetworkTableInstance inst, std::span prefixes, + std::span options) : m_handle{::nt::SubscribeMultiple(inst.GetHandle(), prefixes, options)} {} inline MultiSubscriber::MultiSubscriber(MultiSubscriber&& rhs) diff --git a/ntcore/src/main/native/include/networktables/NetworkTable.h b/ntcore/src/main/native/include/networktables/NetworkTable.h index 50e16b3a32e..e1eec5a14ab 100644 --- a/ntcore/src/main/native/include/networktables/NetworkTable.h +++ b/ntcore/src/main/native/include/networktables/NetworkTable.h @@ -6,6 +6,7 @@ #include #include +#include #include #include #include @@ -13,7 +14,6 @@ #include #include -#include #include "networktables/NetworkTableEntry.h" #include "ntcore_c.h" @@ -400,7 +400,7 @@ class NetworkTable final { * std::vector is special-cased in C++. 0 is false, any * non-zero value is true. */ - bool PutBooleanArray(std::string_view key, wpi::span value); + bool PutBooleanArray(std::string_view key, std::span value); /** * Gets the current value in the table, setting it if it does not exist. @@ -410,7 +410,7 @@ class NetworkTable final { * @return False if the table key exists with a different type */ bool SetDefaultBooleanArray(std::string_view key, - wpi::span defaultValue); + std::span defaultValue); /** * Returns the boolean array the key maps to. If the key does not exist or is @@ -429,7 +429,7 @@ class NetworkTable final { * non-zero value is true. */ std::vector GetBooleanArray(std::string_view key, - wpi::span defaultValue) const; + std::span defaultValue) const; /** * Put a number array in the table @@ -438,7 +438,7 @@ class NetworkTable final { * @param value the value that will be assigned * @return False if the table key already exists with a different type */ - bool PutNumberArray(std::string_view key, wpi::span value); + bool PutNumberArray(std::string_view key, std::span value); /** * Gets the current value in the table, setting it if it does not exist. @@ -448,7 +448,7 @@ class NetworkTable final { * @returns False if the table key exists with a different type */ bool SetDefaultNumberArray(std::string_view key, - wpi::span defaultValue); + std::span defaultValue); /** * Returns the number array the key maps to. If the key does not exist or is @@ -463,7 +463,7 @@ class NetworkTable final { * concern, use GetValue() instead. */ std::vector GetNumberArray( - std::string_view key, wpi::span defaultValue) const; + std::string_view key, std::span defaultValue) const; /** * Put a string array in the table @@ -472,7 +472,7 @@ class NetworkTable final { * @param value the value that will be assigned * @return False if the table key already exists with a different type */ - bool PutStringArray(std::string_view key, wpi::span value); + bool PutStringArray(std::string_view key, std::span value); /** * Gets the current value in the table, setting it if it does not exist. @@ -482,7 +482,7 @@ class NetworkTable final { * @returns False if the table key exists with a different type */ bool SetDefaultStringArray(std::string_view key, - wpi::span defaultValue); + std::span defaultValue); /** * Returns the string array the key maps to. If the key does not exist or is @@ -497,7 +497,7 @@ class NetworkTable final { * concern, use GetValue() instead. */ std::vector GetStringArray( - std::string_view key, wpi::span defaultValue) const; + std::string_view key, std::span defaultValue) const; /** * Put a raw value (byte array) in the table @@ -506,7 +506,7 @@ class NetworkTable final { * @param value the value that will be assigned * @return False if the table key already exists with a different type */ - bool PutRaw(std::string_view key, wpi::span value); + bool PutRaw(std::string_view key, std::span value); /** * Gets the current value in the table, setting it if it does not exist. @@ -516,7 +516,7 @@ class NetworkTable final { * @return False if the table key exists with a different type */ bool SetDefaultRaw(std::string_view key, - wpi::span defaultValue); + std::span defaultValue); /** * Returns the raw value (byte array) the key maps to. If the key does not @@ -531,7 +531,7 @@ class NetworkTable final { * concern, use GetValue() instead. */ std::vector GetRaw(std::string_view key, - wpi::span defaultValue) const; + std::span defaultValue) const; /** * Put a value in the table diff --git a/ntcore/src/main/native/include/networktables/NetworkTableEntry.h b/ntcore/src/main/native/include/networktables/NetworkTableEntry.h index 12b7d5ed04e..14476b58896 100644 --- a/ntcore/src/main/native/include/networktables/NetworkTableEntry.h +++ b/ntcore/src/main/native/include/networktables/NetworkTableEntry.h @@ -8,12 +8,12 @@ #include #include +#include #include #include #include #include -#include #include "networktables/NetworkTableType.h" #include "networktables/NetworkTableValue.h" @@ -170,7 +170,7 @@ class NetworkTableEntry final { * @param defaultValue the value to be returned if no value is found * @return the entry's value or the given default value */ - std::vector GetRaw(wpi::span defaultValue) const; + std::vector GetRaw(std::span defaultValue) const; /** * Gets the entry's value as a boolean array. If the entry does not exist @@ -186,7 +186,7 @@ class NetworkTableEntry final { * because std::vector is special-cased in C++. 0 is false, any * non-zero value is true. */ - std::vector GetBooleanArray(wpi::span defaultValue) const; + std::vector GetBooleanArray(std::span defaultValue) const; /** * Gets the entry's value as a integer array. If the entry does not exist @@ -199,7 +199,7 @@ class NetworkTableEntry final { * concern, use GetValue() instead. */ std::vector GetIntegerArray( - wpi::span defaultValue) const; + std::span defaultValue) const; /** * Gets the entry's value as a float array. If the entry does not exist @@ -211,7 +211,7 @@ class NetworkTableEntry final { * @note This makes a copy of the array. If the overhead of this is a * concern, use GetValue() instead. */ - std::vector GetFloatArray(wpi::span defaultValue) const; + std::vector GetFloatArray(std::span defaultValue) const; /** * Gets the entry's value as a double array. If the entry does not exist @@ -224,7 +224,7 @@ class NetworkTableEntry final { * concern, use GetValue() instead. */ std::vector GetDoubleArray( - wpi::span defaultValue) const; + std::span defaultValue) const; /** * Gets the entry's value as a string array. If the entry does not exist @@ -237,7 +237,7 @@ class NetworkTableEntry final { * concern, use GetValue() instead. */ std::vector GetStringArray( - wpi::span defaultValue) const; + std::span defaultValue) const; /** * Get an array of all value changes since the last call to ReadQueue. @@ -303,7 +303,7 @@ class NetworkTableEntry final { * @param defaultValue the default value to set * @return False if the entry exists with a different type */ - bool SetDefaultRaw(wpi::span defaultValue); + bool SetDefaultRaw(std::span defaultValue); /** * Sets the entry's value if it does not exist. @@ -311,7 +311,7 @@ class NetworkTableEntry final { * @param defaultValue the default value to set * @return False if the entry exists with a different type */ - bool SetDefaultBooleanArray(wpi::span defaultValue); + bool SetDefaultBooleanArray(std::span defaultValue); /** * Sets the entry's value if it does not exist. @@ -319,7 +319,7 @@ class NetworkTableEntry final { * @param defaultValue the default value to set * @return False if the entry exists with a different type */ - bool SetDefaultIntegerArray(wpi::span defaultValue); + bool SetDefaultIntegerArray(std::span defaultValue); /** * Sets the entry's value if it does not exist. @@ -327,7 +327,7 @@ class NetworkTableEntry final { * @param defaultValue the default value to set * @return False if the entry exists with a different type */ - bool SetDefaultFloatArray(wpi::span defaultValue); + bool SetDefaultFloatArray(std::span defaultValue); /** * Sets the entry's value if it does not exist. @@ -335,7 +335,7 @@ class NetworkTableEntry final { * @param defaultValue the default value to set * @return False if the entry exists with a different type */ - bool SetDefaultDoubleArray(wpi::span defaultValue); + bool SetDefaultDoubleArray(std::span defaultValue); /** * Sets the entry's value if it does not exist. @@ -343,7 +343,7 @@ class NetworkTableEntry final { * @param defaultValue the default value to set * @return False if the entry exists with a different type */ - bool SetDefaultStringArray(wpi::span defaultValue); + bool SetDefaultStringArray(std::span defaultValue); /** * Sets the entry's value. @@ -405,7 +405,7 @@ class NetworkTableEntry final { * @param time the timestamp to set (0 = nt::Now()) * @return False if the entry exists with a different type */ - bool SetRaw(wpi::span value, int64_t time = 0); + bool SetRaw(std::span value, int64_t time = 0); /** * Sets the entry's value. @@ -414,7 +414,7 @@ class NetworkTableEntry final { * @param time the timestamp to set (0 = nt::Now()) * @return False if the entry exists with a different type */ - bool SetBooleanArray(wpi::span value, int64_t time = 0); + bool SetBooleanArray(std::span value, int64_t time = 0); /** * Sets the entry's value. @@ -423,7 +423,7 @@ class NetworkTableEntry final { * @param time the timestamp to set (0 = nt::Now()) * @return False if the entry exists with a different type */ - bool SetBooleanArray(wpi::span value, int64_t time = 0); + bool SetBooleanArray(std::span value, int64_t time = 0); /** * Sets the entry's value. @@ -432,7 +432,7 @@ class NetworkTableEntry final { * @param time the timestamp to set (0 = nt::Now()) * @return False if the entry exists with a different type */ - bool SetIntegerArray(wpi::span value, int64_t time = 0); + bool SetIntegerArray(std::span value, int64_t time = 0); /** * Sets the entry's value. @@ -441,7 +441,7 @@ class NetworkTableEntry final { * @param time the timestamp to set (0 = nt::Now()) * @return False if the entry exists with a different type */ - bool SetFloatArray(wpi::span value, int64_t time = 0); + bool SetFloatArray(std::span value, int64_t time = 0); /** * Sets the entry's value. @@ -450,7 +450,7 @@ class NetworkTableEntry final { * @param time the timestamp to set (0 = nt::Now()) * @return False if the entry exists with a different type */ - bool SetDoubleArray(wpi::span value, int64_t time = 0); + bool SetDoubleArray(std::span value, int64_t time = 0); /** * Sets the entry's value. @@ -459,7 +459,7 @@ class NetworkTableEntry final { * @param time the timestamp to set (0 = nt::Now()) * @return False if the entry exists with a different type */ - bool SetStringArray(wpi::span value, int64_t time = 0); + bool SetStringArray(std::span value, int64_t time = 0); /** * Sets flags. diff --git a/ntcore/src/main/native/include/networktables/NetworkTableEntry.inc b/ntcore/src/main/native/include/networktables/NetworkTableEntry.inc index 35648b1740a..0b4f628f4aa 100644 --- a/ntcore/src/main/native/include/networktables/NetworkTableEntry.inc +++ b/ntcore/src/main/native/include/networktables/NetworkTableEntry.inc @@ -70,32 +70,32 @@ inline std::string NetworkTableEntry::GetString( } inline std::vector NetworkTableEntry::GetRaw( - wpi::span defaultValue) const { + std::span defaultValue) const { return nt::GetRaw(m_handle, defaultValue); } inline std::vector NetworkTableEntry::GetBooleanArray( - wpi::span defaultValue) const { + std::span defaultValue) const { return nt::GetBooleanArray(m_handle, defaultValue); } inline std::vector NetworkTableEntry::GetIntegerArray( - wpi::span defaultValue) const { + std::span defaultValue) const { return nt::GetIntegerArray(m_handle, defaultValue); } inline std::vector NetworkTableEntry::GetFloatArray( - wpi::span defaultValue) const { + std::span defaultValue) const { return nt::GetFloatArray(m_handle, defaultValue); } inline std::vector NetworkTableEntry::GetDoubleArray( - wpi::span defaultValue) const { + std::span defaultValue) const { return nt::GetDoubleArray(m_handle, defaultValue); } inline std::vector NetworkTableEntry::GetStringArray( - wpi::span defaultValue) const { + std::span defaultValue) const { return nt::GetStringArray(m_handle, defaultValue); } @@ -128,32 +128,32 @@ inline bool NetworkTableEntry::SetDefaultString(std::string_view defaultValue) { } inline bool NetworkTableEntry::SetDefaultRaw( - wpi::span defaultValue) { + std::span defaultValue) { return nt::SetDefaultRaw(m_handle, defaultValue); } inline bool NetworkTableEntry::SetDefaultBooleanArray( - wpi::span defaultValue) { + std::span defaultValue) { return nt::SetDefaultBooleanArray(m_handle, defaultValue); } inline bool NetworkTableEntry::SetDefaultIntegerArray( - wpi::span defaultValue) { + std::span defaultValue) { return nt::SetDefaultIntegerArray(m_handle, defaultValue); } inline bool NetworkTableEntry::SetDefaultFloatArray( - wpi::span defaultValue) { + std::span defaultValue) { return nt::SetDefaultFloatArray(m_handle, defaultValue); } inline bool NetworkTableEntry::SetDefaultDoubleArray( - wpi::span defaultValue) { + std::span defaultValue) { return nt::SetDefaultDoubleArray(m_handle, defaultValue); } inline bool NetworkTableEntry::SetDefaultStringArray( - wpi::span defaultValue) { + std::span defaultValue) { return nt::SetDefaultStringArray(m_handle, defaultValue); } @@ -181,38 +181,38 @@ inline bool NetworkTableEntry::SetString(std::string_view value, int64_t time) { return nt::SetString(m_handle, value, time); } -inline bool NetworkTableEntry::SetRaw(wpi::span value, +inline bool NetworkTableEntry::SetRaw(std::span value, int64_t time) { return nt::SetRaw(m_handle, value, time); } -inline bool NetworkTableEntry::SetBooleanArray(wpi::span value, +inline bool NetworkTableEntry::SetBooleanArray(std::span value, int64_t time) { return SetEntryValue(m_handle, Value::MakeBooleanArray(value, time)); } -inline bool NetworkTableEntry::SetBooleanArray(wpi::span value, +inline bool NetworkTableEntry::SetBooleanArray(std::span value, int64_t time) { return nt::SetBooleanArray(m_handle, value, time); } -inline bool NetworkTableEntry::SetIntegerArray(wpi::span value, +inline bool NetworkTableEntry::SetIntegerArray(std::span value, int64_t time) { return nt::SetIntegerArray(m_handle, value, time); } -inline bool NetworkTableEntry::SetFloatArray(wpi::span value, +inline bool NetworkTableEntry::SetFloatArray(std::span value, int64_t time) { return nt::SetFloatArray(m_handle, value, time); } -inline bool NetworkTableEntry::SetDoubleArray(wpi::span value, +inline bool NetworkTableEntry::SetDoubleArray(std::span value, int64_t time) { return nt::SetDoubleArray(m_handle, value, time); } inline bool NetworkTableEntry::SetStringArray( - wpi::span value, int64_t time) { + std::span value, int64_t time) { return nt::SetStringArray(m_handle, value, time); } diff --git a/ntcore/src/main/native/include/networktables/NetworkTableInstance.h b/ntcore/src/main/native/include/networktables/NetworkTableInstance.h index 638665c3dbb..876ea395d84 100644 --- a/ntcore/src/main/native/include/networktables/NetworkTableInstance.h +++ b/ntcore/src/main/native/include/networktables/NetworkTableInstance.h @@ -6,13 +6,12 @@ #include #include +#include #include #include #include #include -#include - #include "networktables/NetworkTable.h" #include "networktables/NetworkTableEntry.h" #include "ntcore_c.h" @@ -283,7 +282,7 @@ class NetworkTableInstance final { * @return Array of topic handles. */ std::vector GetTopics(std::string_view prefix, - wpi::span types); + std::span types); /** * Get Topic Information about multiple topics. @@ -336,7 +335,7 @@ class NetworkTableInstance final { * @return Array of topic information. */ std::vector GetTopicInfo(std::string_view prefix, - wpi::span types); + std::span types); /** * Gets the entry for a key. @@ -466,7 +465,7 @@ class NetworkTableInstance final { * @param servers array of server address and port pairs */ void SetServer( - wpi::span> servers); + std::span> servers); /** * Sets server addresses and port for client (without restarting client). @@ -475,7 +474,7 @@ class NetworkTableInstance final { * @param servers array of server names * @param port port to communicate over (0 = default) */ - void SetServer(wpi::span servers, + void SetServer(std::span servers, unsigned int port = 0); /** diff --git a/ntcore/src/main/native/include/networktables/NetworkTableInstance.inc b/ntcore/src/main/native/include/networktables/NetworkTableInstance.inc index f2a088b7f99..73fc86efae3 100644 --- a/ntcore/src/main/native/include/networktables/NetworkTableInstance.inc +++ b/ntcore/src/main/native/include/networktables/NetworkTableInstance.inc @@ -54,7 +54,7 @@ inline std::vector NetworkTableInstance::GetTopics( } inline std::vector NetworkTableInstance::GetTopics( - std::string_view prefix, wpi::span types) { + std::string_view prefix, std::span types) { auto handles = ::nt::GetTopics(m_handle, prefix, types); return {handles.begin(), handles.end()}; } @@ -74,7 +74,7 @@ inline std::vector NetworkTableInstance::GetTopicInfo( } inline std::vector NetworkTableInstance::GetTopicInfo( - std::string_view prefix, wpi::span types) { + std::string_view prefix, std::span types) { return ::nt::GetTopicInfo(m_handle, prefix, types); } @@ -132,7 +132,7 @@ inline void NetworkTableInstance::SetServer(const char* server_name, } inline void NetworkTableInstance::SetServer( - wpi::span> servers) { + std::span> servers) { ::nt::SetServer(m_handle, servers); } diff --git a/ntcore/src/main/native/include/networktables/NetworkTableValue.h b/ntcore/src/main/native/include/networktables/NetworkTableValue.h index 80632b30171..f4454c29244 100644 --- a/ntcore/src/main/native/include/networktables/NetworkTableValue.h +++ b/ntcore/src/main/native/include/networktables/NetworkTableValue.h @@ -9,14 +9,13 @@ #include #include #include +#include #include #include #include #include #include -#include - #include "ntcore_c.h" namespace nt { @@ -235,7 +234,7 @@ class Value final { * * @return The raw value. */ - wpi::span GetRaw() const { + std::span GetRaw() const { assert(m_val.type == NT_RAW); return {m_val.data.v_raw.data, m_val.data.v_raw.size}; } @@ -245,7 +244,7 @@ class Value final { * * @return The boolean array value. */ - wpi::span GetBooleanArray() const { + std::span GetBooleanArray() const { assert(m_val.type == NT_BOOLEAN_ARRAY); return {m_val.data.arr_boolean.arr, m_val.data.arr_boolean.size}; } @@ -255,7 +254,7 @@ class Value final { * * @return The integer array value. */ - wpi::span GetIntegerArray() const { + std::span GetIntegerArray() const { assert(m_val.type == NT_INTEGER_ARRAY); return {m_val.data.arr_int.arr, m_val.data.arr_int.size}; } @@ -265,7 +264,7 @@ class Value final { * * @return The float array value. */ - wpi::span GetFloatArray() const { + std::span GetFloatArray() const { assert(m_val.type == NT_FLOAT_ARRAY); return {m_val.data.arr_float.arr, m_val.data.arr_float.size}; } @@ -275,7 +274,7 @@ class Value final { * * @return The double array value. */ - wpi::span GetDoubleArray() const { + std::span GetDoubleArray() const { assert(m_val.type == NT_DOUBLE_ARRAY); return {m_val.data.arr_double.arr, m_val.data.arr_double.size}; } @@ -285,7 +284,7 @@ class Value final { * * @return The string array value. */ - wpi::span GetStringArray() const { + std::span GetStringArray() const { assert(m_val.type == NT_STRING_ARRAY); return *static_cast*>(m_storage.get()); } @@ -397,7 +396,7 @@ class Value final { * time) * @return The entry value */ - static Value MakeRaw(wpi::span value, int64_t time = 0) { + static Value MakeRaw(std::span value, int64_t time = 0) { Value val{NT_RAW, time, private_init{}}; auto data = std::make_shared>(value.begin(), value.end()); @@ -434,7 +433,7 @@ class Value final { * time) * @return The entry value */ - static Value MakeBooleanArray(wpi::span value, int64_t time = 0); + static Value MakeBooleanArray(std::span value, int64_t time = 0); /** * Creates a boolean array entry value. @@ -446,7 +445,7 @@ class Value final { */ static Value MakeBooleanArray(std::initializer_list value, int64_t time = 0) { - return MakeBooleanArray(wpi::span(value.begin(), value.end()), time); + return MakeBooleanArray(std::span(value.begin(), value.end()), time); } /** @@ -457,7 +456,7 @@ class Value final { * time) * @return The entry value */ - static Value MakeBooleanArray(wpi::span value, int64_t time = 0); + static Value MakeBooleanArray(std::span value, int64_t time = 0); /** * Creates a boolean array entry value. @@ -469,7 +468,7 @@ class Value final { */ static Value MakeBooleanArray(std::initializer_list value, int64_t time = 0) { - return MakeBooleanArray(wpi::span(value.begin(), value.end()), time); + return MakeBooleanArray(std::span(value.begin(), value.end()), time); } /** @@ -480,7 +479,7 @@ class Value final { * time) * @return The entry value */ - static Value MakeIntegerArray(wpi::span value, + static Value MakeIntegerArray(std::span value, int64_t time = 0); /** @@ -493,7 +492,7 @@ class Value final { */ static Value MakeIntegerArray(std::initializer_list value, int64_t time = 0) { - return MakeIntegerArray(wpi::span(value.begin(), value.end()), time); + return MakeIntegerArray(std::span(value.begin(), value.end()), time); } /** @@ -504,7 +503,7 @@ class Value final { * time) * @return The entry value */ - static Value MakeFloatArray(wpi::span value, int64_t time = 0); + static Value MakeFloatArray(std::span value, int64_t time = 0); /** * Creates a float array entry value. @@ -516,7 +515,7 @@ class Value final { */ static Value MakeFloatArray(std::initializer_list value, int64_t time = 0) { - return MakeFloatArray(wpi::span(value.begin(), value.end()), time); + return MakeFloatArray(std::span(value.begin(), value.end()), time); } /** @@ -527,7 +526,7 @@ class Value final { * time) * @return The entry value */ - static Value MakeDoubleArray(wpi::span value, int64_t time = 0); + static Value MakeDoubleArray(std::span value, int64_t time = 0); /** * Creates a double array entry value. @@ -539,7 +538,7 @@ class Value final { */ static Value MakeDoubleArray(std::initializer_list value, int64_t time = 0) { - return MakeDoubleArray(wpi::span(value.begin(), value.end()), time); + return MakeDoubleArray(std::span(value.begin(), value.end()), time); } /** @@ -550,7 +549,7 @@ class Value final { * time) * @return The entry value */ - static Value MakeStringArray(wpi::span value, + static Value MakeStringArray(std::span value, int64_t time = 0); /** @@ -563,7 +562,7 @@ class Value final { */ static Value MakeStringArray(std::initializer_list value, int64_t time = 0) { - return MakeStringArray(wpi::span(value.begin(), value.end()), time); + return MakeStringArray(std::span(value.begin(), value.end()), time); } /** diff --git a/ntcore/src/main/native/include/networktables/Topic.h b/ntcore/src/main/native/include/networktables/Topic.h index 474a92d429c..2f28f0c4940 100644 --- a/ntcore/src/main/native/include/networktables/Topic.h +++ b/ntcore/src/main/native/include/networktables/Topic.h @@ -6,6 +6,7 @@ #include +#include #include #include #include @@ -170,7 +171,7 @@ class Topic { * @return subscriber */ [[nodiscard]] GenericSubscriber GenericSubscribe( - wpi::span options = {}); + std::span options = {}); /** * Create a new subscriber to the topic. @@ -187,7 +188,7 @@ class Topic { * @return subscriber */ [[nodiscard]] GenericSubscriber GenericSubscribe( - std::string_view typeString, wpi::span options = {}); + std::string_view typeString, std::span options = {}); /** * Create a new publisher to the topic. @@ -206,7 +207,7 @@ class Topic { * @return publisher */ [[nodiscard]] GenericPublisher GenericPublish( - std::string_view typeString, wpi::span options = {}); + std::string_view typeString, std::span options = {}); /** * Create a new publisher to the topic, with type string and initial @@ -228,7 +229,7 @@ class Topic { */ [[nodiscard]] GenericPublisher GenericPublishEx( std::string_view typeString, const wpi::json& properties, - wpi::span options = {}); + std::span options = {}); /** * Create a new generic entry for the topic. @@ -249,7 +250,7 @@ class Topic { * @return entry */ [[nodiscard]] GenericEntry GetGenericEntry( - wpi::span options = {}); + std::span options = {}); /** * Create a new generic entry for the topic. @@ -271,7 +272,7 @@ class Topic { * @return entry */ [[nodiscard]] GenericEntry GetGenericEntry( - std::string_view typeString, wpi::span options = {}); + std::string_view typeString, std::span options = {}); /** * Equality operator. Returns true if both instances refer to the same diff --git a/ntcore/src/main/native/include/networktables/TopicListener.h b/ntcore/src/main/native/include/networktables/TopicListener.h index e4f738d0d4d..0f456637dec 100644 --- a/ntcore/src/main/native/include/networktables/TopicListener.h +++ b/ntcore/src/main/native/include/networktables/TopicListener.h @@ -5,11 +5,10 @@ #pragma once #include +#include #include #include -#include - #include "ntcore_cpp.h" namespace nt { @@ -83,7 +82,7 @@ class TopicListener final { * @param listener Listener function */ TopicListener(NetworkTableInstance inst, - wpi::span prefixes, unsigned int mask, + std::span prefixes, unsigned int mask, std::function listener); /** @@ -183,7 +182,7 @@ class TopicListenerPoller final { * @param mask Bitmask of TopicListenerFlags values * @return Listener handle */ - NT_TopicListener Add(wpi::span prefixes, + NT_TopicListener Add(std::span prefixes, unsigned int mask); /** diff --git a/ntcore/src/main/native/include/networktables/TopicListener.inc b/ntcore/src/main/native/include/networktables/TopicListener.inc index 9c94566db47..05fdd613c6a 100644 --- a/ntcore/src/main/native/include/networktables/TopicListener.inc +++ b/ntcore/src/main/native/include/networktables/TopicListener.inc @@ -4,12 +4,11 @@ #pragma once +#include #include #include #include -#include - #include "networktables/MultiSubscriber.h" #include "networktables/NetworkTableEntry.h" #include "networktables/NetworkTableInstance.h" @@ -20,7 +19,7 @@ namespace nt { inline TopicListener::TopicListener( - NetworkTableInstance inst, wpi::span prefixes, + NetworkTableInstance inst, std::span prefixes, unsigned int mask, std::function listener) : m_handle{AddTopicListener(inst.GetHandle(), prefixes, mask, listener)} {} @@ -81,7 +80,7 @@ inline TopicListenerPoller::~TopicListenerPoller() { } inline NT_TopicListener TopicListenerPoller::Add( - wpi::span prefixes, unsigned int mask) { + std::span prefixes, unsigned int mask) { return nt::AddPolledTopicListener(m_handle, prefixes, mask); } diff --git a/ntcore/src/main/native/include/ntcore_cpp.h b/ntcore/src/main/native/include/ntcore_cpp.h index 74f6ff58a25..5deea73cf0b 100644 --- a/ntcore/src/main/native/include/ntcore_cpp.h +++ b/ntcore/src/main/native/include/ntcore_cpp.h @@ -9,13 +9,12 @@ #include #include #include +#include #include #include #include #include -#include - #include "networktables/NetworkTableValue.h" #include "ntcore_c.h" #include "ntcore_cpp_types.h" @@ -482,7 +481,7 @@ std::vector GetTopics(NT_Inst inst, std::string_view prefix, * @return Array of topic handles. */ std::vector GetTopics(NT_Inst inst, std::string_view prefix, - wpi::span types); + std::span types); /** * Get Topic Information about multiple topics. @@ -515,7 +514,7 @@ std::vector GetTopicInfo(NT_Inst inst, std::string_view prefix, * @return Array of topic information. */ std::vector GetTopicInfo(NT_Inst inst, std::string_view prefix, - wpi::span types); + std::span types); /** * Gets Topic Information. @@ -665,7 +664,7 @@ bool SetTopicProperties(NT_Topic topic, const wpi::json& update); * @return Subscriber handle */ NT_Subscriber Subscribe(NT_Topic topic, NT_Type type, std::string_view typeStr, - wpi::span options = {}); + std::span options = {}); /** * Stops subscriber. @@ -684,7 +683,7 @@ void Unsubscribe(NT_Subscriber sub); * @return Publisher handle */ NT_Publisher Publish(NT_Topic topic, NT_Type type, std::string_view typeStr, - wpi::span options = {}); + std::span options = {}); /** * Creates a new publisher to a topic. @@ -698,7 +697,7 @@ NT_Publisher Publish(NT_Topic topic, NT_Type type, std::string_view typeStr, */ NT_Publisher PublishEx(NT_Topic topic, NT_Type type, std::string_view typeStr, const wpi::json& properties, - wpi::span options = {}); + std::span options = {}); /** * Stops publisher. @@ -717,7 +716,7 @@ void Unpublish(NT_Handle pubentry); * @return Entry handle */ NT_Entry GetEntry(NT_Topic topic, NT_Type type, std::string_view typeStr, - wpi::span options = {}); + std::span options = {}); /** * Stops entry subscriber/publisher. @@ -759,8 +758,8 @@ NT_Topic GetTopicFromHandle(NT_Handle pubsubentry); * @return subscriber handle */ NT_MultiSubscriber SubscribeMultiple( - NT_Inst inst, wpi::span prefixes, - wpi::span options = {}); + NT_Inst inst, std::span prefixes, + std::span options = {}); /** * Unsubscribes a multi-subscriber. @@ -786,7 +785,7 @@ void UnsubscribeMultiple(NT_MultiSubscriber sub); * @param callback Listener function */ NT_TopicListener AddTopicListener( - NT_Inst inst, wpi::span prefixes, unsigned int mask, + NT_Inst inst, std::span prefixes, unsigned int mask, std::function callback); /** @@ -841,7 +840,7 @@ std::vector ReadTopicListenerQueue( * @return Listener handle */ NT_TopicListener AddPolledTopicListener( - NT_TopicListenerPoller poller, wpi::span prefixes, + NT_TopicListenerPoller poller, std::span prefixes, unsigned int mask); /** @@ -1102,7 +1101,7 @@ void SetServer(NT_Inst inst, const char* server_name, unsigned int port); */ void SetServer( NT_Inst inst, - wpi::span> servers); + std::span> servers); /** * Sets server addresses and port for client (without restarting client). diff --git a/ntcore/src/test/native/cpp/SpanMatcher.h b/ntcore/src/test/native/cpp/SpanMatcher.h index 28814b3eadd..9973c036cb0 100644 --- a/ntcore/src/test/native/cpp/SpanMatcher.h +++ b/ntcore/src/test/native/cpp/SpanMatcher.h @@ -8,23 +8,22 @@ #include #include #include +#include #include #include #include -#include - #include "TestPrinters.h" #include "gmock/gmock.h" namespace wpi { template -class SpanMatcher : public ::testing::MatcherInterface> { +class SpanMatcher : public ::testing::MatcherInterface> { public: - explicit SpanMatcher(span good_) : good{good_.begin(), good_.end()} {} + explicit SpanMatcher(std::span good_) : good{good_.begin(), good_.end()} {} - bool MatchAndExplain(span val, + bool MatchAndExplain(std::span val, ::testing::MatchResultListener* listener) const override; void DescribeTo(::std::ostream* os) const override; void DescribeNegationTo(::std::ostream* os) const override; @@ -34,12 +33,12 @@ class SpanMatcher : public ::testing::MatcherInterface> { }; template -inline ::testing::Matcher> SpanEq(span good) { +inline ::testing::Matcher> SpanEq(std::span good) { return ::testing::MakeMatcher(new SpanMatcher(good)); } template -inline ::testing::Matcher> SpanEq( +inline ::testing::Matcher> SpanEq( std::initializer_list good) { return ::testing::MakeMatcher( new SpanMatcher({good.begin(), good.end()})); @@ -47,7 +46,7 @@ inline ::testing::Matcher> SpanEq( template bool SpanMatcher::MatchAndExplain( - span val, ::testing::MatchResultListener* listener) const { + std::span val, ::testing::MatchResultListener* listener) const { if (val.size() != good.size() || !std::equal(val.begin(), val.end(), good.begin())) { return false; @@ -57,17 +56,17 @@ bool SpanMatcher::MatchAndExplain( template void SpanMatcher::DescribeTo(::std::ostream* os) const { - PrintTo(span{good}, os); + PrintTo(std::span{good}, os); } template void SpanMatcher::DescribeNegationTo(::std::ostream* os) const { *os << "is not equal to "; - PrintTo(span{good}, os); + PrintTo(std::span{good}, os); } } // namespace wpi -inline wpi::span operator"" _us(const char* str, size_t len) { +inline std::span operator"" _us(const char* str, size_t len) { return {reinterpret_cast(str), len}; } diff --git a/ntcore/src/test/native/cpp/TestPrinters.h b/ntcore/src/test/native/cpp/TestPrinters.h index 381f56160b2..c7e6e9edc45 100644 --- a/ntcore/src/test/native/cpp/TestPrinters.h +++ b/ntcore/src/test/native/cpp/TestPrinters.h @@ -5,11 +5,10 @@ #pragma once #include +#include #include #include -#include - #include "gtest/gtest.h" namespace wpi { @@ -21,7 +20,7 @@ inline void PrintTo(std::string_view str, ::std::ostream* os) { } template -void PrintTo(span val, ::std::ostream* os) { +void PrintTo(std::span val, ::std::ostream* os) { *os << '{'; bool first = true; for (auto v : val) { diff --git a/ntcore/src/test/native/cpp/ValueTest.cpp b/ntcore/src/test/native/cpp/ValueTest.cpp index 2f73c3d538a..d49be44d5d9 100644 --- a/ntcore/src/test/native/cpp/ValueTest.cpp +++ b/ntcore/src/test/native/cpp/ValueTest.cpp @@ -12,15 +12,15 @@ using namespace std::string_view_literals; -namespace wpi { +namespace std { // NOLINT (clang-tidy.cert-dcl58-cpp) template -inline bool operator==(span lhs, span rhs) { +inline bool operator==(std::span lhs, std::span rhs) { if (lhs.size() != rhs.size()) { return false; } return std::equal(lhs.begin(), lhs.end(), rhs.begin()); } -} // namespace wpi +} // namespace std namespace nt { @@ -102,25 +102,25 @@ TEST_F(ValueTest, Raw) { std::vector arr{5, 4, 3, 2, 1}; auto v = Value::MakeRaw(arr); ASSERT_EQ(NT_RAW, v.type()); - ASSERT_EQ(wpi::span(arr), v.GetRaw()); + ASSERT_EQ(std::span(arr), v.GetRaw()); NT_Value cv; NT_InitValue(&cv); ConvertToC(v, &cv); ASSERT_EQ(NT_RAW, cv.type); ASSERT_EQ(5u, cv.data.v_raw.size); - ASSERT_EQ(wpi::span(reinterpret_cast("\5\4\3\2\1"), 5), - wpi::span(cv.data.v_raw.data, 5)); + ASSERT_EQ(std::span(reinterpret_cast("\5\4\3\2\1"), 5), + std::span(cv.data.v_raw.data, 5)); std::vector arr2{1, 2, 3, 4, 5, 6}; v = Value::MakeRaw(arr2); ASSERT_EQ(NT_RAW, v.type()); - ASSERT_EQ(wpi::span(arr2), v.GetRaw()); + ASSERT_EQ(std::span(arr2), v.GetRaw()); NT_DisposeValue(&cv); ConvertToC(v, &cv); ASSERT_EQ(NT_RAW, cv.type); ASSERT_EQ(6u, cv.data.v_raw.size); - ASSERT_EQ(wpi::span(reinterpret_cast("\1\2\3\4\5\6"), 6), - wpi::span(cv.data.v_raw.data, 6)); + ASSERT_EQ(std::span(reinterpret_cast("\1\2\3\4\5\6"), 6), + std::span(cv.data.v_raw.data, 6)); NT_DisposeValue(&cv); } @@ -129,7 +129,7 @@ TEST_F(ValueTest, BooleanArray) { std::vector vec{1, 0, 1}; auto v = Value::MakeBooleanArray(vec); ASSERT_EQ(NT_BOOLEAN_ARRAY, v.type()); - ASSERT_EQ(wpi::span(vec), v.GetBooleanArray()); + ASSERT_EQ(std::span(vec), v.GetBooleanArray()); NT_Value cv; NT_InitValue(&cv); ConvertToC(v, &cv); @@ -143,7 +143,7 @@ TEST_F(ValueTest, BooleanArray) { vec = {0, 1, 0}; v = Value::MakeBooleanArray(vec); ASSERT_EQ(NT_BOOLEAN_ARRAY, v.type()); - ASSERT_EQ(wpi::span(vec), v.GetBooleanArray()); + ASSERT_EQ(std::span(vec), v.GetBooleanArray()); NT_DisposeValue(&cv); ConvertToC(v, &cv); ASSERT_EQ(NT_BOOLEAN_ARRAY, cv.type); @@ -156,7 +156,7 @@ TEST_F(ValueTest, BooleanArray) { vec = {1, 0}; v = Value::MakeBooleanArray(vec); ASSERT_EQ(NT_BOOLEAN_ARRAY, v.type()); - ASSERT_EQ(wpi::span(vec), v.GetBooleanArray()); + ASSERT_EQ(std::span(vec), v.GetBooleanArray()); NT_DisposeValue(&cv); ConvertToC(v, &cv); ASSERT_EQ(NT_BOOLEAN_ARRAY, cv.type); @@ -171,7 +171,7 @@ TEST_F(ValueTest, DoubleArray) { std::vector vec{0.5, 0.25, 0.5}; auto v = Value::MakeDoubleArray(vec); ASSERT_EQ(NT_DOUBLE_ARRAY, v.type()); - ASSERT_EQ(wpi::span(vec), v.GetDoubleArray()); + ASSERT_EQ(std::span(vec), v.GetDoubleArray()); NT_Value cv; NT_InitValue(&cv); ConvertToC(v, &cv); @@ -185,7 +185,7 @@ TEST_F(ValueTest, DoubleArray) { vec = {0.25, 0.5, 0.25}; v = Value::MakeDoubleArray(vec); ASSERT_EQ(NT_DOUBLE_ARRAY, v.type()); - ASSERT_EQ(wpi::span(vec), v.GetDoubleArray()); + ASSERT_EQ(std::span(vec), v.GetDoubleArray()); NT_DisposeValue(&cv); ConvertToC(v, &cv); ASSERT_EQ(NT_DOUBLE_ARRAY, cv.type); @@ -198,7 +198,7 @@ TEST_F(ValueTest, DoubleArray) { vec = {0.5, 0.25}; v = Value::MakeDoubleArray(vec); ASSERT_EQ(NT_DOUBLE_ARRAY, v.type()); - ASSERT_EQ(wpi::span(vec), v.GetDoubleArray()); + ASSERT_EQ(std::span(vec), v.GetDoubleArray()); NT_DisposeValue(&cv); ConvertToC(v, &cv); ASSERT_EQ(NT_DOUBLE_ARRAY, cv.type); diff --git a/ntcore/src/test/native/cpp/net/MockNetworkInterface.h b/ntcore/src/test/native/cpp/net/MockNetworkInterface.h index 6e402faad02..a050ce5c800 100644 --- a/ntcore/src/test/native/cpp/net/MockNetworkInterface.h +++ b/ntcore/src/test/native/cpp/net/MockNetworkInterface.h @@ -36,7 +36,7 @@ class MockNetworkStartupInterface : public NetworkStartupInterface { const wpi::json& properties, const PubSubOptions& options), (override)); MOCK_METHOD(void, Subscribe, - (NT_Subscriber subHandle, wpi::span prefixes, + (NT_Subscriber subHandle, std::span prefixes, const PubSubOptions& options), (override)); MOCK_METHOD(void, SetValue, (NT_Publisher pubHandle, const Value& value), @@ -57,7 +57,7 @@ class MockNetworkInterface : public NetworkInterface { const wpi::json& update), (override)); MOCK_METHOD(void, Subscribe, - (NT_Subscriber subHandle, wpi::span prefixes, + (NT_Subscriber subHandle, std::span prefixes, const PubSubOptions& options), (override)); MOCK_METHOD(void, Unsubscribe, (NT_Subscriber subHandle), (override)); diff --git a/ntcore/src/test/native/cpp/net/MockWireConnection.h b/ntcore/src/test/native/cpp/net/MockWireConnection.h index 36bbcbff21b..3909cabdd8e 100644 --- a/ntcore/src/test/native/cpp/net/MockWireConnection.h +++ b/ntcore/src/test/native/cpp/net/MockWireConnection.h @@ -6,12 +6,12 @@ #include +#include #include #include #include #include -#include #include "gmock/gmock.h" #include "net/WireConnection.h" @@ -28,7 +28,7 @@ class MockWireConnection : public WireConnection { BinaryWriter SendBinary() override { return {m_binary_os, *this}; } MOCK_METHOD(void, Text, (std::string_view contents)); - MOCK_METHOD(void, Binary, (wpi::span contents)); + MOCK_METHOD(void, Binary, (std::span contents)); MOCK_METHOD(void, Flush, (), (override)); diff --git a/ntcore/src/test/native/cpp/net/WireDecoderTest.cpp b/ntcore/src/test/native/cpp/net/WireDecoderTest.cpp index 9af10ad9bec..b9d71904b98 100644 --- a/ntcore/src/test/native/cpp/net/WireDecoderTest.cpp +++ b/ntcore/src/test/native/cpp/net/WireDecoderTest.cpp @@ -30,7 +30,7 @@ class MockClientMessageHandler : public net::ClientMessageHandler { MOCK_METHOD2(ClientSetProperties, void(std::string_view name, const wpi::json& update)); MOCK_METHOD3(ClientSubscribe, - void(int64_t subuid, wpi::span prefixes, + void(int64_t subuid, std::span prefixes, const PubSubOptions& options)); MOCK_METHOD1(ClientUnsubscribe, void(int64_t subuid)); }; diff --git a/ntcore/src/test/native/cpp/net/WireEncoderTest.cpp b/ntcore/src/test/native/cpp/net/WireEncoderTest.cpp index f129c0ba3d2..6b849a0ad2f 100644 --- a/ntcore/src/test/native/cpp/net/WireEncoderTest.cpp +++ b/ntcore/src/test/native/cpp/net/WireEncoderTest.cpp @@ -2,6 +2,7 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +#include #include #include #include @@ -65,7 +66,7 @@ TEST_F(WireEncoderTextTest, SetProperties) { } TEST_F(WireEncoderTextTest, Subscribe) { - net::WireEncodeSubscribe(os, 5, std::vector{{"a", "b"}}, + net::WireEncodeSubscribe(os, 5, std::span{{"a", "b"}}, PubSubOptions{}); ASSERT_EQ(os.str(), "{\"method\":\"subscribe\",\"params\":{" @@ -75,7 +76,7 @@ TEST_F(WireEncoderTextTest, Subscribe) { TEST_F(WireEncoderTextTest, SubscribeSendAll) { PubSubOptions options; options.sendAll = true; - net::WireEncodeSubscribe(os, 5, std::vector{{"a", "b"}}, + net::WireEncodeSubscribe(os, 5, std::span{{"a", "b"}}, options); ASSERT_EQ(os.str(), "{\"method\":\"subscribe\",\"params\":{" @@ -86,7 +87,7 @@ TEST_F(WireEncoderTextTest, SubscribeSendAll) { TEST_F(WireEncoderTextTest, SubscribePeriodic) { PubSubOptions options; options.periodic = 0.5; - net::WireEncodeSubscribe(os, 5, std::vector{{"a", "b"}}, + net::WireEncodeSubscribe(os, 5, std::span{{"a", "b"}}, options); ASSERT_EQ(os.str(), "{\"method\":\"subscribe\",\"params\":{" @@ -98,7 +99,7 @@ TEST_F(WireEncoderTextTest, SubscribeAllOptions) { PubSubOptions options; options.sendAll = true; options.periodic = 0.5; - net::WireEncodeSubscribe(os, 5, std::vector{{"a", "b"}}, + net::WireEncodeSubscribe(os, 5, std::span{{"a", "b"}}, options); ASSERT_EQ(os.str(), "{\"method\":\"subscribe\",\"params\":{" diff --git a/ntcore/src/test/native/cpp/net3/MockWireConnection3.h b/ntcore/src/test/native/cpp/net3/MockWireConnection3.h index cc499d149ae..b7c785f9fa5 100644 --- a/ntcore/src/test/native/cpp/net3/MockWireConnection3.h +++ b/ntcore/src/test/native/cpp/net3/MockWireConnection3.h @@ -6,10 +6,10 @@ #include +#include #include #include -#include #include "gmock/gmock.h" #include "net3/WireConnection3.h" @@ -24,7 +24,7 @@ class MockWireConnection3 : public WireConnection3 { Writer Send() override { return {m_os, *this}; } - MOCK_METHOD(void, Data, (wpi::span data)); + MOCK_METHOD(void, Data, (std::span data)); MOCK_METHOD(void, Flush, (), (override)); diff --git a/ntcore/src/test/native/cpp/net3/WireDecoder3Test.cpp b/ntcore/src/test/native/cpp/net3/WireDecoder3Test.cpp index 8870aec0d72..1cd6ecb915f 100644 --- a/ntcore/src/test/native/cpp/net3/WireDecoder3Test.cpp +++ b/ntcore/src/test/native/cpp/net3/WireDecoder3Test.cpp @@ -42,9 +42,9 @@ class MockMessageHandler3 : public net3::MessageHandler3 { MOCK_METHOD2(FlagsUpdate, void(unsigned int id, unsigned int flags)); MOCK_METHOD1(EntryDelete, void(unsigned int id)); MOCK_METHOD3(ExecuteRpc, void(unsigned int id, unsigned int uid, - wpi::span params)); + std::span params)); MOCK_METHOD3(RpcResponse, void(unsigned int id, unsigned int uid, - wpi::span result)); + std::span result)); }; class WireDecoder3Test : public ::testing::Test { @@ -52,7 +52,7 @@ class WireDecoder3Test : public ::testing::Test { StrictMock handler; net3::WireDecoder3 decoder{handler}; - void DecodeComplete(wpi::span in) { + void DecodeComplete(std::span in) { decoder.Execute(&in); EXPECT_TRUE(in.empty()); ASSERT_EQ(decoder.GetError(), ""); diff --git a/shared/config.gradle b/shared/config.gradle index 2af4c761941..d97d004aa9a 100644 --- a/shared/config.gradle +++ b/shared/config.gradle @@ -35,7 +35,12 @@ nativeUtils.enableSourceLink() nativeUtils.platformConfigs.each { if (it.name.contains('windows')) { + it.cppCompiler.args.remove("/std:c++17") + it.cppCompiler.args.add("/std:c++20") return + } else if (it.name == 'linuxx86-64' || it.name == 'osxx86-64' || it.name == 'osxarm64') { + it.cppCompiler.args.remove("-std=c++17") + it.cppCompiler.args.add("-std=c++20") } if (it.name.contains('osx')) { it.linker.args << '-Wl,-rpath,\'@loader_path\'' diff --git a/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp b/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp index 653565c3604..004752c0d8c 100644 --- a/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp +++ b/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp @@ -7,12 +7,12 @@ #include #include #include +#include #include #include #include #include -#include using namespace halsim; @@ -45,7 +45,7 @@ void DSCommPacket::SetAlliance(uint8_t station_code) { m_alliance_station = static_cast(station_code); } -void DSCommPacket::ReadMatchtimeTag(wpi::span tagData) { +void DSCommPacket::ReadMatchtimeTag(std::span tagData) { if (tagData.size() < 6) { return; } @@ -63,7 +63,7 @@ void DSCommPacket::ReadMatchtimeTag(wpi::span tagData) { m_match_time = matchTime; } -void DSCommPacket::ReadJoystickTag(wpi::span dataInput, +void DSCommPacket::ReadJoystickTag(std::span dataInput, int index) { DSCommJoystickPacket& stick = m_joystick_packets[index]; stick.ResetUdp(); @@ -112,7 +112,7 @@ void DSCommPacket::ReadJoystickTag(wpi::span dataInput, /*---------------------------------------------------------------------------- ** Communication methods **--------------------------------------------------------------------------*/ -void DSCommPacket::DecodeTCP(wpi::span packet) { +void DSCommPacket::DecodeTCP(std::span packet) { // No header while (!packet.empty()) { int tagLength = packet[0] << 8 | packet[1]; @@ -137,7 +137,7 @@ void DSCommPacket::DecodeTCP(wpi::span packet) { } } -void DSCommPacket::DecodeUDP(wpi::span packet) { +void DSCommPacket::DecodeUDP(std::span packet) { if (packet.size() < 6) { return; } @@ -176,7 +176,7 @@ void DSCommPacket::DecodeUDP(wpi::span packet) { } } -void DSCommPacket::ReadNewMatchInfoTag(wpi::span data) { +void DSCommPacket::ReadNewMatchInfoTag(std::span data) { // Size 2 bytes, tag 1 byte if (data.size() <= 3) { return; @@ -204,7 +204,7 @@ void DSCommPacket::ReadNewMatchInfoTag(wpi::span data) { HALSIM_SetMatchInfo(&matchInfo); } -void DSCommPacket::ReadGameSpecificMessageTag(wpi::span data) { +void DSCommPacket::ReadGameSpecificMessageTag(std::span data) { // Size 2 bytes, tag 1 byte if (data.size() <= 3) { return; @@ -220,7 +220,7 @@ void DSCommPacket::ReadGameSpecificMessageTag(wpi::span data) { HALSIM_SetMatchInfo(&matchInfo); } -void DSCommPacket::ReadJoystickDescriptionTag(wpi::span data) { +void DSCommPacket::ReadJoystickDescriptionTag(std::span data) { if (data.size() < 3) { return; } diff --git a/simulation/halsim_ds_socket/src/main/native/include/DSCommPacket.h b/simulation/halsim_ds_socket/src/main/native/include/DSCommPacket.h index 914b07b9e13..bfc42c315f9 100644 --- a/simulation/halsim_ds_socket/src/main/native/include/DSCommPacket.h +++ b/simulation/halsim_ds_socket/src/main/native/include/DSCommPacket.h @@ -5,10 +5,10 @@ #pragma once #include +#include #include #include -#include #include class DSCommPacketTest; @@ -20,8 +20,8 @@ class DSCommPacket { public: DSCommPacket(void); - void DecodeTCP(wpi::span packet); - void DecodeUDP(wpi::span packet); + void DecodeTCP(std::span packet); + void DecodeUDP(std::span packet); void SendUDPToHALSim(void); void SetupSendBuffer(wpi::raw_uv_ostream& buf); @@ -53,11 +53,11 @@ class DSCommPacket { void SetAlliance(uint8_t station_code); void SetupSendHeader(wpi::raw_uv_ostream& buf); void SetupJoystickTag(wpi::raw_uv_ostream& buf); - void ReadMatchtimeTag(wpi::span tagData); - void ReadJoystickTag(wpi::span data, int index); - void ReadNewMatchInfoTag(wpi::span data); - void ReadGameSpecificMessageTag(wpi::span data); - void ReadJoystickDescriptionTag(wpi::span data); + void ReadMatchtimeTag(std::span tagData); + void ReadJoystickTag(std::span data, int index); + void ReadNewMatchInfoTag(std::span data); + void ReadGameSpecificMessageTag(std::span data); + void ReadJoystickDescriptionTag(std::span data); uint8_t m_hi; uint8_t m_lo; diff --git a/simulation/halsim_ds_socket/src/test/native/cpp/DSCommPacketTest.cpp b/simulation/halsim_ds_socket/src/test/native/cpp/DSCommPacketTest.cpp index 84df27cc17e..d1a892a7287 100644 --- a/simulation/halsim_ds_socket/src/test/native/cpp/DSCommPacketTest.cpp +++ b/simulation/halsim_ds_socket/src/test/native/cpp/DSCommPacketTest.cpp @@ -11,24 +11,24 @@ class DSCommPacketTest : public ::testing::Test { void SendJoysticks() { commPacket.SendJoysticks(); } - halsim::DSCommJoystickPacket& ReadJoystickTag(wpi::span data, + halsim::DSCommJoystickPacket& ReadJoystickTag(std::span data, int index) { commPacket.ReadJoystickTag(data, index); return commPacket.m_joystick_packets[index]; } halsim::DSCommJoystickPacket& ReadDescriptorTag( - wpi::span data) { + std::span data) { commPacket.ReadJoystickDescriptionTag(data); return commPacket.m_joystick_packets[data[3]]; } - HAL_MatchInfo& ReadNewMatchInfoTag(wpi::span data) { + HAL_MatchInfo& ReadNewMatchInfoTag(std::span data) { commPacket.ReadNewMatchInfoTag(data); return commPacket.matchInfo; } - HAL_MatchInfo& ReadGameSpecificTag(wpi::span data) { + HAL_MatchInfo& ReadGameSpecificTag(std::span data) { commPacket.ReadGameSpecificMessageTag(data); return commPacket.matchInfo; } diff --git a/simulation/halsim_gui/src/main/native/cpp/AddressableLEDGui.cpp b/simulation/halsim_gui/src/main/native/cpp/AddressableLEDGui.cpp index d6409cdba69..2528185516a 100644 --- a/simulation/halsim_gui/src/main/native/cpp/AddressableLEDGui.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/AddressableLEDGui.cpp @@ -26,7 +26,7 @@ class AddressableLEDModel : public glass::LEDDisplayModel { bool IsRunning() override { return HALSIM_GetAddressableLEDRunning(m_index); } - wpi::span GetData(wpi::SmallVectorImpl&) override { + std::span GetData(wpi::SmallVectorImpl&) override { size_t length = HALSIM_GetAddressableLEDData(m_index, m_data); return {reinterpret_cast(m_data), length}; } diff --git a/simulation/halsim_ws_server/src/test/native/cpp/main.cpp b/simulation/halsim_ws_server/src/test/native/cpp/main.cpp index 6a81441e228..382656fd8a2 100644 --- a/simulation/halsim_ws_server/src/test/native/cpp/main.cpp +++ b/simulation/halsim_ws_server/src/test/native/cpp/main.cpp @@ -28,7 +28,7 @@ class WebServerIntegrationTest : public ::testing::Test { m_server.Initialize(); // Create and initialize client - m_server.runner.ExecSync([=](auto& loop) { + m_server.runner.ExecSync([=, this](auto& loop) { m_webserverClient = std::make_shared(loop); m_webserverClient->Initialize(); }); diff --git a/upstream_utils/fmt_patches/0001-Don-t-throw-on-write-failure.patch b/upstream_utils/fmt_patches/0001-Don-t-throw-on-write-failure.patch index de3355a1225..edaf5759dad 100644 --- a/upstream_utils/fmt_patches/0001-Don-t-throw-on-write-failure.patch +++ b/upstream_utils/fmt_patches/0001-Don-t-throw-on-write-failure.patch @@ -1,7 +1,7 @@ -From d14a5bd3815e659b3c515e4c36debfecc6a47450 Mon Sep 17 00:00:00 2001 +From e685209746aabbbed0a9db54694b8ea1ca504163 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Wed, 18 May 2022 10:21:49 -0700 -Subject: [PATCH] Don't throw on write failure +Subject: [PATCH 1/2] Don't throw on write failure --- include/fmt/format-inl.h | 4 +--- diff --git a/upstream_utils/fmt_patches/0002-Suppress-C-20-clang-tidy-warning-false-positive.patch b/upstream_utils/fmt_patches/0002-Suppress-C-20-clang-tidy-warning-false-positive.patch new file mode 100644 index 00000000000..7e25fc07461 --- /dev/null +++ b/upstream_utils/fmt_patches/0002-Suppress-C-20-clang-tidy-warning-false-positive.patch @@ -0,0 +1,22 @@ +From 1d8e07241d380d13383a6ff479f3895ef49ce514 Mon Sep 17 00:00:00 2001 +From: Tyler Veness +Date: Fri, 2 Sep 2022 15:12:54 -0700 +Subject: [PATCH 2/2] Suppress C++20 clang-tidy warning false positive + +--- + include/fmt/core.h | 2 +- + 1 file changed, 1 insertion(+), 1 deletion(-) + +diff --git a/include/fmt/core.h b/include/fmt/core.h +index f6a37af..5c210bc 100644 +--- a/include/fmt/core.h ++++ b/include/fmt/core.h +@@ -2952,7 +2952,7 @@ class format_string_checker { + basic_string_view format_str, ErrorHandler eh) + : context_(format_str, num_args, types_, eh), + parse_funcs_{&parse_format_specs...}, +- types_{ ++ types_{ // NOLINT(clang-analyzer-optin.cplusplus.UninitializedObject) + mapped_type_constant>::value...} { + } diff --git a/upstream_utils/update_fmt.py b/upstream_utils/update_fmt.py index e9d5de4f9d7..1088c3937b7 100755 --- a/upstream_utils/update_fmt.py +++ b/upstream_utils/update_fmt.py @@ -21,6 +21,7 @@ def main(): os.chdir(upstream_root) for f in [ "0001-Don-t-throw-on-write-failure.patch", + "0002-Suppress-C-20-clang-tidy-warning-false-positive.patch", ]: git_am(os.path.join(wpilib_root, "upstream_utils/fmt_patches", f)) diff --git a/upstream_utils/update_llvm.py b/upstream_utils/update_llvm.py index 9e2453730ce..03e1f4d2013 100755 --- a/upstream_utils/update_llvm.py +++ b/upstream_utils/update_llvm.py @@ -27,6 +27,19 @@ def run_global_replacements(wpiutil_llvm_files): content = content.replace('include "llvm/Config', 'include "wpi') content = content.replace('include "llvm/Support', 'include "wpi') + # Fix uses of span + content = content.replace("span", "std::span") + content = content.replace('include "wpi/std::span.h"', "include ") + if wpi_file.endswith("ConvertUTFWrapper.cpp"): + content = content.replace( + "const UTF16 *Src = reinterpret_cast(SrcBytes.begin());", + "const UTF16 *Src = reinterpret_cast(&*SrcBytes.begin());", + ) + content = content.replace( + "const UTF16 *SrcEnd = reinterpret_cast(SrcBytes.end());", + "const UTF16 *SrcEnd = reinterpret_cast(&*SrcBytes.begin() + SrcBytes.size());", + ) + # Remove unused headers content = content.replace('#include "llvm-c/ErrorHandling.h"\n', "") content = content.replace('#include "wpi/Debug.h"\n', "") diff --git a/wpilibNewCommands/CMakeLists.txt b/wpilibNewCommands/CMakeLists.txt index d44939f8748..716c5080c71 100644 --- a/wpilibNewCommands/CMakeLists.txt +++ b/wpilibNewCommands/CMakeLists.txt @@ -31,7 +31,7 @@ add_library(wpilibNewCommands ${wpilibNewCommands_native_src}) set_target_properties(wpilibNewCommands PROPERTIES DEBUG_POSTFIX "d") set_property(TARGET wpilibNewCommands PROPERTY FOLDER "libraries") -target_compile_features(wpilibNewCommands PUBLIC cxx_std_17) +target_compile_features(wpilibNewCommands PUBLIC cxx_std_20) wpilib_target_warnings(wpilibNewCommands) target_link_libraries(wpilibNewCommands wpilibc) diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/Command.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/Command.cpp index f170e407b4b..70d5b5cce3a 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/Command.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/Command.cpp @@ -68,7 +68,7 @@ CommandPtr Command::BeforeStarting( } CommandPtr Command::BeforeStarting( - std::function toRun, wpi::span requirements) && { + std::function toRun, std::span requirements) && { return CommandPtr(std::move(*this).TransferOwnership()) .BeforeStarting(std::move(toRun), requirements); } @@ -80,7 +80,7 @@ CommandPtr Command::AndThen(std::function toRun, } CommandPtr Command::AndThen(std::function toRun, - wpi::span requirements) && { + std::span requirements) && { return CommandPtr(std::move(*this).TransferOwnership()) .AndThen(std::move(toRun), requirements); } diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandBase.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandBase.cpp index b6f76f365f2..4744dca021a 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandBase.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandBase.cpp @@ -18,7 +18,7 @@ void CommandBase::AddRequirements( m_requirements.insert(requirements.begin(), requirements.end()); } -void CommandBase::AddRequirements(wpi::span requirements) { +void CommandBase::AddRequirements(std::span requirements) { m_requirements.insert(requirements.begin(), requirements.end()); } diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandGroupBase.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandGroupBase.cpp index a3d275df42a..44e19857b7f 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandGroupBase.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandGroupBase.cpp @@ -20,7 +20,7 @@ bool CommandGroupBase::RequireUngrouped(const Command* command) { } bool CommandGroupBase::RequireUngrouped( - wpi::span> commands) { + std::span> commands) { bool allUngrouped = true; for (auto&& command : commands) { allUngrouped &= !command.get()->IsGrouped(); diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandPtr.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandPtr.cpp index 73ab14230c3..8b124f683c5 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandPtr.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandPtr.cpp @@ -79,7 +79,7 @@ CommandPtr CommandPtr::WithInterruptBehavior( } CommandPtr CommandPtr::AndThen(std::function toRun, - wpi::span requirements) && { + std::span requirements) && { return std::move(*this).AndThen(CommandPtr( std::make_unique(std::move(toRun), requirements))); } @@ -100,7 +100,7 @@ CommandPtr CommandPtr::AndThen(CommandPtr&& next) && { } CommandPtr CommandPtr::BeforeStarting( - std::function toRun, wpi::span requirements) && { + std::function toRun, std::span requirements) && { return std::move(*this).BeforeStarting(CommandPtr( std::make_unique(std::move(toRun), requirements))); } diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp index b4a62927062..61222a456e6 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp @@ -163,7 +163,7 @@ void CommandScheduler::Schedule(Command* command) { } } -void CommandScheduler::Schedule(wpi::span commands) { +void CommandScheduler::Schedule(std::span commands) { for (auto command : commands) { Schedule(command); } @@ -276,7 +276,7 @@ void CommandScheduler::RegisterSubsystem( } void CommandScheduler::RegisterSubsystem( - wpi::span subsystems) { + std::span subsystems) { for (auto* subsystem : subsystems) { RegisterSubsystem(subsystem); } @@ -290,7 +290,7 @@ void CommandScheduler::UnregisterSubsystem( } void CommandScheduler::UnregisterSubsystem( - wpi::span subsystems) { + std::span subsystems) { for (auto* subsystem : subsystems) { UnregisterSubsystem(subsystem); } @@ -336,7 +336,7 @@ void CommandScheduler::Cancel(const CommandPtr& command) { Cancel(command.get()); } -void CommandScheduler::Cancel(wpi::span commands) { +void CommandScheduler::Cancel(std::span commands) { for (auto command : commands) { Cancel(command); } @@ -357,7 +357,7 @@ void CommandScheduler::CancelAll() { } bool CommandScheduler::IsScheduled( - wpi::span commands) const { + std::span commands) const { for (auto command : commands) { if (!IsScheduled(command)) { return false; diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/FunctionalCommand.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/FunctionalCommand.cpp index 0c45099d68f..02e83385c5a 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/FunctionalCommand.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/FunctionalCommand.cpp @@ -21,7 +21,7 @@ FunctionalCommand::FunctionalCommand(std::function onInit, std::function onExecute, std::function onEnd, std::function isFinished, - wpi::span requirements) + std::span requirements) : m_onInit{std::move(onInit)}, m_onExecute{std::move(onExecute)}, m_onEnd{std::move(onEnd)}, diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/InstantCommand.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/InstantCommand.cpp index 96da37044a6..7b7323993fb 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/InstantCommand.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/InstantCommand.cpp @@ -13,7 +13,7 @@ InstantCommand::InstantCommand(std::function toRun, requirements) {} InstantCommand::InstantCommand(std::function toRun, - wpi::span requirements) + std::span requirements) : CommandHelper( std::move(toRun), [] {}, [](bool interrupted) {}, [] { return true; }, requirements) {} diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/MecanumControllerCommand.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/MecanumControllerCommand.cpp index 4a22493a1dc..d95d59629a4 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/MecanumControllerCommand.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/MecanumControllerCommand.cpp @@ -98,7 +98,7 @@ MecanumControllerCommand::MecanumControllerCommand( std::function output, - wpi::span requirements) + std::span requirements) : m_trajectory(std::move(trajectory)), m_pose(std::move(pose)), m_feedforward(feedforward), @@ -135,7 +135,7 @@ MecanumControllerCommand::MecanumControllerCommand( std::function output, - wpi::span requirements) + std::span requirements) : m_trajectory(std::move(trajectory)), m_pose(std::move(pose)), m_feedforward(feedforward), @@ -208,7 +208,7 @@ MecanumControllerCommand::MecanumControllerCommand( std::function output, - wpi::span requirements) + std::span requirements) : m_trajectory(std::move(trajectory)), m_pose(std::move(pose)), m_kinematics(kinematics), @@ -229,7 +229,7 @@ MecanumControllerCommand::MecanumControllerCommand( std::function output, - wpi::span requirements) + std::span requirements) : m_trajectory(std::move(trajectory)), m_pose(std::move(pose)), m_kinematics(kinematics), diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/NotifierCommand.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/NotifierCommand.cpp index 37e5bc6ae41..2081d073dc9 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/NotifierCommand.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/NotifierCommand.cpp @@ -15,7 +15,7 @@ NotifierCommand::NotifierCommand(std::function toRun, NotifierCommand::NotifierCommand(std::function toRun, units::second_t period, - wpi::span requirements) + std::span requirements) : m_toRun(toRun), m_notifier{std::move(toRun)}, m_period{period} { AddRequirements(requirements); } diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/PIDCommand.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/PIDCommand.cpp index d11735aa713..672fa47123a 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/PIDCommand.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/PIDCommand.cpp @@ -24,7 +24,7 @@ PIDCommand::PIDCommand(PIDController controller, std::function measurementSource, std::function setpointSource, std::function useOutput, - wpi::span requirements) + std::span requirements) : m_controller{std::move(controller)}, m_measurement{std::move(measurementSource)}, m_setpoint{std::move(setpointSource)}, @@ -43,7 +43,7 @@ PIDCommand::PIDCommand(PIDController controller, PIDCommand::PIDCommand(PIDController controller, std::function measurementSource, double setpoint, std::function useOutput, - wpi::span requirements) + std::span requirements) : PIDCommand( controller, measurementSource, [setpoint] { return setpoint; }, useOutput, requirements) {} diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/ProxyScheduleCommand.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/ProxyScheduleCommand.cpp index 8935b5ca673..a2cc827f396 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/ProxyScheduleCommand.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/ProxyScheduleCommand.cpp @@ -7,7 +7,7 @@ using namespace frc2; ProxyScheduleCommand::ProxyScheduleCommand( - wpi::span toSchedule) { + std::span toSchedule) { SetInsert(m_toSchedule, toSchedule); } diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/RamseteCommand.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/RamseteCommand.cpp index 179d7f61301..24f3922f581 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/RamseteCommand.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/RamseteCommand.cpp @@ -38,7 +38,7 @@ RamseteCommand::RamseteCommand( std::function wheelSpeeds, frc2::PIDController leftController, frc2::PIDController rightController, std::function output, - wpi::span requirements) + std::span requirements) : m_trajectory(std::move(trajectory)), m_pose(std::move(pose)), m_controller(controller), @@ -74,7 +74,7 @@ RamseteCommand::RamseteCommand( frc::DifferentialDriveKinematics kinematics, std::function output, - wpi::span requirements) + std::span requirements) : m_trajectory(std::move(trajectory)), m_pose(std::move(pose)), m_controller(controller), diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/RunCommand.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/RunCommand.cpp index 067ee372d75..342362febee 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/RunCommand.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/RunCommand.cpp @@ -12,6 +12,6 @@ RunCommand::RunCommand(std::function toRun, [] { return false; }, requirements) {} RunCommand::RunCommand(std::function toRun, - wpi::span requirements) + std::span requirements) : CommandHelper([] {}, std::move(toRun), [](bool interrupted) {}, [] { return false; }, requirements) {} diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/ScheduleCommand.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/ScheduleCommand.cpp index ff50bc5e2d7..54c3042ae10 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/ScheduleCommand.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/ScheduleCommand.cpp @@ -6,7 +6,7 @@ using namespace frc2; -ScheduleCommand::ScheduleCommand(wpi::span toSchedule) { +ScheduleCommand::ScheduleCommand(std::span toSchedule) { SetInsert(m_toSchedule, toSchedule); } diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/StartEndCommand.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/StartEndCommand.cpp index 3a59bf00115..3d91ac5dd6d 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/StartEndCommand.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/StartEndCommand.cpp @@ -16,7 +16,7 @@ StartEndCommand::StartEndCommand(std::function onInit, StartEndCommand::StartEndCommand(std::function onInit, std::function onEnd, - wpi::span requirements) + std::span requirements) : CommandHelper( std::move(onInit), [] {}, [onEnd = std::move(onEnd)](bool interrupted) { onEnd(); }, diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Button.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Button.cpp index a0e617d375f..84d9d213317 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Button.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Button.cpp @@ -25,7 +25,7 @@ Button Button::WhenPressed(std::function toRun, } Button Button::WhenPressed(std::function toRun, - wpi::span requirements) { + std::span requirements) { WhenActive(std::move(toRun), requirements); return *this; } @@ -47,7 +47,7 @@ Button Button::WhileHeld(std::function toRun, } Button Button::WhileHeld(std::function toRun, - wpi::span requirements) { + std::span requirements) { WhileActiveContinous(std::move(toRun), requirements); return *this; } @@ -79,7 +79,7 @@ Button Button::WhenReleased(std::function toRun, } Button Button::WhenReleased(std::function toRun, - wpi::span requirements) { + std::span requirements) { WhenInactive(std::move(toRun), requirements); return *this; } diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Trigger.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Trigger.cpp index bdd152041aa..022bd49ad61 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Trigger.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Trigger.cpp @@ -30,7 +30,7 @@ Trigger Trigger::WhenActive(std::function toRun, } Trigger Trigger::WhenActive(std::function toRun, - wpi::span requirements) { + std::span requirements) { return WhenActive(InstantCommand(std::move(toRun), requirements)); } @@ -55,7 +55,7 @@ Trigger Trigger::WhileActiveContinous( } Trigger Trigger::WhileActiveContinous( - std::function toRun, wpi::span requirements) { + std::function toRun, std::span requirements) { return WhileActiveContinous(InstantCommand(std::move(toRun), requirements)); } @@ -90,7 +90,7 @@ Trigger Trigger::WhenInactive(std::function toRun, } Trigger Trigger::WhenInactive(std::function toRun, - wpi::span requirements) { + std::span requirements) { return WhenInactive(InstantCommand(std::move(toRun), requirements)); } diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/Command.h b/wpilibNewCommands/src/main/native/include/frc2/command/Command.h index cc1d83780d5..c499f6ef077 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/Command.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/Command.h @@ -7,13 +7,13 @@ #include #include #include +#include #include #include #include #include #include -#include #include "frc2/command/Subsystem.h" @@ -171,7 +171,7 @@ class Command { */ [[nodiscard]] CommandPtr BeforeStarting( std::function toRun, - wpi::span requirements = {}) &&; + std::span requirements = {}) &&; /** * Decorates this command with a runnable to run after the command finishes. @@ -193,7 +193,7 @@ class Command { */ [[nodiscard]] CommandPtr AndThen( std::function toRun, - wpi::span requirements = {}) &&; + std::span requirements = {}) &&; /** * Decorates this command to run perpetually, ignoring its ordinary end diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/CommandBase.h b/wpilibNewCommands/src/main/native/include/frc2/command/CommandBase.h index 9050a127e97..54326ff6129 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/CommandBase.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/CommandBase.h @@ -5,13 +5,13 @@ #pragma once #include +#include #include #include #include #include #include -#include #include "frc2/command/Command.h" @@ -37,7 +37,7 @@ class CommandBase : public Command, * * @param requirements the Subsystem requirements to add */ - void AddRequirements(wpi::span requirements); + void AddRequirements(std::span requirements); /** * Adds the specified Subsystem requirements to the command. diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/CommandGroupBase.h b/wpilibNewCommands/src/main/native/include/frc2/command/CommandGroupBase.h index d7ae4473ccb..c1aaaca78b9 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/CommandGroupBase.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/CommandGroupBase.h @@ -6,10 +6,9 @@ #include #include +#include #include -#include - #include "frc2/command/CommandBase.h" namespace frc2 { @@ -49,7 +48,7 @@ class CommandGroupBase : public CommandBase { * @return True if all the commands are ungrouped. */ static bool RequireUngrouped( - wpi::span> commands); + std::span> commands); /** * Requires that the specified commands not have been already allocated to a diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/CommandPtr.h b/wpilibNewCommands/src/main/native/include/frc2/command/CommandPtr.h index fbe48551240..dbdbfb6492a 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/CommandPtr.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/CommandPtr.h @@ -7,6 +7,7 @@ #include #include #include +#include #include #include @@ -89,7 +90,7 @@ class CommandPtr final { */ [[nodiscard]] CommandPtr AndThen( std::function toRun, - wpi::span requirements = {}) &&; + std::span requirements = {}) &&; /** * Decorates this command with a runnable to run after the command finishes. @@ -132,7 +133,7 @@ class CommandPtr final { */ [[nodiscard]] CommandPtr BeforeStarting( std::function toRun, - wpi::span requirements = {}) &&; + std::span requirements = {}) &&; /** * Decorates this command with another command to run before this command diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/CommandScheduler.h b/wpilibNewCommands/src/main/native/include/frc2/command/CommandScheduler.h index 067734a96f0..12e573a7533 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/CommandScheduler.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/CommandScheduler.h @@ -6,6 +6,7 @@ #include #include +#include #include #include @@ -16,7 +17,6 @@ #include #include #include -#include namespace frc2 { class Command; @@ -111,7 +111,7 @@ class CommandScheduler final : public nt::NTSendable, * * @param commands the commands to schedule */ - void Schedule(wpi::span commands); + void Schedule(std::span commands); /** * Schedules multiple commands for execution. Does nothing for commands @@ -159,10 +159,10 @@ class CommandScheduler final : public nt::NTSendable, void UnregisterSubsystem(Subsystem* subsystem); void RegisterSubsystem(std::initializer_list subsystems); - void RegisterSubsystem(wpi::span subsystems); + void RegisterSubsystem(std::span subsystems); void UnregisterSubsystem(std::initializer_list subsystems); - void UnregisterSubsystem(wpi::span subsystems); + void UnregisterSubsystem(std::span subsystems); /** * Sets the default command for a subsystem. Registers that subsystem if it @@ -234,7 +234,7 @@ class CommandScheduler final : public nt::NTSendable, * * @param commands the commands to cancel */ - void Cancel(wpi::span commands); + void Cancel(std::span commands); /** * Cancels commands. The scheduler will only call Command::End() @@ -261,7 +261,7 @@ class CommandScheduler final : public nt::NTSendable, * @param commands the command to query * @return whether the command is currently scheduled */ - bool IsScheduled(wpi::span commands) const; + bool IsScheduled(std::span commands) const; /** * Whether the given commands are running. Note that this only works on diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/FunctionalCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/FunctionalCommand.h index a4891a4f10d..ef2b5b93ab9 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/FunctionalCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/FunctionalCommand.h @@ -6,8 +6,7 @@ #include #include - -#include +#include #include "frc2/command/CommandBase.h" #include "frc2/command/CommandHelper.h" @@ -54,7 +53,7 @@ class FunctionalCommand : public CommandHelper { std::function onExecute, std::function onEnd, std::function isFinished, - wpi::span requirements = {}); + std::span requirements = {}); FunctionalCommand(FunctionalCommand&& other) = default; diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/InstantCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/InstantCommand.h index 2abc9ceed8f..cae0b3e0e77 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/InstantCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/InstantCommand.h @@ -6,8 +6,7 @@ #include #include - -#include +#include #include "frc2/command/CommandHelper.h" #include "frc2/command/FunctionalCommand.h" @@ -40,7 +39,7 @@ class InstantCommand : public CommandHelper { * @param requirements the subsystems required by this command */ explicit InstantCommand(std::function toRun, - wpi::span requirements = {}); + std::span requirements = {}); InstantCommand(InstantCommand&& other) = default; diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/MecanumControllerCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/MecanumControllerCommand.h index 92c569d7685..4f5debd25b6 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/MecanumControllerCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/MecanumControllerCommand.h @@ -6,6 +6,7 @@ #include #include #include +#include #include #include @@ -21,7 +22,6 @@ #include #include #include -#include #include "CommandBase.h" #include "CommandHelper.h" @@ -206,7 +206,7 @@ class MecanumControllerCommand std::function output, - wpi::span requirements = {}); + std::span requirements = {}); /** * Constructs a new MecanumControllerCommand that when executed will follow @@ -259,7 +259,7 @@ class MecanumControllerCommand std::function output, - wpi::span requirements = {}); + std::span requirements = {}); /** * Constructs a new MecanumControllerCommand that when executed will follow @@ -375,7 +375,7 @@ class MecanumControllerCommand units::meters_per_second_t, units::meters_per_second_t)> output, - wpi::span requirements = {}); + std::span requirements = {}); /** * Constructs a new MecanumControllerCommand that when executed will follow @@ -415,7 +415,7 @@ class MecanumControllerCommand units::meters_per_second_t, units::meters_per_second_t)> output, - wpi::span requirements = {}); + std::span requirements = {}); void Initialize() override; diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/NotifierCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/NotifierCommand.h index d2be98544c1..607799bebe6 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/NotifierCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/NotifierCommand.h @@ -6,10 +6,10 @@ #include #include +#include #include #include -#include #include "frc2/command/CommandBase.h" #include "frc2/command/CommandHelper.h" @@ -47,7 +47,7 @@ class NotifierCommand : public CommandHelper { * @param requirements the subsystems required by this command */ NotifierCommand(std::function toRun, units::second_t period, - wpi::span requirements = {}); + std::span requirements = {}); NotifierCommand(NotifierCommand&& other); diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/PIDCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/PIDCommand.h index a63d55c2b65..818c50b05e0 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/PIDCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/PIDCommand.h @@ -6,9 +6,9 @@ #include #include +#include #include -#include #include "frc2/command/CommandBase.h" #include "frc2/command/CommandHelper.h" @@ -56,7 +56,7 @@ class PIDCommand : public CommandHelper { std::function measurementSource, std::function setpointSource, std::function useOutput, - wpi::span requirements = {}); + std::span requirements = {}); /** * Creates a new PIDCommand, which controls the given output with a @@ -86,7 +86,7 @@ class PIDCommand : public CommandHelper { PIDCommand(PIDController controller, std::function measurementSource, double setpoint, std::function useOutput, - wpi::span requirements = {}); + std::span requirements = {}); PIDCommand(PIDCommand&& other) = default; diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDCommand.h index d106ad348da..3fbe726cbd6 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDCommand.h @@ -6,11 +6,11 @@ #include #include +#include #include #include #include -#include #include "frc2/command/CommandBase.h" #include "frc2/command/CommandHelper.h" @@ -72,7 +72,7 @@ class ProfiledPIDCommand std::function measurementSource, std::function goalSource, std::function useOutput, - wpi::span requirements = {}) + std::span requirements = {}) : m_controller{controller}, m_measurement{std::move(measurementSource)}, m_goal{std::move(goalSource)}, @@ -116,7 +116,7 @@ class ProfiledPIDCommand std::function measurementSource, std::function goalSource, std::function useOutput, - wpi::span requirements = {}) + std::span requirements = {}) : ProfiledPIDCommand( controller, measurementSource, [goalSource = std::move(goalSource)]() { @@ -155,7 +155,7 @@ class ProfiledPIDCommand ProfiledPIDCommand(frc::ProfiledPIDController controller, std::function measurementSource, State goal, std::function useOutput, - wpi::span requirements = {}) + std::span requirements = {}) : ProfiledPIDCommand( controller, measurementSource, [goal] { return goal; }, useOutput, requirements) {} @@ -193,7 +193,7 @@ class ProfiledPIDCommand std::function measurementSource, Distance_t goal, std::function useOutput, - wpi::span requirements = {}) + std::span requirements = {}) : ProfiledPIDCommand( controller, measurementSource, [goal] { return goal; }, useOutput, requirements) {} diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/ProxyScheduleCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/ProxyScheduleCommand.h index 543e37eb2ce..e20d329389f 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/ProxyScheduleCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/ProxyScheduleCommand.h @@ -5,9 +5,9 @@ #pragma once #include +#include #include -#include #include "frc2/command/CommandBase.h" #include "frc2/command/CommandHelper.h" @@ -31,7 +31,7 @@ class ProxyScheduleCommand * * @param toSchedule the commands to schedule */ - explicit ProxyScheduleCommand(wpi::span toSchedule); + explicit ProxyScheduleCommand(std::span toSchedule); explicit ProxyScheduleCommand(Command* toSchedule); diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/RamseteCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/RamseteCommand.h index 73c55272156..c80589ccb89 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/RamseteCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/RamseteCommand.h @@ -7,6 +7,7 @@ #include #include #include +#include #include #include @@ -17,7 +18,6 @@ #include #include #include -#include #include "frc2/command/CommandBase.h" #include "frc2/command/CommandHelper.h" @@ -116,7 +116,7 @@ class RamseteCommand : public CommandHelper { frc2::PIDController leftController, frc2::PIDController rightController, std::function output, - wpi::span requirements = {}); + std::span requirements = {}); /** * Constructs a new RamseteCommand that, when executed, will follow the @@ -164,7 +164,7 @@ class RamseteCommand : public CommandHelper { std::function output, - wpi::span requirements = {}); + std::span requirements = {}); void Initialize() override; diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/RunCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/RunCommand.h index 596bc48af60..3bfecf7ffb6 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/RunCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/RunCommand.h @@ -6,8 +6,7 @@ #include #include - -#include +#include #include "frc2/command/CommandHelper.h" #include "frc2/command/FunctionalCommand.h" @@ -41,7 +40,7 @@ class RunCommand : public CommandHelper { * @param requirements the subsystems to require */ explicit RunCommand(std::function toRun, - wpi::span requirements = {}); + std::span requirements = {}); RunCommand(RunCommand&& other) = default; diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/ScheduleCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/ScheduleCommand.h index b099fb3b201..4e71f31b540 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/ScheduleCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/ScheduleCommand.h @@ -4,8 +4,9 @@ #pragma once +#include + #include -#include #include "frc2/command/CommandBase.h" #include "frc2/command/CommandHelper.h" @@ -28,7 +29,7 @@ class ScheduleCommand : public CommandHelper { * * @param toSchedule the commands to schedule */ - explicit ScheduleCommand(wpi::span toSchedule); + explicit ScheduleCommand(std::span toSchedule); explicit ScheduleCommand(Command* toSchedule); diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/SequentialCommandGroup.h b/wpilibNewCommands/src/main/native/include/frc2/command/SequentialCommandGroup.h index 741eba416b2..bdcf2efa080 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/SequentialCommandGroup.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/SequentialCommandGroup.h @@ -11,6 +11,7 @@ #include #include +#include #include #include #include diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/SetUtilities.h b/wpilibNewCommands/src/main/native/include/frc2/command/SetUtilities.h index d40fbecaa61..e70e17b9d57 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/SetUtilities.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/SetUtilities.h @@ -4,12 +4,13 @@ #pragma once +#include + #include -#include namespace frc2 { template -void SetInsert(wpi::SmallVectorImpl& vector, wpi::span toAdd) { +void SetInsert(wpi::SmallVectorImpl& vector, std::span toAdd) { for (auto addCommand : toAdd) { bool exists = false; for (auto existingCommand : vector) { diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/StartEndCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/StartEndCommand.h index 4831faaefa6..b1f56b2061b 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/StartEndCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/StartEndCommand.h @@ -6,8 +6,7 @@ #include #include - -#include +#include #include "frc2/command/CommandHelper.h" #include "frc2/command/FunctionalCommand.h" @@ -45,7 +44,7 @@ class StartEndCommand * @param requirements the subsystems required by this command */ StartEndCommand(std::function onInit, std::function onEnd, - wpi::span requirements = {}); + std::span requirements = {}); StartEndCommand(StartEndCommand&& other) = default; diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.h index 212beb5d801..fefb793e651 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.h @@ -6,6 +6,7 @@ #include #include #include +#include #include #include @@ -19,7 +20,6 @@ #include #include #include -#include #include "CommandBase.h" #include "CommandHelper.h" @@ -169,7 +169,7 @@ class SwerveControllerCommand std::function desiredRotation, std::function)> output, - wpi::span requirements = {}); + std::span requirements = {}); /** * Constructs a new SwerveControllerCommand that when executed will follow the @@ -207,7 +207,7 @@ class SwerveControllerCommand frc::ProfiledPIDController thetaController, std::function)> output, - wpi::span requirements = {}); + std::span requirements = {}); void Initialize() override; diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.inc b/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.inc index aef7e097322..4b6e76c4679 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.inc +++ b/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.inc @@ -53,7 +53,7 @@ SwerveControllerCommand::SwerveControllerCommand( frc::ProfiledPIDController thetaController, std::function desiredRotation, std::function)> output, - wpi::span requirements) + std::span requirements) : m_trajectory(std::move(trajectory)), m_pose(std::move(pose)), m_kinematics(kinematics), @@ -70,7 +70,7 @@ SwerveControllerCommand::SwerveControllerCommand( frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController thetaController, std::function)> output, - wpi::span requirements) + std::span requirements) : m_trajectory(std::move(trajectory)), m_pose(std::move(pose)), m_kinematics(kinematics), diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileCommand.h index 3a609be52b2..413553bdb38 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileCommand.h @@ -6,10 +6,10 @@ #include #include +#include #include #include -#include #include "frc2/command/CommandBase.h" #include "frc2/command/CommandHelper.h" @@ -58,7 +58,7 @@ class TrapezoidProfileCommand */ TrapezoidProfileCommand(frc::TrapezoidProfile profile, std::function output, - wpi::span requirements = {}) + std::span requirements = {}) : m_profile(profile), m_output(output) { this->AddRequirements(requirements); } diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/button/Button.h b/wpilibNewCommands/src/main/native/include/frc2/command/button/Button.h index 44c6d959c23..5a1956eb8ff 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/button/Button.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/button/Button.h @@ -6,10 +6,9 @@ #include #include +#include #include -#include - #include "Trigger.h" #include "frc2/command/CommandPtr.h" @@ -90,7 +89,7 @@ class Button : public Trigger { * @param requirements the required subsystems. */ Button WhenPressed(std::function toRun, - wpi::span requirements = {}); + std::span requirements = {}); /** * Binds a command to be started repeatedly while the button is pressed, and @@ -144,7 +143,7 @@ class Button : public Trigger { * @param requirements the required subsystems. */ Button WhileHeld(std::function toRun, - wpi::span requirements = {}); + std::span requirements = {}); /** * Binds a command to be started when the button is pressed, and canceled @@ -234,7 +233,7 @@ class Button : public Trigger { * @param requirements the required subsystems. */ Button WhenReleased(std::function toRun, - wpi::span requirements = {}); + std::span requirements = {}); /** * Binds a command to start when the button is pressed, and be canceled when diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/button/Trigger.h b/wpilibNewCommands/src/main/native/include/frc2/command/button/Trigger.h index c098ad47c51..77364613994 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/button/Trigger.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/button/Trigger.h @@ -7,13 +7,13 @@ #include #include #include +#include #include #include #include #include #include -#include #include "frc2/command/Command.h" #include "frc2/command/CommandScheduler.h" @@ -113,7 +113,7 @@ class Trigger : public frc::BooleanEvent { * @param requirements the required subsystems. */ Trigger WhenActive(std::function toRun, - wpi::span requirements = {}); + std::span requirements = {}); /** * Binds a command to be started repeatedly while the trigger is active, and @@ -171,7 +171,7 @@ class Trigger : public frc::BooleanEvent { * @param requirements the required subsystems. */ Trigger WhileActiveContinous(std::function toRun, - wpi::span requirements = {}); + std::span requirements = {}); /** * Binds a command to be started when the trigger becomes active, and @@ -268,7 +268,7 @@ class Trigger : public frc::BooleanEvent { * @param requirements the required subsystems. */ Trigger WhenInactive(std::function toRun, - wpi::span requirements = {}); + std::span requirements = {}); /** * Binds a command to start when the trigger becomes active, and be canceled diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/MecanumControllerCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/MecanumControllerCommandTest.cpp index ceeafd8e65a..cb2810c63df 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/MecanumControllerCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/MecanumControllerCommandTest.cpp @@ -5,6 +5,8 @@ #include #include +#include + #include #include #include @@ -14,7 +16,6 @@ #include #include #include -#include #include "gtest/gtest.h" diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/SwerveControllerCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/SwerveControllerCommandTest.cpp index 93117b8c82c..6891d501714 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/SwerveControllerCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/SwerveControllerCommandTest.cpp @@ -5,6 +5,8 @@ #include #include +#include + #include #include #include @@ -15,7 +17,6 @@ #include #include #include -#include #include "gtest/gtest.h" diff --git a/wpilibc/src/main/native/cpp/ADIS16448_IMU.cpp b/wpilibc/src/main/native/cpp/ADIS16448_IMU.cpp index 53f4b31bedb..9c09c5faadd 100644 --- a/wpilibc/src/main/native/cpp/ADIS16448_IMU.cpp +++ b/wpilibc/src/main/native/cpp/ADIS16448_IMU.cpp @@ -22,11 +22,11 @@ #include #include +#include #include #include #include -#include #include #include "frc/Errors.h" @@ -630,29 +630,29 @@ void ADIS16448_IMU::Acquire() { /* Complementary filter functions */ double ADIS16448_IMU::FormatFastConverge(double compAngle, double accAngle) { - if (compAngle > accAngle + wpi::numbers::pi) { - compAngle = compAngle - 2.0 * wpi::numbers::pi; - } else if (accAngle > compAngle + wpi::numbers::pi) { - compAngle = compAngle + 2.0 * wpi::numbers::pi; + if (compAngle > accAngle + std::numbers::pi) { + compAngle = compAngle - 2.0 * std::numbers::pi; + } else if (accAngle > compAngle + std::numbers::pi) { + compAngle = compAngle + 2.0 * std::numbers::pi; } return compAngle; } double ADIS16448_IMU::FormatRange0to2PI(double compAngle) { - while (compAngle >= 2 * wpi::numbers::pi) { - compAngle = compAngle - 2.0 * wpi::numbers::pi; + while (compAngle >= 2 * std::numbers::pi) { + compAngle = compAngle - 2.0 * std::numbers::pi; } while (compAngle < 0.0) { - compAngle = compAngle + 2.0 * wpi::numbers::pi; + compAngle = compAngle + 2.0 * std::numbers::pi; } return compAngle; } double ADIS16448_IMU::FormatAccelRange(double accelAngle, double accelZ) { if (accelZ < 0.0) { - accelAngle = wpi::numbers::pi - accelAngle; + accelAngle = std::numbers::pi - accelAngle; } else if (accelZ > 0.0 && accelAngle < 0.0) { - accelAngle = 2.0 * wpi::numbers::pi + accelAngle; + accelAngle = 2.0 * std::numbers::pi + accelAngle; } return accelAngle; } @@ -663,8 +663,8 @@ double ADIS16448_IMU::CompFilterProcess(double compAngle, double accelAngle, compAngle = m_alpha * (compAngle + omega * m_dt) + (1.0 - m_alpha) * accelAngle; compAngle = FormatRange0to2PI(compAngle); - if (compAngle > wpi::numbers::pi) { - compAngle = compAngle - 2.0 * wpi::numbers::pi; + if (compAngle > std::numbers::pi) { + compAngle = compAngle - 2.0 * std::numbers::pi; } return compAngle; } @@ -874,5 +874,5 @@ int ADIS16448_IMU::GetPort() const { void ADIS16448_IMU::InitSendable(nt::NTSendableBuilder& builder) { builder.SetSmartDashboardType("ADIS16448 IMU"); builder.AddDoubleProperty( - "Yaw Angle", [=] { return GetAngle().value(); }, nullptr); + "Yaw Angle", [=, this] { return GetAngle().value(); }, nullptr); } diff --git a/wpilibc/src/main/native/cpp/ADIS16470_IMU.cpp b/wpilibc/src/main/native/cpp/ADIS16470_IMU.cpp index 6661045f722..8cf7ea6b7bd 100644 --- a/wpilibc/src/main/native/cpp/ADIS16470_IMU.cpp +++ b/wpilibc/src/main/native/cpp/ADIS16470_IMU.cpp @@ -19,11 +19,11 @@ #include #include +#include #include #include #include -#include #include #include "frc/Errors.h" @@ -647,29 +647,29 @@ void ADIS16470_IMU::Acquire() { /* Complementary filter functions */ double ADIS16470_IMU::FormatFastConverge(double compAngle, double accAngle) { - if (compAngle > accAngle + wpi::numbers::pi) { - compAngle = compAngle - 2.0 * wpi::numbers::pi; - } else if (accAngle > compAngle + wpi::numbers::pi) { - compAngle = compAngle + 2.0 * wpi::numbers::pi; + if (compAngle > accAngle + std::numbers::pi) { + compAngle = compAngle - 2.0 * std::numbers::pi; + } else if (accAngle > compAngle + std::numbers::pi) { + compAngle = compAngle + 2.0 * std::numbers::pi; } return compAngle; } double ADIS16470_IMU::FormatRange0to2PI(double compAngle) { - while (compAngle >= 2 * wpi::numbers::pi) { - compAngle = compAngle - 2.0 * wpi::numbers::pi; + while (compAngle >= 2 * std::numbers::pi) { + compAngle = compAngle - 2.0 * std::numbers::pi; } while (compAngle < 0.0) { - compAngle = compAngle + 2.0 * wpi::numbers::pi; + compAngle = compAngle + 2.0 * std::numbers::pi; } return compAngle; } double ADIS16470_IMU::FormatAccelRange(double accelAngle, double accelZ) { if (accelZ < 0.0) { - accelAngle = wpi::numbers::pi - accelAngle; + accelAngle = std::numbers::pi - accelAngle; } else if (accelZ > 0.0 && accelAngle < 0.0) { - accelAngle = 2.0 * wpi::numbers::pi + accelAngle; + accelAngle = 2.0 * std::numbers::pi + accelAngle; } return accelAngle; } @@ -680,8 +680,8 @@ double ADIS16470_IMU::CompFilterProcess(double compAngle, double accelAngle, compAngle = m_alpha * (compAngle + omega * m_dt) + (1.0 - m_alpha) * accelAngle; compAngle = FormatRange0to2PI(compAngle); - if (compAngle > wpi::numbers::pi) { - compAngle = compAngle - 2.0 * wpi::numbers::pi; + if (compAngle > std::numbers::pi) { + compAngle = compAngle - 2.0 * std::numbers::pi; } return compAngle; } @@ -809,5 +809,5 @@ int ADIS16470_IMU::GetPort() const { void ADIS16470_IMU::InitSendable(nt::NTSendableBuilder& builder) { builder.SetSmartDashboardType("ADIS16470 IMU"); builder.AddDoubleProperty( - "Yaw Angle", [=] { return GetAngle().value(); }, nullptr); + "Yaw Angle", [=, this] { return GetAngle().value(); }, nullptr); } diff --git a/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp b/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp index 542d1ae314f..57e78e963eb 100644 --- a/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp +++ b/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp @@ -137,5 +137,5 @@ int ADXRS450_Gyro::GetPort() const { void ADXRS450_Gyro::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("Gyro"); builder.AddDoubleProperty( - "Value", [=] { return GetAngle(); }, nullptr); + "Value", [=, this] { return GetAngle(); }, nullptr); } diff --git a/wpilibc/src/main/native/cpp/AddressableLED.cpp b/wpilibc/src/main/native/cpp/AddressableLED.cpp index 759c3864d56..538dc102b63 100644 --- a/wpilibc/src/main/native/cpp/AddressableLED.cpp +++ b/wpilibc/src/main/native/cpp/AddressableLED.cpp @@ -51,9 +51,9 @@ void AddressableLED::SetLength(int length) { static_assert(sizeof(AddressableLED::LEDData) == sizeof(HAL_AddressableLEDData), "LED Structs MUST be the same size"); -void AddressableLED::SetData(wpi::span ledData) { +void AddressableLED::SetData(std::span ledData) { int32_t status = 0; - HAL_WriteAddressableLEDData(m_handle, ledData.begin(), ledData.size(), + HAL_WriteAddressableLEDData(m_handle, ledData.data(), ledData.size(), &status); FRC_CheckErrorStatus(status, "Port {}", m_port); } diff --git a/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp b/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp index 0b39e6409d5..6789436802e 100644 --- a/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp +++ b/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp @@ -49,7 +49,7 @@ void AnalogAccelerometer::SetZero(double zero) { void AnalogAccelerometer::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("Accelerometer"); builder.AddDoubleProperty( - "Value", [=] { return GetAcceleration(); }, nullptr); + "Value", [=, this] { return GetAcceleration(); }, nullptr); } void AnalogAccelerometer::InitAccelerometer() { diff --git a/wpilibc/src/main/native/cpp/AnalogGyro.cpp b/wpilibc/src/main/native/cpp/AnalogGyro.cpp index 106293be2ee..fdc0183ef30 100644 --- a/wpilibc/src/main/native/cpp/AnalogGyro.cpp +++ b/wpilibc/src/main/native/cpp/AnalogGyro.cpp @@ -140,5 +140,5 @@ std::shared_ptr AnalogGyro::GetAnalogInput() const { void AnalogGyro::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("Gyro"); builder.AddDoubleProperty( - "Value", [=] { return GetAngle(); }, nullptr); + "Value", [=, this] { return GetAngle(); }, nullptr); } diff --git a/wpilibc/src/main/native/cpp/AnalogInput.cpp b/wpilibc/src/main/native/cpp/AnalogInput.cpp index dfa5764fff7..4c4d212b7ff 100644 --- a/wpilibc/src/main/native/cpp/AnalogInput.cpp +++ b/wpilibc/src/main/native/cpp/AnalogInput.cpp @@ -197,5 +197,5 @@ void AnalogInput::SetSimDevice(HAL_SimDeviceHandle device) { void AnalogInput::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("Analog Input"); builder.AddDoubleProperty( - "Value", [=] { return GetAverageVoltage(); }, nullptr); + "Value", [=, this] { return GetAverageVoltage(); }, nullptr); } diff --git a/wpilibc/src/main/native/cpp/AnalogOutput.cpp b/wpilibc/src/main/native/cpp/AnalogOutput.cpp index a39127135b6..90f538bf79b 100644 --- a/wpilibc/src/main/native/cpp/AnalogOutput.cpp +++ b/wpilibc/src/main/native/cpp/AnalogOutput.cpp @@ -61,6 +61,6 @@ int AnalogOutput::GetChannel() const { void AnalogOutput::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("Analog Output"); builder.AddDoubleProperty( - "Value", [=] { return GetVoltage(); }, - [=](double value) { SetVoltage(value); }); + "Value", [=, this] { return GetVoltage(); }, + [=, this](double value) { SetVoltage(value); }); } diff --git a/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp b/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp index ba94613b11e..d43c84fe752 100644 --- a/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp +++ b/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp @@ -46,5 +46,5 @@ double AnalogPotentiometer::Get() const { void AnalogPotentiometer::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("Analog Input"); builder.AddDoubleProperty( - "Value", [=] { return Get(); }, nullptr); + "Value", [=, this] { return Get(); }, nullptr); } diff --git a/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp b/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp index 1b8da851d44..88f37725a0a 100644 --- a/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp +++ b/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp @@ -47,9 +47,9 @@ double BuiltInAccelerometer::GetZ() { void BuiltInAccelerometer::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("3AxisAccelerometer"); builder.AddDoubleProperty( - "X", [=] { return GetX(); }, nullptr); + "X", [=, this] { return GetX(); }, nullptr); builder.AddDoubleProperty( - "Y", [=] { return GetY(); }, nullptr); + "Y", [=, this] { return GetY(); }, nullptr); builder.AddDoubleProperty( - "Z", [=] { return GetZ(); }, nullptr); + "Z", [=, this] { return GetZ(); }, nullptr); } diff --git a/wpilibc/src/main/native/cpp/Compressor.cpp b/wpilibc/src/main/native/cpp/Compressor.cpp index 2fa2cee1ad7..2479ffc1e39 100644 --- a/wpilibc/src/main/native/cpp/Compressor.cpp +++ b/wpilibc/src/main/native/cpp/Compressor.cpp @@ -83,7 +83,7 @@ CompressorConfigType Compressor::GetConfigType() const { void Compressor::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("Compressor"); builder.AddBooleanProperty( - "Enabled", [=] { return IsEnabled(); }, nullptr); + "Enabled", [this] { return IsEnabled(); }, nullptr); builder.AddBooleanProperty( - "Pressure switch", [=]() { return GetPressureSwitchValue(); }, nullptr); + "Pressure switch", [this] { return GetPressureSwitchValue(); }, nullptr); } diff --git a/wpilibc/src/main/native/cpp/Counter.cpp b/wpilibc/src/main/native/cpp/Counter.cpp index a1ad9e7a388..ca7d0ad7f52 100644 --- a/wpilibc/src/main/native/cpp/Counter.cpp +++ b/wpilibc/src/main/native/cpp/Counter.cpp @@ -309,5 +309,5 @@ bool Counter::GetDirection() const { void Counter::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("Counter"); builder.AddDoubleProperty( - "Value", [=] { return Get(); }, nullptr); + "Value", [=, this] { return Get(); }, nullptr); } diff --git a/wpilibc/src/main/native/cpp/DigitalInput.cpp b/wpilibc/src/main/native/cpp/DigitalInput.cpp index 86f1c3a2590..02757415de3 100644 --- a/wpilibc/src/main/native/cpp/DigitalInput.cpp +++ b/wpilibc/src/main/native/cpp/DigitalInput.cpp @@ -69,5 +69,5 @@ int DigitalInput::GetChannel() const { void DigitalInput::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("Digital Input"); builder.AddBooleanProperty( - "Value", [=] { return Get(); }, nullptr); + "Value", [=, this] { return Get(); }, nullptr); } diff --git a/wpilibc/src/main/native/cpp/DigitalOutput.cpp b/wpilibc/src/main/native/cpp/DigitalOutput.cpp index 3890782a7de..aa86a54f845 100644 --- a/wpilibc/src/main/native/cpp/DigitalOutput.cpp +++ b/wpilibc/src/main/native/cpp/DigitalOutput.cpp @@ -143,5 +143,6 @@ void DigitalOutput::SetSimDevice(HAL_SimDeviceHandle device) { void DigitalOutput::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("Digital Output"); builder.AddBooleanProperty( - "Value", [=] { return Get(); }, [=](bool value) { Set(value); }); + "Value", [=, this] { return Get(); }, + [=, this](bool value) { Set(value); }); } diff --git a/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp b/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp index 566c9f2418f..c111622545c 100644 --- a/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp +++ b/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp @@ -129,10 +129,10 @@ bool DoubleSolenoid::IsRevSolenoidDisabled() const { void DoubleSolenoid::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("Double Solenoid"); builder.SetActuator(true); - builder.SetSafeState([=] { Set(kOff); }); + builder.SetSafeState([=, this] { Set(kOff); }); builder.AddSmallStringProperty( "Value", - [=](wpi::SmallVectorImpl& buf) -> std::string_view { + [=, this](wpi::SmallVectorImpl& buf) -> std::string_view { switch (Get()) { case kForward: return "Forward"; @@ -142,7 +142,7 @@ void DoubleSolenoid::InitSendable(wpi::SendableBuilder& builder) { return "Off"; } }, - [=](std::string_view value) { + [=, this](std::string_view value) { Value lvalue = kOff; if (value == "Forward") { lvalue = kForward; diff --git a/wpilibc/src/main/native/cpp/DriverStation.cpp b/wpilibc/src/main/native/cpp/DriverStation.cpp index b7c0800f7be..817252d6597 100644 --- a/wpilibc/src/main/native/cpp/DriverStation.cpp +++ b/wpilibc/src/main/native/cpp/DriverStation.cpp @@ -9,6 +9,7 @@ #include #include #include +#include #include #include #include @@ -846,7 +847,7 @@ void JoystickLogSender::Init(wpi::log::DataLog& log, unsigned int stick, HAL_GetJoystickPOVs(m_stick, &m_prevPOVs); AppendButtons(m_prevButtons, timestamp); m_logAxes.Append( - wpi::span{m_prevAxes.axes, + std::span{m_prevAxes.axes, static_cast(m_prevAxes.count)}, timestamp); AppendPOVs(m_prevPOVs, timestamp); @@ -867,7 +868,7 @@ void JoystickLogSender::Send(uint64_t timestamp) { std::memcmp(axes.axes, m_prevAxes.axes, sizeof(axes.axes[0]) * axes.count) != 0) { m_logAxes.Append( - wpi::span{axes.axes, static_cast(axes.count)}, + std::span{axes.axes, static_cast(axes.count)}, timestamp); } m_prevAxes = axes; @@ -888,7 +889,7 @@ void JoystickLogSender::AppendButtons(HAL_JoystickButtons buttons, for (unsigned int i = 0; i < buttons.count; ++i) { buttonsArr[i] = (buttons.buttons & (1u << i)) != 0; } - m_logButtons.Append(wpi::span{buttonsArr, buttons.count}, + m_logButtons.Append(std::span{buttonsArr, buttons.count}, timestamp); } @@ -899,7 +900,7 @@ void JoystickLogSender::AppendPOVs(const HAL_JoystickPOVs& povs, povsArr[i] = povs.povs[i]; } m_logPOVs.Append( - wpi::span{povsArr, static_cast(povs.count)}, + std::span{povsArr, static_cast(povs.count)}, timestamp); } diff --git a/wpilibc/src/main/native/cpp/Encoder.cpp b/wpilibc/src/main/native/cpp/Encoder.cpp index bef6d76aeab..47700957781 100644 --- a/wpilibc/src/main/native/cpp/Encoder.cpp +++ b/wpilibc/src/main/native/cpp/Encoder.cpp @@ -217,11 +217,12 @@ void Encoder::InitSendable(wpi::SendableBuilder& builder) { } builder.AddDoubleProperty( - "Speed", [=] { return GetRate(); }, nullptr); + "Speed", [=, this] { return GetRate(); }, nullptr); builder.AddDoubleProperty( - "Distance", [=] { return GetDistance(); }, nullptr); + "Distance", [=, this] { return GetDistance(); }, nullptr); builder.AddDoubleProperty( - "Distance per Tick", [=] { return GetDistancePerPulse(); }, nullptr); + "Distance per Tick", [=, this] { return GetDistancePerPulse(); }, + nullptr); } void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType) { diff --git a/wpilibc/src/main/native/cpp/Joystick.cpp b/wpilibc/src/main/native/cpp/Joystick.cpp index 826e2d66be0..4a7b91f8074 100644 --- a/wpilibc/src/main/native/cpp/Joystick.cpp +++ b/wpilibc/src/main/native/cpp/Joystick.cpp @@ -5,9 +5,9 @@ #include "frc/Joystick.h" #include +#include #include -#include #include "frc/event/BooleanEvent.h" @@ -124,5 +124,5 @@ double Joystick::GetDirectionRadians() const { } double Joystick::GetDirectionDegrees() const { - return (180 / wpi::numbers::pi) * GetDirectionRadians(); + return (180 / std::numbers::pi) * GetDirectionRadians(); } diff --git a/wpilibc/src/main/native/cpp/Notifier.cpp b/wpilibc/src/main/native/cpp/Notifier.cpp index 441f7507c8d..20679a7af00 100644 --- a/wpilibc/src/main/native/cpp/Notifier.cpp +++ b/wpilibc/src/main/native/cpp/Notifier.cpp @@ -25,7 +25,7 @@ Notifier::Notifier(std::function handler) { m_notifier = HAL_InitializeNotifier(&status); FRC_CheckErrorStatus(status, "{}", "InitializeNotifier"); - m_thread = std::thread([=] { + m_thread = std::thread([=, this] { for (;;) { int32_t status = 0; HAL_NotifierHandle notifier = m_notifier.load(); @@ -67,7 +67,7 @@ Notifier::Notifier(int priority, std::function handler) { m_notifier = HAL_InitializeNotifier(&status); FRC_CheckErrorStatus(status, "{}", "InitializeNotifier"); - m_thread = std::thread([=] { + m_thread = std::thread([=, this] { int32_t status = 0; HAL_SetCurrentThreadPriority(true, priority, &status); for (;;) { diff --git a/wpilibc/src/main/native/cpp/PWM.cpp b/wpilibc/src/main/native/cpp/PWM.cpp index 7df9955370b..5c5e6f57d88 100644 --- a/wpilibc/src/main/native/cpp/PWM.cpp +++ b/wpilibc/src/main/native/cpp/PWM.cpp @@ -166,7 +166,8 @@ int PWM::GetChannel() const { void PWM::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("PWM"); builder.SetActuator(true); - builder.SetSafeState([=] { SetDisabled(); }); + builder.SetSafeState([=, this] { SetDisabled(); }); builder.AddDoubleProperty( - "Value", [=] { return GetRaw(); }, [=](double value) { SetRaw(value); }); + "Value", [=, this] { return GetRaw(); }, + [=, this](double value) { SetRaw(value); }); } diff --git a/wpilibc/src/main/native/cpp/PowerDistribution.cpp b/wpilibc/src/main/native/cpp/PowerDistribution.cpp index 21101f2a207..ba4cb383c30 100644 --- a/wpilibc/src/main/native/cpp/PowerDistribution.cpp +++ b/wpilibc/src/main/native/cpp/PowerDistribution.cpp @@ -195,7 +195,7 @@ void PowerDistribution::InitSendable(wpi::SendableBuilder& builder) { for (int i = 0; i < numChannels; ++i) { builder.AddDoubleProperty( fmt::format("Chan{}", i), - [=] { + [=, this] { int32_t lStatus = 0; return HAL_GetPowerDistributionChannelCurrent(m_handle, i, &lStatus); }, @@ -203,25 +203,25 @@ void PowerDistribution::InitSendable(wpi::SendableBuilder& builder) { } builder.AddDoubleProperty( "Voltage", - [=] { + [=, this] { int32_t lStatus = 0; return HAL_GetPowerDistributionVoltage(m_handle, &lStatus); }, nullptr); builder.AddDoubleProperty( "TotalCurrent", - [=] { + [=, this] { int32_t lStatus = 0; return HAL_GetPowerDistributionTotalCurrent(m_handle, &lStatus); }, nullptr); builder.AddBooleanProperty( "SwitchableChannel", - [=] { + [=, this] { int32_t lStatus = 0; return HAL_GetPowerDistributionSwitchableChannel(m_handle, &lStatus); }, - [=](bool value) { + [=, this](bool value) { int32_t lStatus = 0; HAL_SetPowerDistributionSwitchableChannel(m_handle, value, &lStatus); }); diff --git a/wpilibc/src/main/native/cpp/Relay.cpp b/wpilibc/src/main/native/cpp/Relay.cpp index 9bec566d12c..3dfbe64930d 100644 --- a/wpilibc/src/main/native/cpp/Relay.cpp +++ b/wpilibc/src/main/native/cpp/Relay.cpp @@ -175,10 +175,10 @@ std::string Relay::GetDescription() const { void Relay::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("Relay"); builder.SetActuator(true); - builder.SetSafeState([=] { Set(kOff); }); + builder.SetSafeState([=, this] { Set(kOff); }); builder.AddSmallStringProperty( "Value", - [=](wpi::SmallVectorImpl& buf) -> std::string_view { + [=, this](wpi::SmallVectorImpl& buf) -> std::string_view { switch (Get()) { case kOn: return "On"; @@ -190,7 +190,7 @@ void Relay::InitSendable(wpi::SendableBuilder& builder) { return "Off"; } }, - [=](std::string_view value) { + [=, this](std::string_view value) { if (value == "Off") { Set(kOff); } else if (value == "Forward") { diff --git a/wpilibc/src/main/native/cpp/SPI.cpp b/wpilibc/src/main/native/cpp/SPI.cpp index a629d4de59b..29cd00635e5 100644 --- a/wpilibc/src/main/native/cpp/SPI.cpp +++ b/wpilibc/src/main/native/cpp/SPI.cpp @@ -25,7 +25,7 @@ class SPI::Accumulator { public: Accumulator(HAL_SPIPort port, int xferSize, int validMask, int validValue, int dataShift, int dataSize, bool isSigned, bool bigEndian) - : m_notifier([=] { + : m_notifier([=, this] { std::scoped_lock lock(m_mutex); Update(); }), @@ -268,7 +268,7 @@ void SPI::FreeAuto() { FRC_CheckErrorStatus(status, "Port {}", static_cast(m_port)); } -void SPI::SetAutoTransmitData(wpi::span dataToSend, +void SPI::SetAutoTransmitData(std::span dataToSend, int zeroSize) { int32_t status = 0; HAL_SetSPIAutoTransmitData(m_port, dataToSend.data(), dataToSend.size(), diff --git a/wpilibc/src/main/native/cpp/Servo.cpp b/wpilibc/src/main/native/cpp/Servo.cpp index c410bff8ae5..4a292b9bd03 100644 --- a/wpilibc/src/main/native/cpp/Servo.cpp +++ b/wpilibc/src/main/native/cpp/Servo.cpp @@ -64,7 +64,8 @@ double Servo::GetMinAngle() const { void Servo::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("Servo"); builder.AddDoubleProperty( - "Value", [=] { return Get(); }, [=](double value) { Set(value); }); + "Value", [=, this] { return Get(); }, + [=, this](double value) { Set(value); }); } double Servo::GetServoAngleRange() const { diff --git a/wpilibc/src/main/native/cpp/Solenoid.cpp b/wpilibc/src/main/native/cpp/Solenoid.cpp index 9cb181e9008..819f79a8d71 100644 --- a/wpilibc/src/main/native/cpp/Solenoid.cpp +++ b/wpilibc/src/main/native/cpp/Solenoid.cpp @@ -77,7 +77,8 @@ void Solenoid::StartPulse() { void Solenoid::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("Solenoid"); builder.SetActuator(true); - builder.SetSafeState([=] { Set(false); }); + builder.SetSafeState([=, this] { Set(false); }); builder.AddBooleanProperty( - "Value", [=] { return Get(); }, [=](bool value) { Set(value); }); + "Value", [=, this] { return Get(); }, + [=, this](bool value) { Set(value); }); } diff --git a/wpilibc/src/main/native/cpp/TimedRobot.cpp b/wpilibc/src/main/native/cpp/TimedRobot.cpp index ac889ce55c6..2d534045932 100644 --- a/wpilibc/src/main/native/cpp/TimedRobot.cpp +++ b/wpilibc/src/main/native/cpp/TimedRobot.cpp @@ -72,7 +72,7 @@ void TimedRobot::EndCompetition() { TimedRobot::TimedRobot(units::second_t period) : IterativeRobotBase(period) { m_startTime = Timer::GetFPGATimestamp(); - AddPeriodic([=] { LoopFunc(); }, period); + AddPeriodic([=, this] { LoopFunc(); }, period); int32_t status = 0; m_notifier = HAL_InitializeNotifier(&status); diff --git a/wpilibc/src/main/native/cpp/Ultrasonic.cpp b/wpilibc/src/main/native/cpp/Ultrasonic.cpp index c441c7164d9..615f3d7e211 100644 --- a/wpilibc/src/main/native/cpp/Ultrasonic.cpp +++ b/wpilibc/src/main/native/cpp/Ultrasonic.cpp @@ -157,7 +157,8 @@ void Ultrasonic::SetEnabled(bool enable) { void Ultrasonic::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("Ultrasonic"); builder.AddDoubleProperty( - "Value", [=] { return units::inch_t{GetRange()}.value(); }, nullptr); + "Value", [=, this] { return units::inch_t{GetRange()}.value(); }, + nullptr); } void Ultrasonic::Initialize() { diff --git a/wpilibc/src/main/native/cpp/Watchdog.cpp b/wpilibc/src/main/native/cpp/Watchdog.cpp index 854f9e9d393..b8a08f9c525 100644 --- a/wpilibc/src/main/native/cpp/Watchdog.cpp +++ b/wpilibc/src/main/native/cpp/Watchdog.cpp @@ -50,7 +50,7 @@ Watchdog::Impl::Impl() { FRC_CheckErrorStatus(status, "{}", "starting watchdog notifier"); HAL_SetNotifierName(m_notifier, "Watchdog", &status); - m_thread = std::thread([=] { Main(); }); + m_thread = std::thread([=, this] { Main(); }); } Watchdog::Impl::~Impl() { diff --git a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp index 7d9c53c61e0..a541eb1d24f 100644 --- a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp @@ -189,11 +189,11 @@ std::string DifferentialDrive::GetDescription() const { void DifferentialDrive::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("DifferentialDrive"); builder.SetActuator(true); - builder.SetSafeState([=] { StopMotor(); }); + builder.SetSafeState([=, this] { StopMotor(); }); builder.AddDoubleProperty( - "Left Motor Speed", [=] { return m_leftMotor->Get(); }, - [=](double value) { m_leftMotor->Set(value); }); + "Left Motor Speed", [=, this] { return m_leftMotor->Get(); }, + [=, this](double value) { m_leftMotor->Set(value); }); builder.AddDoubleProperty( - "Right Motor Speed", [=] { return m_rightMotor->Get(); }, - [=](double value) { m_rightMotor->Set(value); }); + "Right Motor Speed", [=, this] { return m_rightMotor->Get(); }, + [=, this](double value) { m_rightMotor->Set(value); }); } diff --git a/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp b/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp index 3131ce88228..ae6e118d9f7 100644 --- a/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp @@ -6,9 +6,9 @@ #include #include +#include #include -#include #include #include @@ -30,12 +30,12 @@ KilloughDrive::KilloughDrive(MotorController& leftMotor, : m_leftMotor(&leftMotor), m_rightMotor(&rightMotor), m_backMotor(&backMotor) { - m_leftVec = {std::cos(leftMotorAngle * (wpi::numbers::pi / 180.0)), - std::sin(leftMotorAngle * (wpi::numbers::pi / 180.0))}; - m_rightVec = {std::cos(rightMotorAngle * (wpi::numbers::pi / 180.0)), - std::sin(rightMotorAngle * (wpi::numbers::pi / 180.0))}; - m_backVec = {std::cos(backMotorAngle * (wpi::numbers::pi / 180.0)), - std::sin(backMotorAngle * (wpi::numbers::pi / 180.0))}; + m_leftVec = {std::cos(leftMotorAngle * (std::numbers::pi / 180.0)), + std::sin(leftMotorAngle * (std::numbers::pi / 180.0))}; + m_rightVec = {std::cos(rightMotorAngle * (std::numbers::pi / 180.0)), + std::sin(rightMotorAngle * (std::numbers::pi / 180.0))}; + m_backVec = {std::cos(backMotorAngle * (std::numbers::pi / 180.0)), + std::sin(backMotorAngle * (std::numbers::pi / 180.0))}; wpi::SendableRegistry::AddChild(this, m_leftMotor); wpi::SendableRegistry::AddChild(this, m_rightMotor); wpi::SendableRegistry::AddChild(this, m_backMotor); @@ -73,8 +73,8 @@ void KilloughDrive::DrivePolar(double magnitude, double angle, reported = true; } - DriveCartesian(magnitude * std::sin(angle * (wpi::numbers::pi / 180.0)), - magnitude * std::cos(angle * (wpi::numbers::pi / 180.0)), + DriveCartesian(magnitude * std::sin(angle * (std::numbers::pi / 180.0)), + magnitude * std::cos(angle * (std::numbers::pi / 180.0)), zRotation, 0.0); } @@ -113,14 +113,14 @@ std::string KilloughDrive::GetDescription() const { void KilloughDrive::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("KilloughDrive"); builder.SetActuator(true); - builder.SetSafeState([=] { StopMotor(); }); + builder.SetSafeState([=, this] { StopMotor(); }); builder.AddDoubleProperty( - "Left Motor Speed", [=] { return m_leftMotor->Get(); }, - [=](double value) { m_leftMotor->Set(value); }); + "Left Motor Speed", [=, this] { return m_leftMotor->Get(); }, + [=, this](double value) { m_leftMotor->Set(value); }); builder.AddDoubleProperty( - "Right Motor Speed", [=] { return m_rightMotor->Get(); }, - [=](double value) { m_rightMotor->Set(value); }); + "Right Motor Speed", [=, this] { return m_rightMotor->Get(); }, + [=, this](double value) { m_rightMotor->Set(value); }); builder.AddDoubleProperty( - "Back Motor Speed", [=] { return m_backMotor->Get(); }, - [=](double value) { m_backMotor->Set(value); }); + "Back Motor Speed", [=, this] { return m_backMotor->Get(); }, + [=, this](double value) { m_backMotor->Set(value); }); } diff --git a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp index b5c4a888421..b714cd2dfc3 100644 --- a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp @@ -6,9 +6,9 @@ #include #include +#include #include -#include #include #include @@ -65,8 +65,8 @@ void MecanumDrive::DrivePolar(double magnitude, double angle, reported = true; } - DriveCartesian(magnitude * std::cos(angle * (wpi::numbers::pi / 180.0)), - magnitude * std::sin(angle * (wpi::numbers::pi / 180.0)), + DriveCartesian(magnitude * std::cos(angle * (std::numbers::pi / 180.0)), + magnitude * std::sin(angle * (std::numbers::pi / 180.0)), zRotation, 0.0); } @@ -108,17 +108,17 @@ std::string MecanumDrive::GetDescription() const { void MecanumDrive::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("MecanumDrive"); builder.SetActuator(true); - builder.SetSafeState([=] { StopMotor(); }); + builder.SetSafeState([=, this] { StopMotor(); }); builder.AddDoubleProperty( - "Front Left Motor Speed", [=] { return m_frontLeftMotor->Get(); }, - [=](double value) { m_frontLeftMotor->Set(value); }); + "Front Left Motor Speed", [=, this] { return m_frontLeftMotor->Get(); }, + [=, this](double value) { m_frontLeftMotor->Set(value); }); builder.AddDoubleProperty( - "Front Right Motor Speed", [=] { return m_frontRightMotor->Get(); }, - [=](double value) { m_frontRightMotor->Set(value); }); + "Front Right Motor Speed", [=, this] { return m_frontRightMotor->Get(); }, + [=, this](double value) { m_frontRightMotor->Set(value); }); builder.AddDoubleProperty( - "Rear Left Motor Speed", [=] { return m_rearLeftMotor->Get(); }, - [=](double value) { m_rearLeftMotor->Set(value); }); + "Rear Left Motor Speed", [=, this] { return m_rearLeftMotor->Get(); }, + [=, this](double value) { m_rearLeftMotor->Set(value); }); builder.AddDoubleProperty( - "Rear Right Motor Speed", [=] { return m_rearRightMotor->Get(); }, - [=](double value) { m_rearRightMotor->Set(value); }); + "Rear Right Motor Speed", [=, this] { return m_rearRightMotor->Get(); }, + [=, this](double value) { m_rearRightMotor->Set(value); }); } diff --git a/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp b/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp index a320f4ad870..fbd0c6e63e2 100644 --- a/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp +++ b/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp @@ -30,7 +30,7 @@ void RobotDriveBase::FeedWatchdog() { Feed(); } -void RobotDriveBase::Desaturate(wpi::span wheelSpeeds) { +void RobotDriveBase::Desaturate(std::span wheelSpeeds) { double maxMagnitude = std::abs(wheelSpeeds[0]); for (size_t i = 1; i < wheelSpeeds.size(); i++) { double temp = std::abs(wheelSpeeds[i]); diff --git a/wpilibc/src/main/native/cpp/drive/Vector2d.cpp b/wpilibc/src/main/native/cpp/drive/Vector2d.cpp index a342dc276d8..acfbbd60b2b 100644 --- a/wpilibc/src/main/native/cpp/drive/Vector2d.cpp +++ b/wpilibc/src/main/native/cpp/drive/Vector2d.cpp @@ -5,8 +5,7 @@ #include "frc/drive/Vector2d.h" #include - -#include +#include using namespace frc; @@ -16,8 +15,8 @@ Vector2d::Vector2d(double x, double y) { } void Vector2d::Rotate(double angle) { - double cosA = std::cos(angle * (wpi::numbers::pi / 180.0)); - double sinA = std::sin(angle * (wpi::numbers::pi / 180.0)); + double cosA = std::cos(angle * (std::numbers::pi / 180.0)); + double sinA = std::sin(angle * (std::numbers::pi / 180.0)); double out[2]; out[0] = x * cosA - y * sinA; out[1] = x * sinA + y * cosA; diff --git a/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp b/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp index 32a8a2f0d05..f855d14b0ee 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp +++ b/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp @@ -69,7 +69,8 @@ void MotorControllerGroup::StopMotor() { void MotorControllerGroup::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("Motor Controller"); builder.SetActuator(true); - builder.SetSafeState([=] { StopMotor(); }); + builder.SetSafeState([=, this] { StopMotor(); }); builder.AddDoubleProperty( - "Value", [=] { return Get(); }, [=](double value) { Set(value); }); + "Value", [=, this] { return Get(); }, + [=, this](double value) { Set(value); }); } diff --git a/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp b/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp index 21164eb5a2e..01c70d042e7 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp +++ b/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp @@ -73,7 +73,8 @@ int NidecBrushless::GetChannel() const { void NidecBrushless::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("Nidec Brushless"); builder.SetActuator(true); - builder.SetSafeState([=] { StopMotor(); }); + builder.SetSafeState([=, this] { StopMotor(); }); builder.AddDoubleProperty( - "Value", [=] { return Get(); }, [=](double value) { Set(value); }); + "Value", [=, this] { return Get(); }, + [=, this](double value) { Set(value); }); } diff --git a/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp b/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp index f9ff4b8b24e..6de356fb066 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp +++ b/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp @@ -54,7 +54,8 @@ PWMMotorController::PWMMotorController(std::string_view name, int channel) void PWMMotorController::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("Motor Controller"); builder.SetActuator(true); - builder.SetSafeState([=] { Disable(); }); + builder.SetSafeState([=, this] { Disable(); }); builder.AddDoubleProperty( - "Value", [=] { return Get(); }, [=](double value) { Set(value); }); + "Value", [=, this] { return Get(); }, + [=, this](double value) { Set(value); }); } diff --git a/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp b/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp index e4446a34120..814660ace32 100644 --- a/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp +++ b/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp @@ -118,27 +118,27 @@ SimpleWidget& ShuffleboardContainer::Add(std::string_view title, } SimpleWidget& ShuffleboardContainer::Add(std::string_view title, - wpi::span defaultValue) { + std::span defaultValue) { return Add(title, nt::Value::MakeBooleanArray(defaultValue)); } SimpleWidget& ShuffleboardContainer::Add(std::string_view title, - wpi::span defaultValue) { + std::span defaultValue) { return Add(title, nt::Value::MakeDoubleArray(defaultValue)); } SimpleWidget& ShuffleboardContainer::Add(std::string_view title, - wpi::span defaultValue) { + std::span defaultValue) { return Add(title, nt::Value::MakeFloatArray(defaultValue)); } SimpleWidget& ShuffleboardContainer::Add( - std::string_view title, wpi::span defaultValue) { + std::string_view title, std::span defaultValue) { return Add(title, nt::Value::MakeIntegerArray(defaultValue)); } SimpleWidget& ShuffleboardContainer::Add( - std::string_view title, wpi::span defaultValue) { + std::string_view title, std::span defaultValue) { return Add(title, nt::Value::MakeStringArray(defaultValue)); } @@ -353,27 +353,27 @@ SimpleWidget& ShuffleboardContainer::AddPersistent( } SimpleWidget& ShuffleboardContainer::AddPersistent( - std::string_view title, wpi::span defaultValue) { + std::string_view title, std::span defaultValue) { return AddPersistent(title, nt::Value::MakeBooleanArray(defaultValue)); } SimpleWidget& ShuffleboardContainer::AddPersistent( - std::string_view title, wpi::span defaultValue) { + std::string_view title, std::span defaultValue) { return AddPersistent(title, nt::Value::MakeDoubleArray(defaultValue)); } SimpleWidget& ShuffleboardContainer::AddPersistent( - std::string_view title, wpi::span defaultValue) { + std::string_view title, std::span defaultValue) { return AddPersistent(title, nt::Value::MakeFloatArray(defaultValue)); } SimpleWidget& ShuffleboardContainer::AddPersistent( - std::string_view title, wpi::span defaultValue) { + std::string_view title, std::span defaultValue) { return AddPersistent(title, nt::Value::MakeIntegerArray(defaultValue)); } SimpleWidget& ShuffleboardContainer::AddPersistent( - std::string_view title, wpi::span defaultValue) { + std::string_view title, std::span defaultValue) { return AddPersistent(title, nt::Value::MakeStringArray(defaultValue)); } diff --git a/wpilibc/src/main/native/cpp/smartdashboard/FieldObject2d.cpp b/wpilibc/src/main/native/cpp/smartdashboard/FieldObject2d.cpp index 9d334e46ba8..3895e870f96 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/FieldObject2d.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/FieldObject2d.cpp @@ -42,7 +42,7 @@ Pose2d FieldObject2d::GetPose() const { return m_poses[0]; } -void FieldObject2d::SetPoses(wpi::span poses) { +void FieldObject2d::SetPoses(std::span poses) { std::scoped_lock lock(m_mutex); m_poses.assign(poses.begin(), poses.end()); UpdateEntry(); @@ -68,7 +68,7 @@ std::vector FieldObject2d::GetPoses() const { return std::vector(m_poses.begin(), m_poses.end()); } -wpi::span FieldObject2d::GetPoses( +std::span FieldObject2d::GetPoses( wpi::SmallVectorImpl& out) const { std::scoped_lock lock(m_mutex); UpdateFromEntry(); diff --git a/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp b/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp index 9c35e4f2388..71a36613fae 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp @@ -176,35 +176,35 @@ void SendableBuilderImpl::AddStringProperty( void SendableBuilderImpl::AddBooleanArrayProperty( std::string_view key, std::function()> getter, - std::function)> setter) { + std::function)> setter) { AddPropertyImpl(m_table->GetBooleanArrayTopic(key), std::move(getter), std::move(setter)); } void SendableBuilderImpl::AddIntegerArrayProperty( std::string_view key, std::function()> getter, - std::function)> setter) { + std::function)> setter) { AddPropertyImpl(m_table->GetIntegerArrayTopic(key), std::move(getter), std::move(setter)); } void SendableBuilderImpl::AddFloatArrayProperty( std::string_view key, std::function()> getter, - std::function)> setter) { + std::function)> setter) { AddPropertyImpl(m_table->GetFloatArrayTopic(key), std::move(getter), std::move(setter)); } void SendableBuilderImpl::AddDoubleArrayProperty( std::string_view key, std::function()> getter, - std::function)> setter) { + std::function)> setter) { AddPropertyImpl(m_table->GetDoubleArrayTopic(key), std::move(getter), std::move(setter)); } void SendableBuilderImpl::AddStringArrayProperty( std::string_view key, std::function()> getter, - std::function)> setter) { + std::function)> setter) { AddPropertyImpl(m_table->GetStringArrayTopic(key), std::move(getter), std::move(setter)); } @@ -212,7 +212,7 @@ void SendableBuilderImpl::AddStringArrayProperty( void SendableBuilderImpl::AddRawProperty( std::string_view key, std::string_view typeString, std::function()> getter, - std::function)> setter) { + std::function)> setter) { auto topic = m_table->GetRawTopic(key); auto prop = std::make_unique>(); if (getter) { @@ -265,35 +265,35 @@ void SendableBuilderImpl::AddSmallStringProperty( void SendableBuilderImpl::AddSmallBooleanArrayProperty( std::string_view key, - std::function(wpi::SmallVectorImpl& buf)> getter, - std::function)> setter) { + std::function(wpi::SmallVectorImpl& buf)> getter, + std::function)> setter) { AddSmallPropertyImpl(m_table->GetBooleanArrayTopic(key), std::move(getter), std::move(setter)); } void SendableBuilderImpl::AddSmallIntegerArrayProperty( std::string_view key, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::SmallVectorImpl& buf)> getter, - std::function)> setter) { + std::function)> setter) { AddSmallPropertyImpl(m_table->GetIntegerArrayTopic(key), std::move(getter), std::move(setter)); } void SendableBuilderImpl::AddSmallFloatArrayProperty( std::string_view key, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::SmallVectorImpl& buf)> getter, - std::function)> setter) { + std::function)> setter) { AddSmallPropertyImpl(m_table->GetFloatArrayTopic(key), std::move(getter), std::move(setter)); } void SendableBuilderImpl::AddSmallDoubleArrayProperty( std::string_view key, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::SmallVectorImpl& buf)> getter, - std::function)> setter) { + std::function)> setter) { AddSmallPropertyImpl(m_table->GetDoubleArrayTopic(key), std::move(getter), std::move(setter)); } @@ -301,18 +301,18 @@ void SendableBuilderImpl::AddSmallDoubleArrayProperty( void SendableBuilderImpl::AddSmallStringArrayProperty( std::string_view key, std::function< - wpi::span(wpi::SmallVectorImpl& buf)> + std::span(wpi::SmallVectorImpl& buf)> getter, - std::function)> setter) { + std::function)> setter) { AddSmallPropertyImpl(m_table->GetStringArrayTopic(key), std::move(getter), std::move(setter)); } void SendableBuilderImpl::AddSmallRawProperty( std::string_view key, std::string_view typeString, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::SmallVectorImpl& buf)> getter, - std::function)> setter) { + std::function)> setter) { auto topic = m_table->GetRawTopic(key); auto prop = std::make_unique>(); if (getter) { diff --git a/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp b/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp index 334a139aa53..f1e84be7a99 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp @@ -157,63 +157,63 @@ std::string SmartDashboard::GetString(std::string_view keyName, } bool SmartDashboard::PutBooleanArray(std::string_view key, - wpi::span value) { + std::span value) { return GetInstance().table->GetEntry(key).SetBooleanArray(value); } bool SmartDashboard::SetDefaultBooleanArray(std::string_view key, - wpi::span defaultValue) { + std::span defaultValue) { return GetInstance().table->GetEntry(key).SetDefaultBooleanArray( defaultValue); } std::vector SmartDashboard::GetBooleanArray( - std::string_view key, wpi::span defaultValue) { + std::string_view key, std::span defaultValue) { return GetInstance().table->GetEntry(key).GetBooleanArray(defaultValue); } bool SmartDashboard::PutNumberArray(std::string_view key, - wpi::span value) { + std::span value) { return GetInstance().table->GetEntry(key).SetDoubleArray(value); } bool SmartDashboard::SetDefaultNumberArray( - std::string_view key, wpi::span defaultValue) { + std::string_view key, std::span defaultValue) { return GetInstance().table->GetEntry(key).SetDefaultDoubleArray(defaultValue); } std::vector SmartDashboard::GetNumberArray( - std::string_view key, wpi::span defaultValue) { + std::string_view key, std::span defaultValue) { return GetInstance().table->GetEntry(key).GetDoubleArray(defaultValue); } bool SmartDashboard::PutStringArray(std::string_view key, - wpi::span value) { + std::span value) { return GetInstance().table->GetEntry(key).SetStringArray(value); } bool SmartDashboard::SetDefaultStringArray( - std::string_view key, wpi::span defaultValue) { + std::string_view key, std::span defaultValue) { return GetInstance().table->GetEntry(key).SetDefaultStringArray(defaultValue); } std::vector SmartDashboard::GetStringArray( - std::string_view key, wpi::span defaultValue) { + std::string_view key, std::span defaultValue) { return GetInstance().table->GetEntry(key).GetStringArray(defaultValue); } bool SmartDashboard::PutRaw(std::string_view key, - wpi::span value) { + std::span value) { return GetInstance().table->GetEntry(key).SetRaw(value); } bool SmartDashboard::SetDefaultRaw(std::string_view key, - wpi::span defaultValue) { + std::span defaultValue) { return GetInstance().table->GetEntry(key).SetDefaultRaw(defaultValue); } std::vector SmartDashboard::GetRaw( - std::string_view key, wpi::span defaultValue) { + std::string_view key, std::span defaultValue) { return GetInstance().table->GetEntry(key).GetRaw(defaultValue); } diff --git a/wpilibc/src/main/native/include/frc/AddressableLED.h b/wpilibc/src/main/native/include/frc/AddressableLED.h index 561eb3756a0..e6adfca28c5 100644 --- a/wpilibc/src/main/native/include/frc/AddressableLED.h +++ b/wpilibc/src/main/native/include/frc/AddressableLED.h @@ -5,11 +5,11 @@ #pragma once #include +#include #include #include #include -#include #include "util/Color.h" #include "util/Color8Bit.h" @@ -107,7 +107,7 @@ class AddressableLED { * * @param ledData the buffer to write */ - void SetData(wpi::span ledData); + void SetData(std::span ledData); /** * Sets the led output data. diff --git a/wpilibc/src/main/native/include/frc/SPI.h b/wpilibc/src/main/native/include/frc/SPI.h index 3f515951947..0d5b468cf38 100644 --- a/wpilibc/src/main/native/include/frc/SPI.h +++ b/wpilibc/src/main/native/include/frc/SPI.h @@ -7,11 +7,11 @@ #include #include +#include #include #include #include -#include namespace frc { @@ -196,7 +196,7 @@ class SPI { * @param dataToSend data to send (maximum 16 bytes) * @param zeroSize number of zeros to send after the data */ - void SetAutoTransmitData(wpi::span dataToSend, int zeroSize); + void SetAutoTransmitData(std::span dataToSend, int zeroSize); /** * Start running the automatic SPI transfer engine at a periodic rate. diff --git a/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h b/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h index 8f213cf2007..b3fb56be4ba 100644 --- a/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h +++ b/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h @@ -5,10 +5,9 @@ #pragma once #include +#include #include -#include - #include "frc/MotorSafety.h" namespace frc { @@ -75,7 +74,7 @@ class RobotDriveBase : public MotorSafety { * Renormalize all wheel speeds if the magnitude of any wheel is greater than * 1.0. */ - static void Desaturate(wpi::span wheelSpeeds); + static void Desaturate(std::span wheelSpeeds); double m_deadband = 0.02; double m_maxOutput = 1.0; diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/SendableCameraWrapper.h b/wpilibc/src/main/native/include/frc/shuffleboard/SendableCameraWrapper.h index 55701c28361..7951cf91e04 100644 --- a/wpilibc/src/main/native/include/frc/shuffleboard/SendableCameraWrapper.h +++ b/wpilibc/src/main/native/include/frc/shuffleboard/SendableCameraWrapper.h @@ -6,6 +6,7 @@ #include #include +#include #include #include @@ -25,7 +26,6 @@ using CS_Source = CS_Handle; // NOLINT #include #include #include -#include namespace frc { @@ -64,7 +64,7 @@ class SendableCameraWrapper * @param cameraUrls camera URLs */ SendableCameraWrapper(std::string_view cameraName, - wpi::span cameraUrls, + std::span cameraUrls, const private_init&); /** @@ -79,7 +79,7 @@ class SendableCameraWrapper static SendableCameraWrapper& Wrap(CS_Source source); static SendableCameraWrapper& Wrap(std::string_view cameraName, - wpi::span cameraUrls); + std::span cameraUrls); void InitSendable(wpi::SendableBuilder& builder) override; @@ -97,7 +97,7 @@ inline SendableCameraWrapper::SendableCameraWrapper(std::string_view name, } inline SendableCameraWrapper::SendableCameraWrapper( - std::string_view cameraName, wpi::span cameraUrls, + std::string_view cameraName, std::span cameraUrls, const private_init&) : SendableCameraWrapper(cameraName, private_init{}) { m_streams = nt::NetworkTableInstance::GetDefault() @@ -123,7 +123,7 @@ inline SendableCameraWrapper& SendableCameraWrapper::Wrap(CS_Source source) { } inline SendableCameraWrapper& SendableCameraWrapper::Wrap( - std::string_view cameraName, wpi::span cameraUrls) { + std::string_view cameraName, std::span cameraUrls) { auto& wrapper = detail::GetSendableCameraWrapper(cameraName); if (!wrapper) { wrapper = std::make_shared(cameraName, cameraUrls, diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardContainer.h b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardContainer.h index 719bf9ed5ec..5d207838208 100644 --- a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardContainer.h +++ b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardContainer.h @@ -6,6 +6,7 @@ #include #include +#include #include #include #include @@ -14,7 +15,6 @@ #include #include #include -#include #include "frc/shuffleboard/BuiltInLayouts.h" #include "frc/shuffleboard/LayoutType.h" @@ -137,7 +137,7 @@ class ShuffleboardContainer : public virtual ShuffleboardValue { * @return a widget to display the camera stream */ ComplexWidget& AddCamera(std::string_view title, std::string_view cameraName, - wpi::span cameraUrls); + std::span cameraUrls); /** * Adds a widget to this container to display the given sendable. @@ -259,10 +259,10 @@ class ShuffleboardContainer : public virtual ShuffleboardValue { * @return a widget to display the sendable data * @throws IllegalArgumentException if a widget already exists in this * container with the given title - * @see AddPersistent(std::string_view, wpi::span) - * Add(std::string_view title, wpi::span defaultValue) + * @see AddPersistent(std::string_view, std::span) + * Add(std::string_view title, std::span defaultValue) */ - SimpleWidget& Add(std::string_view title, wpi::span defaultValue); + SimpleWidget& Add(std::string_view title, std::span defaultValue); /** * Adds a widget to this container to display the given data. @@ -272,11 +272,11 @@ class ShuffleboardContainer : public virtual ShuffleboardValue { * @return a widget to display the sendable data * @throws IllegalArgumentException if a widget already exists in this * container with the given title - * @see AddPersistent(std::string_view, wpi::span) - * Add(std::string_view title, wpi::span defaultValue) + * @see AddPersistent(std::string_view, std::span) + * Add(std::string_view title, std::span defaultValue) */ SimpleWidget& Add(std::string_view title, - wpi::span defaultValue); + std::span defaultValue); /** * Adds a widget to this container to display the given data. @@ -286,11 +286,11 @@ class ShuffleboardContainer : public virtual ShuffleboardValue { * @return a widget to display the sendable data * @throws IllegalArgumentException if a widget already exists in this * container with the given title - * @see AddPersistent(std::string_view, wpi::span) - * Add(std::string_view title, wpi::span defaultValue) + * @see AddPersistent(std::string_view, std::span) + * Add(std::string_view title, std::span defaultValue) */ SimpleWidget& Add(std::string_view title, - wpi::span defaultValue); + std::span defaultValue); /** * Adds a widget to this container to display the given data. @@ -300,11 +300,11 @@ class ShuffleboardContainer : public virtual ShuffleboardValue { * @return a widget to display the sendable data * @throws IllegalArgumentException if a widget already exists in this * container with the given title - * @see AddPersistent(std::string_view, wpi::span) - * Add(std::string_view title, wpi::span defaultValue) + * @see AddPersistent(std::string_view, std::span) + * Add(std::string_view title, std::span defaultValue) */ SimpleWidget& Add(std::string_view title, - wpi::span defaultValue); + std::span defaultValue); /** * Adds a widget to this container to display the given data. @@ -314,11 +314,11 @@ class ShuffleboardContainer : public virtual ShuffleboardValue { * @return a widget to display the sendable data * @throws IllegalArgumentException if a widget already exists in this * container with the given title - * @see AddPersistent(std::string_view, wpi::span) - * Add(std::string_view title, wpi::span defaultValue) + * @see AddPersistent(std::string_view, std::span) + * Add(std::string_view title, std::span defaultValue) */ SimpleWidget& Add(std::string_view title, - wpi::span defaultValue); + std::span defaultValue); /** * Adds a widget to this container. The widget will display the data provided @@ -600,82 +600,82 @@ class ShuffleboardContainer : public virtual ShuffleboardValue { /** * Adds a widget to this container to display a simple piece of data. * - * Unlike Add(std::string_view, wpi::span), the value in the + * Unlike Add(std::string_view, std::span), the value in the * widget will be saved on the robot and will be used when the robot program * next starts rather than {@code defaultValue}. * * @param title the title of the widget * @param defaultValue the default value of the widget * @return a widget to display the sendable data - * @see Add(std::string_view, wpi::span) - * Add(std::string_view title, wpi::span defaultValue) + * @see Add(std::string_view, std::span) + * Add(std::string_view title, std::span defaultValue) */ SimpleWidget& AddPersistent(std::string_view title, - wpi::span defaultValue); + std::span defaultValue); /** * Adds a widget to this container to display a simple piece of data. * - * Unlike Add(std::string_view, wpi::span), the value in the + * Unlike Add(std::string_view, std::span), the value in the * widget will be saved on the robot and will be used when the robot program * next starts rather than {@code defaultValue}. * * @param title the title of the widget * @param defaultValue the default value of the widget * @return a widget to display the sendable data - * @see Add(std::string_view, wpi::span) - * Add(std::string_view title, wpi::span defaultValue) + * @see Add(std::string_view, std::span) + * Add(std::string_view title, std::span defaultValue) */ SimpleWidget& AddPersistent(std::string_view title, - wpi::span defaultValue); + std::span defaultValue); /** * Adds a widget to this container to display a simple piece of data. * - * Unlike Add(std::string_view, wpi::span), the value in the + * Unlike Add(std::string_view, std::span), the value in the * widget will be saved on the robot and will be used when the robot program * next starts rather than {@code defaultValue}. * * @param title the title of the widget * @param defaultValue the default value of the widget * @return a widget to display the sendable data - * @see Add(std::string_view, wpi::span) - * Add(std::string_view title, wpi::span defaultValue) + * @see Add(std::string_view, std::span) + * Add(std::string_view title, std::span defaultValue) */ SimpleWidget& AddPersistent(std::string_view title, - wpi::span defaultValue); + std::span defaultValue); /** * Adds a widget to this container to display a simple piece of data. * - * Unlike Add(std::string_view, wpi::span), the value in the + * Unlike Add(std::string_view, std::span), the value in the * widget will be saved on the robot and will be used when the robot program * next starts rather than {@code defaultValue}. * * @param title the title of the widget * @param defaultValue the default value of the widget * @return a widget to display the sendable data - * @see Add(std::string_view, wpi::span) - * Add(std::string_view title, wpi::span defaultValue) + * @see Add(std::string_view, std::span) + * Add(std::string_view title, std::span defaultValue) */ SimpleWidget& AddPersistent(std::string_view title, - wpi::span defaultValue); + std::span defaultValue); /** * Adds a widget to this container to display a simple piece of data. * - * Unlike Add(std::string_view, wpi::span), the value in + * Unlike Add(std::string_view, std::span), the value in * the widget will be saved on the robot and will be used when the robot * program next starts rather than {@code defaultValue}. * * @param title the title of the widget * @param defaultValue the default value of the widget * @return a widget to display the sendable data - * @see Add(std::string_view, wpi::span) - * Add(std::string_view title, wpi::span defaultValue) + * @see Add(std::string_view, std::span) + * Add(std::string_view title, std::span defaultValue) */ SimpleWidget& AddPersistent(std::string_view title, - wpi::span defaultValue); + std::span defaultValue); void EnableIfActuator() override; @@ -721,7 +721,7 @@ inline frc::ComplexWidget& frc::ShuffleboardContainer::Add( inline frc::ComplexWidget& frc::ShuffleboardContainer::AddCamera( std::string_view title, std::string_view cameraName, - wpi::span cameraUrls) { + std::span cameraUrls) { return Add(title, frc::SendableCameraWrapper::Wrap(cameraName, cameraUrls)); } #endif diff --git a/wpilibc/src/main/native/include/frc/simulation/BatterySim.h b/wpilibc/src/main/native/include/frc/simulation/BatterySim.h index 90523436c2d..ab79844e30c 100644 --- a/wpilibc/src/main/native/include/frc/simulation/BatterySim.h +++ b/wpilibc/src/main/native/include/frc/simulation/BatterySim.h @@ -5,11 +5,11 @@ #pragma once #include +#include #include #include #include -#include namespace frc::sim { @@ -32,7 +32,7 @@ class BatterySim { */ static units::volt_t Calculate(units::volt_t nominalVoltage, units::ohm_t resistance, - wpi::span currents) { + std::span currents) { return nominalVoltage - std::accumulate(currents.begin(), currents.end(), 0_A) * resistance; } @@ -66,7 +66,7 @@ class BatterySim { * @param currents The currents drawn from the battery. * @return The battery's voltage under load. */ - static units::volt_t Calculate(wpi::span currents) { + static units::volt_t Calculate(std::span currents) { return Calculate(12_V, 0.02_Ohm, currents); } diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/FieldObject2d.h b/wpilibc/src/main/native/include/frc/smartdashboard/FieldObject2d.h index 83bdc9d392f..f55938e8df0 100644 --- a/wpilibc/src/main/native/include/frc/smartdashboard/FieldObject2d.h +++ b/wpilibc/src/main/native/include/frc/smartdashboard/FieldObject2d.h @@ -5,6 +5,7 @@ #pragma once #include +#include #include #include #include @@ -14,7 +15,6 @@ #include #include #include -#include #include "frc/geometry/Pose2d.h" #include "frc/geometry/Rotation2d.h" @@ -66,7 +66,7 @@ class FieldObject2d { * * @param poses array of 2D poses */ - void SetPoses(wpi::span poses); + void SetPoses(std::span poses); /** * Set multiple poses from an array of Pose objects. @@ -97,7 +97,7 @@ class FieldObject2d { * @param out output SmallVector to hold 2D poses * @return span referring to output SmallVector */ - wpi::span GetPoses(wpi::SmallVectorImpl& out) const; + std::span GetPoses(wpi::SmallVectorImpl& out) const; private: void UpdateEntry(bool setDefault = false); diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h b/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h index d156ca1b01b..4bd42896e2a 100644 --- a/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h +++ b/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h @@ -6,6 +6,7 @@ #include #include +#include #include #include #include @@ -17,7 +18,6 @@ #include #include #include -#include namespace frc { @@ -111,28 +111,28 @@ class SendableBuilderImpl : public nt::NTSendableBuilder { void AddBooleanArrayProperty( std::string_view key, std::function()> getter, - std::function)> setter) override; + std::function)> setter) override; void AddIntegerArrayProperty( std::string_view key, std::function()> getter, - std::function)> setter) override; + std::function)> setter) override; void AddFloatArrayProperty( std::string_view key, std::function()> getter, - std::function)> setter) override; + std::function)> setter) override; void AddDoubleArrayProperty( std::string_view key, std::function()> getter, - std::function)> setter) override; + std::function)> setter) override; void AddStringArrayProperty( std::string_view key, std::function()> getter, - std::function)> setter) override; + std::function)> setter) override; void AddRawProperty( std::string_view key, std::string_view typeString, std::function()> getter, - std::function)> setter) override; + std::function)> setter) override; void AddSmallStringProperty( std::string_view key, @@ -141,41 +141,41 @@ class SendableBuilderImpl : public nt::NTSendableBuilder { void AddSmallBooleanArrayProperty( std::string_view key, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::SmallVectorImpl& buf)> getter, - std::function)> setter) override; + std::function)> setter) override; void AddSmallIntegerArrayProperty( std::string_view key, std::function< - wpi::span(wpi::SmallVectorImpl& buf)> + std::span(wpi::SmallVectorImpl& buf)> getter, - std::function)> setter) override; + std::function)> setter) override; void AddSmallFloatArrayProperty( std::string_view key, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::SmallVectorImpl& buf)> getter, - std::function)> setter) override; + std::function)> setter) override; void AddSmallDoubleArrayProperty( std::string_view key, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::SmallVectorImpl& buf)> getter, - std::function)> setter) override; + std::function)> setter) override; void AddSmallStringArrayProperty( std::string_view key, std::function< - wpi::span(wpi::SmallVectorImpl& buf)> + std::span(wpi::SmallVectorImpl& buf)> getter, - std::function)> setter) override; + std::function)> setter) override; void AddSmallRawProperty( std::string_view key, std::string_view typeString, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::SmallVectorImpl& buf)> getter, - std::function)> setter) override; + std::function)> setter) override; private: struct Property { diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.inc b/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.inc index 7bc30cbfb83..e90542b96bf 100644 --- a/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.inc +++ b/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.inc @@ -58,7 +58,7 @@ void SendableChooser::InitSendable(nt::NTSendableBuilder& builder) { } builder.AddStringArrayProperty( kOptions, - [=] { + [=, this] { std::vector keys; for (const auto& choice : m_choices) { keys.emplace_back(choice.first()); @@ -73,13 +73,13 @@ void SendableChooser::InitSendable(nt::NTSendableBuilder& builder) { nullptr); builder.AddSmallStringProperty( kDefault, - [=](wpi::SmallVectorImpl&) -> std::string_view { + [=, this](wpi::SmallVectorImpl&) -> std::string_view { return m_defaultChoice; }, nullptr); builder.AddSmallStringProperty( kActive, - [=](wpi::SmallVectorImpl& buf) -> std::string_view { + [=, this](wpi::SmallVectorImpl& buf) -> std::string_view { std::scoped_lock lock(m_mutex); if (m_haveSelected) { buf.assign(m_selected.begin(), m_selected.end()); @@ -89,14 +89,15 @@ void SendableChooser::InitSendable(nt::NTSendableBuilder& builder) { } }, nullptr); - builder.AddStringProperty(kSelected, nullptr, [=](std::string_view val) { - std::scoped_lock lock(m_mutex); - m_haveSelected = true; - m_selected = val; - for (auto& pub : m_activePubs) { - pub.Set(val); - } - }); + builder.AddStringProperty(kSelected, nullptr, + [=, this](std::string_view val) { + std::scoped_lock lock(m_mutex); + m_haveSelected = true; + m_selected = val; + for (auto& pub : m_activePubs) { + pub.Set(val); + } + }); } template diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SmartDashboard.h b/wpilibc/src/main/native/include/frc/smartdashboard/SmartDashboard.h index 2e352156f10..aeb4947f7c9 100644 --- a/wpilibc/src/main/native/include/frc/smartdashboard/SmartDashboard.h +++ b/wpilibc/src/main/native/include/frc/smartdashboard/SmartDashboard.h @@ -5,13 +5,13 @@ #pragma once #include +#include #include #include #include #include #include -#include namespace wpi { class Sendable; @@ -216,7 +216,7 @@ class SmartDashboard { * std::vector is special-cased in C++. 0 is false, any * non-zero value is true. */ - static bool PutBooleanArray(std::string_view key, wpi::span value); + static bool PutBooleanArray(std::string_view key, std::span value); /** * Gets the current value in the table, setting it if it does not exist. @@ -226,7 +226,7 @@ class SmartDashboard { * @returns False if the table key exists with a different type */ static bool SetDefaultBooleanArray(std::string_view key, - wpi::span defaultValue); + std::span defaultValue); /** * Returns the boolean array the key maps to. @@ -247,7 +247,7 @@ class SmartDashboard { * non-zero value is true. */ static std::vector GetBooleanArray(std::string_view key, - wpi::span defaultValue); + std::span defaultValue); /** * Put a number array in the table. @@ -257,7 +257,7 @@ class SmartDashboard { * @return False if the table key already exists with a different type */ static bool PutNumberArray(std::string_view key, - wpi::span value); + std::span value); /** * Gets the current value in the table, setting it if it does not exist. @@ -267,7 +267,7 @@ class SmartDashboard { * @returns False if the table key exists with a different type */ static bool SetDefaultNumberArray(std::string_view key, - wpi::span defaultValue); + std::span defaultValue); /** * Returns the number array the key maps to. @@ -284,7 +284,7 @@ class SmartDashboard { * use GetValue() instead. */ static std::vector GetNumberArray( - std::string_view key, wpi::span defaultValue); + std::string_view key, std::span defaultValue); /** * Put a string array in the table. @@ -294,7 +294,7 @@ class SmartDashboard { * @return False if the table key already exists with a different type */ static bool PutStringArray(std::string_view key, - wpi::span value); + std::span value); /** * Gets the current value in the table, setting it if it does not exist. @@ -304,7 +304,7 @@ class SmartDashboard { * @returns False if the table key exists with a different type */ static bool SetDefaultStringArray(std::string_view key, - wpi::span defaultValue); + std::span defaultValue); /** * Returns the string array the key maps to. @@ -321,7 +321,7 @@ class SmartDashboard { * use GetValue() instead. */ static std::vector GetStringArray( - std::string_view key, wpi::span defaultValue); + std::string_view key, std::span defaultValue); /** * Put a raw value (byte array) in the table. @@ -330,7 +330,7 @@ class SmartDashboard { * @param value The value that will be assigned. * @return False if the table key already exists with a different type */ - static bool PutRaw(std::string_view key, wpi::span value); + static bool PutRaw(std::string_view key, std::span value); /** * Gets the current value in the table, setting it if it does not exist. @@ -340,7 +340,7 @@ class SmartDashboard { * @returns False if the table key exists with a different type */ static bool SetDefaultRaw(std::string_view key, - wpi::span defaultValue); + std::span defaultValue); /** * Returns the raw value (byte array) the key maps to. @@ -357,7 +357,7 @@ class SmartDashboard { * concern, use GetValue() instead. */ static std::vector GetRaw(std::string_view key, - wpi::span defaultValue); + std::span defaultValue); /** * Maps the specified key to the specified complex value (such as an array) in diff --git a/wpilibc/src/test/native/cpp/simulation/AnalogEncoderSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/AnalogEncoderSimTest.cpp index 375e21a43cb..0a1b687175a 100644 --- a/wpilibc/src/test/native/cpp/simulation/AnalogEncoderSimTest.cpp +++ b/wpilibc/src/test/native/cpp/simulation/AnalogEncoderSimTest.cpp @@ -2,9 +2,10 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +#include + #include #include -#include #include "frc/AnalogEncoder.h" #include "frc/AnalogInput.h" @@ -22,6 +23,6 @@ TEST(AnalogEncoderSimTest, Basic) { encoderSim.SetPosition(180_deg); EXPECT_NEAR(encoder.Get().value(), 0.5, 1E-8); EXPECT_NEAR(encoderSim.GetTurns().value(), 0.5, 1E-8); - EXPECT_NEAR(encoderSim.GetPosition().Radians().value(), wpi::numbers::pi, + EXPECT_NEAR(encoderSim.GetPosition().Radians().value(), std::numbers::pi, 1E-8); } diff --git a/wpilibc/src/test/native/cpp/simulation/SingleJointedArmSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/SingleJointedArmSimTest.cpp index dbcffb07c46..2e4c793e568 100644 --- a/wpilibc/src/test/native/cpp/simulation/SingleJointedArmSimTest.cpp +++ b/wpilibc/src/test/native/cpp/simulation/SingleJointedArmSimTest.cpp @@ -2,7 +2,7 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include +#include #include "frc/simulation/SingleJointedArmSim.h" #include "gtest/gtest.h" @@ -18,5 +18,5 @@ TEST(SingleJointedArmTest, Disabled) { } // The arm should swing down. - EXPECT_NEAR(sim.GetAngle().value(), -wpi::numbers::pi / 2, 0.01); + EXPECT_NEAR(sim.GetAngle().value(), -std::numbers::pi / 2, 0.01); } diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Constants.h index bd432eea051..cff39322b27 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Constants.h +++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Constants.h @@ -4,11 +4,12 @@ #pragma once +#include + #include #include #include #include -#include /** * The Constants header provides a convenient place for teams to hold robot-wide @@ -34,7 +35,7 @@ constexpr int kEncoderCPR = 1024; constexpr double kWheelDiameterInches = 6; constexpr double kEncoderDistancePerPulse = // Assumes the encoders are directly mounted on the wheel shafts - (kWheelDiameterInches * wpi::numbers::pi) / + (kWheelDiameterInches * std::numbers::pi) / static_cast(kEncoderCPR); } // namespace DriveConstants @@ -56,7 +57,7 @@ constexpr auto kMaxAcceleration = 10_rad / (1_s * 1_s); constexpr int kEncoderPorts[]{4, 5}; constexpr int kEncoderPPR = 256; constexpr auto kEncoderDistancePerPulse = - 2.0_rad * wpi::numbers::pi / kEncoderPPR; + 2.0_rad * std::numbers::pi / kEncoderPPR; // The offset of the arm from the horizontal in its neutral position, // measured from the horizontal diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Constants.h index bd432eea051..cff39322b27 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Constants.h +++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Constants.h @@ -4,11 +4,12 @@ #pragma once +#include + #include #include #include #include -#include /** * The Constants header provides a convenient place for teams to hold robot-wide @@ -34,7 +35,7 @@ constexpr int kEncoderCPR = 1024; constexpr double kWheelDiameterInches = 6; constexpr double kEncoderDistancePerPulse = // Assumes the encoders are directly mounted on the wheel shafts - (kWheelDiameterInches * wpi::numbers::pi) / + (kWheelDiameterInches * std::numbers::pi) / static_cast(kEncoderCPR); } // namespace DriveConstants @@ -56,7 +57,7 @@ constexpr auto kMaxAcceleration = 10_rad / (1_s * 1_s); constexpr int kEncoderPorts[]{4, 5}; constexpr int kEncoderPPR = 256; constexpr auto kEncoderDistancePerPulse = - 2.0_rad * wpi::numbers::pi / kEncoderPPR; + 2.0_rad * std::numbers::pi / kEncoderPPR; // The offset of the arm from the horizontal in its neutral position, // measured from the horizontal diff --git a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp index e8003755b3d..2027d255efd 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +#include + #include #include #include @@ -22,7 +24,6 @@ #include #include #include -#include /** * This is a sample program to demonstrate how to use a state-space controller @@ -45,7 +46,7 @@ class Robot : public frc::TimedRobot { // distance per pulse = (angle per revolution) / (pulses per revolution) // = (2 * PI rads) / (4096 pulses) static constexpr double kArmEncoderDistPerPulse = - 2.0 * wpi::numbers::pi / 4096.0; + 2.0 * std::numbers::pi / 4096.0; // The arm gearbox represents a gearbox containing two Vex 775pro motors. frc::DCMotor m_armGearbox = frc::DCMotor::Vex775Pro(2); diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h index 81d0a71ba5d..bdc624c5113 100644 --- a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h @@ -4,6 +4,8 @@ #pragma once +#include + #include #include #include @@ -16,7 +18,6 @@ #include #include #include -#include /** * Represents a differential drive style drivetrain. @@ -33,9 +34,9 @@ class Drivetrain { // Set the distance per pulse for the drive encoders. We can simply use the // distance traveled for one rotation of the wheel divided by the encoder // resolution. - m_leftEncoder.SetDistancePerPulse(2 * wpi::numbers::pi * kWheelRadius / + m_leftEncoder.SetDistancePerPulse(2 * std::numbers::pi * kWheelRadius / kEncoderResolution); - m_rightEncoder.SetDistancePerPulse(2 * wpi::numbers::pi * kWheelRadius / + m_rightEncoder.SetDistancePerPulse(2 * std::numbers::pi * kWheelRadius / kEncoderResolution); m_leftEncoder.Reset(); @@ -45,7 +46,7 @@ class Drivetrain { static constexpr units::meters_per_second_t kMaxSpeed = 3.0_mps; // 3 meters per second static constexpr units::radians_per_second_t kMaxAngularSpeed{ - wpi::numbers::pi}; // 1/2 rotation per second + std::numbers::pi}; // 1/2 rotation per second void SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds); void Drive(units::meters_per_second_t xSpeed, diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h index 65948feb5cf..9de12892777 100644 --- a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h @@ -4,6 +4,8 @@ #pragma once +#include + #include #include #include @@ -16,7 +18,6 @@ #include #include #include -#include /** * Represents a differential drive style drivetrain. @@ -34,9 +35,9 @@ class Drivetrain { // distance traveled for one rotation of the wheel divided by the encoder // resolution. m_leftEncoder.SetDistancePerPulse( - 2 * wpi::numbers::pi * kWheelRadius.value() / kEncoderResolution); + 2 * std::numbers::pi * kWheelRadius.value() / kEncoderResolution); m_rightEncoder.SetDistancePerPulse( - 2 * wpi::numbers::pi * kWheelRadius.value() / kEncoderResolution); + 2 * std::numbers::pi * kWheelRadius.value() / kEncoderResolution); m_leftEncoder.Reset(); m_rightEncoder.Reset(); @@ -45,7 +46,7 @@ class Drivetrain { static constexpr units::meters_per_second_t kMaxSpeed = 3.0_mps; // 3 meters per second static constexpr units::radians_per_second_t kMaxAngularSpeed{ - wpi::numbers::pi}; // 1/2 rotation per second + std::numbers::pi}; // 1/2 rotation per second void SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds); void Drive(units::meters_per_second_t xSpeed, diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Constants.h index 6644c089afa..7b7de4080ee 100644 --- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Constants.h +++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Constants.h @@ -4,12 +4,13 @@ #pragma once +#include + #include #include #include #include #include -#include /** * The Constants header provides a convenient place for teams to hold robot-wide diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorProfiledPID/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ElevatorProfiledPID/cpp/Robot.cpp index 5ea7ca4ebc3..518114a0a27 100644 --- a/wpilibcExamples/src/main/cpp/examples/ElevatorProfiledPID/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ElevatorProfiledPID/cpp/Robot.cpp @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +#include + #include #include #include @@ -12,14 +14,13 @@ #include #include #include -#include class Robot : public frc::TimedRobot { public: static constexpr units::second_t kDt = 20_ms; Robot() { - m_encoder.SetDistancePerPulse(1.0 / 360.0 * 2.0 * wpi::numbers::pi * 1.5); + m_encoder.SetDistancePerPulse(1.0 / 360.0 * 2.0 * std::numbers::pi * 1.5); } void TeleopPeriodic() override { diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/Robot.cpp index eebbb0a7b89..cd61cf7dc5c 100644 --- a/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/Robot.cpp @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +#include + #include #include #include @@ -23,7 +25,6 @@ #include #include #include -#include /** * This is a sample program to demonstrate how to use a state-space controller @@ -46,7 +47,7 @@ class Robot : public frc::TimedRobot { // distance per pulse = (distance per revolution) / (pulses per revolution) // = (Pi * D) / ppr static constexpr double kArmEncoderDistPerPulse = - 2.0 * wpi::numbers::pi * kElevatorDrumRadius.value() / 4096.0; + 2.0 * std::numbers::pi * kElevatorDrumRadius.value() / 4096.0; // This gearbox represents a gearbox containing 4 Vex 775pro motors. frc::DCMotor m_elevatorGearbox = frc::DCMotor::Vex775Pro(4); diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp index d62918578fd..f708143cebd 100644 --- a/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +#include + #include #include #include @@ -11,7 +13,6 @@ #include #include #include -#include #include "ExampleSmartMotorController.h" diff --git a/wpilibcExamples/src/main/cpp/examples/Encoder/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Encoder/cpp/Robot.cpp index 7db2c8309a5..255cc4f7033 100644 --- a/wpilibcExamples/src/main/cpp/examples/Encoder/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Encoder/cpp/Robot.cpp @@ -2,10 +2,11 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +#include + #include #include #include -#include /** * Sample program displaying the value of a quadrature encoder on the @@ -40,7 +41,7 @@ class Robot : public frc::TimedRobot { * inch diameter (1.5inch radius) wheel, and that we want to measure * distance in inches. */ - m_encoder.SetDistancePerPulse(1.0 / 360.0 * 2.0 * wpi::numbers::pi * 1.5); + m_encoder.SetDistancePerPulse(1.0 / 360.0 * 2.0 * std::numbers::pi * 1.5); /* Defines the lowest rate at which the encoder will not be considered * stopped, for the purposes of the GetStopped() method. Units are in diff --git a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/Constants.h index 8ac7b0ec6c0..855603ac194 100644 --- a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/Constants.h +++ b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/Constants.h @@ -4,10 +4,11 @@ #pragma once +#include + #include #include #include -#include /** * The Constants header provides a convenient place for teams to hold robot-wide @@ -33,7 +34,7 @@ constexpr int kEncoderCPR = 1024; constexpr double kWheelDiameterInches = 6; constexpr double kEncoderDistancePerPulse = // Assumes the encoders are directly mounted on the wheel shafts - (kWheelDiameterInches * wpi::numbers::pi) / + (kWheelDiameterInches * std::numbers::pi) / static_cast(kEncoderCPR); } // namespace DriveConstants diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp index 16d6e460938..2bfd391d6aa 100644 --- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp +++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp @@ -4,10 +4,11 @@ #include "subsystems/Drivetrain.h" +#include + #include #include #include -#include Drivetrain::Drivetrain() { // We need to invert one side of the drivetrain so that positive voltages @@ -26,9 +27,9 @@ Drivetrain::Drivetrain() { #else // Circumference = diameter * pi. 360 tick simulated encoders. m_leftEncoder.SetDistancePerPulse(units::foot_t{4_in}.value() * - wpi::numbers::pi / 360.0); + std::numbers::pi / 360.0); m_rightEncoder.SetDistancePerPulse(units::foot_t{4_in}.value() * - wpi::numbers::pi / 360.0); + std::numbers::pi / 360.0); #endif SetName("Drivetrain"); // Let's show everything on the LiveWindow diff --git a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/Constants.h index 210f82dd9b7..77673c96a17 100644 --- a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/Constants.h +++ b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/Constants.h @@ -4,9 +4,10 @@ #pragma once +#include + #include #include -#include /** * The Constants header provides a convenient place for teams to hold robot-wide @@ -32,7 +33,7 @@ constexpr int kEncoderCPR = 1024; constexpr double kWheelDiameterInches = 6; constexpr double kEncoderDistancePerPulse = // Assumes the encoders are directly mounted on the wheel shafts - (kWheelDiameterInches * wpi::numbers::pi) / + (kWheelDiameterInches * std::numbers::pi) / static_cast(kEncoderCPR); constexpr bool kGyroReversed = true; diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Constants.h index e9fbfdc8480..7a2bdae72e8 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Constants.h +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Constants.h @@ -4,7 +4,7 @@ #pragma once -#include +#include /** * The Constants header provides a convenient place for teams to hold robot-wide @@ -30,7 +30,7 @@ constexpr int kEncoderCPR = 1024; constexpr double kWheelDiameterInches = 6; constexpr double kEncoderDistancePerPulse = // Assumes the encoders are directly mounted on the wheel shafts - (kWheelDiameterInches * wpi::numbers::pi) / + (kWheelDiameterInches * std::numbers::pi) / static_cast(kEncoderCPR); } // namespace DriveConstants diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Constants.h index e9fbfdc8480..7a2bdae72e8 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Constants.h +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Constants.h @@ -4,7 +4,7 @@ #pragma once -#include +#include /** * The Constants header provides a convenient place for teams to hold robot-wide @@ -30,7 +30,7 @@ constexpr int kEncoderCPR = 1024; constexpr double kWheelDiameterInches = 6; constexpr double kEncoderDistancePerPulse = // Assumes the encoders are directly mounted on the wheel shafts - (kWheelDiameterInches * wpi::numbers::pi) / + (kWheelDiameterInches * std::numbers::pi) / static_cast(kEncoderCPR); } // namespace DriveConstants diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.h index 9ec5fc5b771..2f76b596e92 100644 --- a/wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.h @@ -4,6 +4,8 @@ #pragma once +#include + #include #include #include @@ -13,7 +15,6 @@ #include #include #include -#include /** * Represents a mecanum drive style drivetrain. @@ -39,7 +40,7 @@ class Drivetrain { static constexpr units::meters_per_second_t kMaxSpeed = 3.0_mps; // 3 meters per second static constexpr units::radians_per_second_t kMaxAngularSpeed{ - wpi::numbers::pi}; // 1/2 rotation per second + std::numbers::pi}; // 1/2 rotation per second private: frc::PWMSparkMax m_frontLeftMotor{1}; diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Constants.h index 9385f2aa3de..527504ac3c0 100644 --- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Constants.h +++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Constants.h @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +#include + #include #include #include @@ -13,7 +15,6 @@ #include #include #include -#include #pragma once @@ -52,7 +53,7 @@ constexpr int kEncoderCPR = 1024; constexpr double kWheelDiameterMeters = 0.15; constexpr double kEncoderDistancePerPulse = // Assumes the encoders are directly mounted on the wheel shafts - (kWheelDiameterMeters * wpi::numbers::pi) / + (kWheelDiameterMeters * std::numbers::pi) / static_cast(kEncoderCPR); // These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT! diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/Drivetrain.h index e19b1fe25b2..a4cc5838689 100644 --- a/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/Drivetrain.h @@ -4,6 +4,8 @@ #pragma once +#include + #include #include #include @@ -14,7 +16,6 @@ #include #include #include -#include /** * Represents a mecanum drive style drivetrain. @@ -39,7 +40,7 @@ class Drivetrain { static constexpr auto kMaxSpeed = 3.0_mps; // 3 meters per second static constexpr units::radians_per_second_t kMaxAngularSpeed{ - wpi::numbers::pi}; // 1/2 rotation per second + std::numbers::pi}; // 1/2 rotation per second private: frc::PWMSparkMax m_frontLeftMotor{1}; diff --git a/wpilibcExamples/src/main/cpp/examples/MotorControlEncoder/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MotorControlEncoder/cpp/Robot.cpp index 7d0e9baf964..97d773c5715 100644 --- a/wpilibcExamples/src/main/cpp/examples/MotorControlEncoder/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/MotorControlEncoder/cpp/Robot.cpp @@ -2,12 +2,13 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +#include + #include #include #include #include #include -#include /** * This sample program shows how to control a motor using a joystick. In the @@ -35,7 +36,7 @@ class Robot : public frc::TimedRobot { void RobotInit() override { // Use SetDistancePerPulse to set the multiplier for GetDistance // This is set up assuming a 6 inch wheel with a 360 CPR encoder. - m_encoder.SetDistancePerPulse((wpi::numbers::pi * 6) / 360.0); + m_encoder.SetDistancePerPulse((std::numbers::pi * 6) / 360.0); } private: diff --git a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h index 5562f7718f4..18747d4eed4 100644 --- a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h +++ b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +#include + #include #include #include @@ -10,7 +12,6 @@ #include #include #include -#include #pragma once @@ -41,7 +42,7 @@ constexpr int kEncoderCPR = 1024; constexpr double kWheelDiameterInches = 6; constexpr double kEncoderDistancePerPulse = // Assumes the encoders are directly mounted on the wheel shafts - (kWheelDiameterInches * wpi::numbers::pi) / + (kWheelDiameterInches * std::numbers::pi) / static_cast(kEncoderCPR); // These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT! diff --git a/wpilibcExamples/src/main/cpp/examples/RamseteController/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/RamseteController/include/Drivetrain.h index 11fa52342ae..e66d9e8726c 100644 --- a/wpilibcExamples/src/main/cpp/examples/RamseteController/include/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/RamseteController/include/Drivetrain.h @@ -4,6 +4,8 @@ #pragma once +#include + #include #include #include @@ -14,7 +16,6 @@ #include #include #include -#include /** * Represents a differential drive style drivetrain. @@ -32,9 +33,9 @@ class Drivetrain { // Set the distance per pulse for the drive encoders. We can simply use the // distance traveled for one rotation of the wheel divided by the encoder // resolution. - m_leftEncoder.SetDistancePerPulse(2 * wpi::numbers::pi * kWheelRadius / + m_leftEncoder.SetDistancePerPulse(2 * std::numbers::pi * kWheelRadius / kEncoderResolution); - m_rightEncoder.SetDistancePerPulse(2 * wpi::numbers::pi * kWheelRadius / + m_rightEncoder.SetDistancePerPulse(2 * std::numbers::pi * kWheelRadius / kEncoderResolution); m_leftEncoder.Reset(); @@ -44,7 +45,7 @@ class Drivetrain { static constexpr units::meters_per_second_t kMaxSpeed = 3.0_mps; // 3 meters per second static constexpr units::radians_per_second_t kMaxAngularSpeed{ - wpi::numbers::pi}; // 1/2 rotation per second + std::numbers::pi}; // 1/2 rotation per second void SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds); void Drive(units::meters_per_second_t xSpeed, diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/commands/TurnDegrees.cpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/commands/TurnDegrees.cpp index 2d6c148df17..8c1f29e5f78 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/commands/TurnDegrees.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/commands/TurnDegrees.cpp @@ -4,8 +4,9 @@ #include "commands/TurnDegrees.h" +#include + #include -#include void TurnDegrees::Initialize() { // Set motors to stop, read encoder values for starting point @@ -26,7 +27,7 @@ bool TurnDegrees::IsFinished() { // found here https://www.pololu.com/category/203/romi-chassis-kits, has a // wheel placement diameter (149 mm) - width of the wheel (8 mm) = 141 mm // or 5.551 inches. We then take into consideration the width of the tires. - static auto inchPerDegree = (5.551_in * wpi::numbers::pi) / 360_deg; + static auto inchPerDegree = (5.551_in * std::numbers::pi) / 360_deg; // Compare distance traveled from start to distance based on degree turn. return GetAverageTurningDistance() >= inchPerDegree * m_angle; diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp index 9382e57ed9d..979f8a0e5d4 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp @@ -4,7 +4,7 @@ #include "subsystems/Drivetrain.h" -#include +#include #include "Constants.h" @@ -20,9 +20,9 @@ Drivetrain::Drivetrain() { // gearbox is constructed, you might have to invert the left side instead. m_rightMotor.SetInverted(true); - m_leftEncoder.SetDistancePerPulse(wpi::numbers::pi * kWheelDiameter.value() / + m_leftEncoder.SetDistancePerPulse(std::numbers::pi * kWheelDiameter.value() / kCountsPerRevolution); - m_rightEncoder.SetDistancePerPulse(wpi::numbers::pi * kWheelDiameter.value() / + m_rightEncoder.SetDistancePerPulse(std::numbers::pi * kWheelDiameter.value() / kCountsPerRevolution); ResetEncoders(); } diff --git a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.h index d8c58c28e8d..f163c9b038f 100644 --- a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.h @@ -4,6 +4,8 @@ #pragma once +#include + #include #include #include @@ -22,7 +24,6 @@ #include #include #include -#include /** * Represents a differential drive style drivetrain. @@ -40,9 +41,9 @@ class Drivetrain { // Set the distance per pulse for the drive encoders. We can simply use the // distance traveled for one rotation of the wheel divided by the encoder // resolution. - m_leftEncoder.SetDistancePerPulse(2 * wpi::numbers::pi * kWheelRadius / + m_leftEncoder.SetDistancePerPulse(2 * std::numbers::pi * kWheelRadius / kEncoderResolution); - m_rightEncoder.SetDistancePerPulse(2 * wpi::numbers::pi * kWheelRadius / + m_rightEncoder.SetDistancePerPulse(2 * std::numbers::pi * kWheelRadius / kEncoderResolution); m_leftEncoder.Reset(); @@ -56,7 +57,7 @@ class Drivetrain { static constexpr units::meters_per_second_t kMaxSpeed = 3.0_mps; // 3 meters per second static constexpr units::radians_per_second_t kMaxAngularSpeed{ - wpi::numbers::pi}; // 1/2 rotation per second + std::numbers::pi}; // 1/2 rotation per second void SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds); void Drive(units::meters_per_second_t xSpeed, diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp index 3b160437136..aec97381afc 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +#include + #include #include #include @@ -15,7 +17,6 @@ #include #include #include -#include /** * This is a sample program to demonstrate how to use a state-space controller @@ -63,8 +64,8 @@ class Robot : public frc::TimedRobot { // qelms. Velocity error tolerance, in radians and radians per second. // Decrease this to more heavily penalize state excursion, or make the // controller behave more aggressively. - {1.0 * 2.0 * wpi::numbers::pi / 360.0, - 10.0 * 2.0 * wpi::numbers::pi / 360.0}, + {1.0 * 2.0 * std::numbers::pi / 360.0, + 10.0 * 2.0 * std::numbers::pi / 360.0}, // relms. Control effort (voltage) tolerance. Decrease this to more // heavily penalize control effort, or make the controller less // aggressive. 12 is a good starting point because that is the @@ -93,7 +94,7 @@ class Robot : public frc::TimedRobot { public: void RobotInit() override { // We go 2 pi radians per 4096 clicks. - m_encoder.SetDistancePerPulse(2.0 * wpi::numbers::pi / 4096.0); + m_encoder.SetDistancePerPulse(2.0 * std::numbers::pi / 4096.0); } void TeleopInit() override { diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/Constants.h index b12eef1bcb9..d8080cafd18 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/Constants.h +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/Constants.h @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +#include + #include #include #include @@ -12,7 +14,6 @@ #include #include #include -#include #pragma once @@ -43,7 +44,7 @@ constexpr int kEncoderCPR = 1024; constexpr auto kWheelDiameter = 6_in; constexpr double kEncoderDistancePerPulse = // Assumes the encoders are directly mounted on the wheel shafts - (kWheelDiameter.value() * wpi::numbers::pi) / + (kWheelDiameter.value() * std::numbers::pi) / static_cast(kEncoderCPR); // These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT! diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp index 92cca5b33de..7decddd9b23 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +#include + #include #include #include @@ -17,7 +19,6 @@ #include #include #include -#include /** * This is a sample program to demonstrate how to use a state-space controller @@ -90,7 +91,7 @@ class Robot : public frc::TimedRobot { public: void RobotInit() override { // Circumference = pi * d, so distance per click = pi * d / counts - m_encoder.SetDistancePerPulse(2.0 * wpi::numbers::pi * kDrumRadius.value() / + m_encoder.SetDistancePerPulse(2.0 * std::numbers::pi * kDrumRadius.value() / 4096.0); } diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp index 90b332df60e..5d413ab26b0 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +#include + #include #include #include @@ -14,7 +16,6 @@ #include #include #include -#include /** * This is a sample program to demonstrate how to use a state-space controller @@ -81,7 +82,7 @@ class Robot : public frc::TimedRobot { public: void RobotInit() override { // We go 2 pi radians per 4096 clicks. - m_encoder.SetDistancePerPulse(2.0 * wpi::numbers::pi / 4096.0); + m_encoder.SetDistancePerPulse(2.0 * std::numbers::pi / 4096.0); } void TeleopInit() override { diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp index 334b4d26d8a..d3bab6e7954 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +#include + #include #include #include @@ -13,7 +15,6 @@ #include #include #include -#include /** * This is a sample program to demonstrate how to use a state-space controller @@ -81,7 +82,7 @@ class Robot : public frc::TimedRobot { public: void RobotInit() override { // We go 2 pi radians per 4096 clicks. - m_encoder.SetDistancePerPulse(2.0 * wpi::numbers::pi / 4096.0); + m_encoder.SetDistancePerPulse(2.0 * std::numbers::pi / 4096.0); } void TeleopInit() override { diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/SwerveModule.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/SwerveModule.cpp index 8f98c0c209a..021c73cc146 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/SwerveModule.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/SwerveModule.cpp @@ -4,8 +4,9 @@ #include "SwerveModule.h" +#include + #include -#include SwerveModule::SwerveModule(const int driveMotorChannel, const int turningMotorChannel, @@ -20,19 +21,19 @@ SwerveModule::SwerveModule(const int driveMotorChannel, // Set the distance per pulse for the drive encoder. We can simply use the // distance traveled for one rotation of the wheel divided by the encoder // resolution. - m_driveEncoder.SetDistancePerPulse(2 * wpi::numbers::pi * kWheelRadius / + m_driveEncoder.SetDistancePerPulse(2 * std::numbers::pi * kWheelRadius / kEncoderResolution); // Set the distance (in this case, angle) per pulse for the turning encoder. - // This is the the angle through an entire rotation (2 * wpi::numbers::pi) + // This is the the angle through an entire rotation (2 * std::numbers::pi) // divided by the encoder resolution. - m_turningEncoder.SetDistancePerPulse(2 * wpi::numbers::pi / + m_turningEncoder.SetDistancePerPulse(2 * std::numbers::pi / kEncoderResolution); // Limit the PID Controller's input range between -pi and pi and set the input // to be continuous. m_turningPIDController.EnableContinuousInput( - -units::radian_t{wpi::numbers::pi}, units::radian_t{wpi::numbers::pi}); + -units::radian_t{std::numbers::pi}, units::radian_t{std::numbers::pi}); } frc::SwerveModuleState SwerveModule::GetState() const { diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/Drivetrain.h index 2b3cc0e8873..38fbdbebb5a 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/Drivetrain.h @@ -4,11 +4,12 @@ #pragma once +#include + #include #include #include #include -#include #include "SwerveModule.h" @@ -27,7 +28,7 @@ class Drivetrain { static constexpr units::meters_per_second_t kMaxSpeed = 3.0_mps; // 3 meters per second static constexpr units::radians_per_second_t kMaxAngularSpeed{ - wpi::numbers::pi}; // 1/2 rotation per second + std::numbers::pi}; // 1/2 rotation per second private: frc::Translation2d m_frontLeftLocation{+0.381_m, +0.381_m}; diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/SwerveModule.h b/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/SwerveModule.h index 00a938b83ff..71e54cd8953 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/SwerveModule.h +++ b/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/SwerveModule.h @@ -4,6 +4,8 @@ #pragma once +#include + #include #include #include @@ -14,7 +16,6 @@ #include #include #include -#include class SwerveModule { public: @@ -29,9 +30,9 @@ class SwerveModule { static constexpr int kEncoderResolution = 4096; static constexpr auto kModuleMaxAngularVelocity = - wpi::numbers::pi * 1_rad_per_s; // radians per second + std::numbers::pi * 1_rad_per_s; // radians per second static constexpr auto kModuleMaxAngularAcceleration = - wpi::numbers::pi * 2_rad_per_s / 1_s; // radians per second^2 + std::numbers::pi * 2_rad_per_s / 1_s; // radians per second^2 frc::PWMSparkMax m_driveMotor; frc::PWMSparkMax m_turningMotor; diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/RobotContainer.cpp index bea15462ded..52b25b9cb73 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/RobotContainer.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/RobotContainer.cpp @@ -66,8 +66,8 @@ frc2::Command* RobotContainer::GetAutonomousCommand() { AutoConstants::kPThetaController, 0, 0, AutoConstants::kThetaControllerConstraints}; - thetaController.EnableContinuousInput(units::radian_t{-wpi::numbers::pi}, - units::radian_t{wpi::numbers::pi}); + thetaController.EnableContinuousInput(units::radian_t{-std::numbers::pi}, + units::radian_t{std::numbers::pi}); frc2::SwerveControllerCommand<4> swerveControllerCommand( exampleTrajectory, [this]() { return m_drive.GetPose(); }, diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/SwerveModule.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/SwerveModule.cpp index aa12aafbc4b..c63187053f9 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/SwerveModule.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/SwerveModule.cpp @@ -4,8 +4,9 @@ #include "subsystems/SwerveModule.h" +#include + #include -#include #include "Constants.h" @@ -27,7 +28,7 @@ SwerveModule::SwerveModule(int driveMotorChannel, int turningMotorChannel, ModuleConstants::kDriveEncoderDistancePerPulse); // Set the distance (in this case, angle) per pulse for the turning encoder. - // This is the the angle through an entire rotation (2 * wpi::numbers::pi) + // This is the the angle through an entire rotation (2 * std::numbers::pi) // divided by the encoder resolution. m_turningEncoder.SetDistancePerPulse( ModuleConstants::kTurningEncoderDistancePerPulse); @@ -35,7 +36,7 @@ SwerveModule::SwerveModule(int driveMotorChannel, int turningMotorChannel, // Limit the PID Controller's input range between -pi and pi and set the input // to be continuous. m_turningPIDController.EnableContinuousInput( - units::radian_t{-wpi::numbers::pi}, units::radian_t{wpi::numbers::pi}); + units::radian_t{-std::numbers::pi}, units::radian_t{std::numbers::pi}); } frc::SwerveModuleState SwerveModule::GetState() { diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Constants.h index 24664517d49..cacab876c0a 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Constants.h +++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Constants.h @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +#include + #include #include #include @@ -13,7 +15,6 @@ #include #include #include -#include #pragma once @@ -77,12 +78,12 @@ constexpr int kEncoderCPR = 1024; constexpr double kWheelDiameterMeters = 0.15; constexpr double kDriveEncoderDistancePerPulse = // Assumes the encoders are directly mounted on the wheel shafts - (kWheelDiameterMeters * wpi::numbers::pi) / + (kWheelDiameterMeters * std::numbers::pi) / static_cast(kEncoderCPR); constexpr double kTurningEncoderDistancePerPulse = // Assumes the encoders are directly mounted on the wheel shafts - (wpi::numbers::pi * 2) / static_cast(kEncoderCPR); + (std::numbers::pi * 2) / static_cast(kEncoderCPR); constexpr double kPModuleTurningController = 1; constexpr double kPModuleDriveController = 1; diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/SwerveModule.h b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/SwerveModule.h index 46474456f90..f0c0a6856ee 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/SwerveModule.h +++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/SwerveModule.h @@ -4,6 +4,8 @@ #pragma once +#include + #include #include #include @@ -11,7 +13,6 @@ #include #include #include -#include #include "Constants.h" @@ -33,9 +34,9 @@ class SwerveModule { // meters per second squared. static constexpr auto kModuleMaxAngularVelocity = - units::radians_per_second_t{wpi::numbers::pi}; + units::radians_per_second_t{std::numbers::pi}; static constexpr auto kModuleMaxAngularAcceleration = - units::radians_per_second_squared_t{wpi::numbers::pi * 2.0}; + units::radians_per_second_squared_t{std::numbers::pi * 2.0}; frc::Spark m_driveMotor; frc::Spark m_turningMotor; diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/SwerveModule.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/SwerveModule.cpp index f3cfd593b5c..c822e9215b7 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/SwerveModule.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/SwerveModule.cpp @@ -4,8 +4,9 @@ #include "SwerveModule.h" +#include + #include -#include SwerveModule::SwerveModule(const int driveMotorChannel, const int turningMotorChannel, @@ -20,19 +21,19 @@ SwerveModule::SwerveModule(const int driveMotorChannel, // Set the distance per pulse for the drive encoder. We can simply use the // distance traveled for one rotation of the wheel divided by the encoder // resolution. - m_driveEncoder.SetDistancePerPulse(2 * wpi::numbers::pi * + m_driveEncoder.SetDistancePerPulse(2 * std::numbers::pi * kWheelRadius.value() / kEncoderResolution); // Set the distance (in this case, angle) per pulse for the turning encoder. - // This is the the angle through an entire rotation (2 * wpi::numbers::pi) + // This is the the angle through an entire rotation (2 * std::numbers::pi) // divided by the encoder resolution. - m_turningEncoder.SetDistancePerPulse(2 * wpi::numbers::pi / + m_turningEncoder.SetDistancePerPulse(2 * std::numbers::pi / kEncoderResolution); // Limit the PID Controller's input range between -pi and pi and set the input // to be continuous. m_turningPIDController.EnableContinuousInput( - -units::radian_t{wpi::numbers::pi}, units::radian_t{wpi::numbers::pi}); + -units::radian_t{std::numbers::pi}, units::radian_t{std::numbers::pi}); } frc::SwerveModuleState SwerveModule::GetState() const { diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/Drivetrain.h index 547ec1c96fa..3566657b90a 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/Drivetrain.h @@ -4,12 +4,13 @@ #pragma once +#include + #include #include #include #include #include -#include #include "SwerveModule.h" @@ -27,7 +28,7 @@ class Drivetrain { static constexpr auto kMaxSpeed = 3.0_mps; // 3 meters per second static constexpr units::radians_per_second_t kMaxAngularSpeed{ - wpi::numbers::pi}; // 1/2 rotation per second + std::numbers::pi}; // 1/2 rotation per second private: frc::Translation2d m_frontLeftLocation{+0.381_m, +0.381_m}; diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/SwerveModule.h b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/SwerveModule.h index 7456584730b..5242de26c1d 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/SwerveModule.h +++ b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/SwerveModule.h @@ -4,6 +4,8 @@ #pragma once +#include + #include #include #include @@ -14,7 +16,6 @@ #include #include #include -#include class SwerveModule { public: @@ -29,9 +30,9 @@ class SwerveModule { static constexpr int kEncoderResolution = 4096; static constexpr auto kModuleMaxAngularVelocity = - wpi::numbers::pi * 1_rad_per_s; // radians per second + std::numbers::pi * 1_rad_per_s; // radians per second static constexpr auto kModuleMaxAngularAcceleration = - wpi::numbers::pi * 2_rad_per_s / 1_s; // radians per second^2 + std::numbers::pi * 2_rad_per_s / 1_s; // radians per second^2 frc::PWMSparkMax m_driveMotor; frc::PWMSparkMax m_turningMotor; diff --git a/wpimath/CMakeLists.txt b/wpimath/CMakeLists.txt index 58fe93134cb..ba5d515352a 100644 --- a/wpimath/CMakeLists.txt +++ b/wpimath/CMakeLists.txt @@ -101,7 +101,7 @@ set_target_properties(wpimath PROPERTIES DEBUG_POSTFIX "d") set_property(TARGET wpimath PROPERTY FOLDER "libraries") target_compile_definitions(wpimath PRIVATE WPILIB_EXPORTS) -target_compile_features(wpimath PUBLIC cxx_std_17) +target_compile_features(wpimath PUBLIC cxx_std_20) if (MSVC) target_compile_options(wpimath PUBLIC /bigobj) endif() diff --git a/wpimath/src/dev/native/cpp/main.cpp b/wpimath/src/dev/native/cpp/main.cpp index 54952b7188f..447d3f2bce9 100644 --- a/wpimath/src/dev/native/cpp/main.cpp +++ b/wpimath/src/dev/native/cpp/main.cpp @@ -2,9 +2,10 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +#include + #include -#include int main() { - fmt::print("{}\n", wpi::numbers::pi); + fmt::print("{}\n", std::numbers::pi); } diff --git a/wpimath/src/main/native/cpp/geometry/Rotation3d.cpp b/wpimath/src/main/native/cpp/geometry/Rotation3d.cpp index 258c4c6ae19..d752afc864c 100644 --- a/wpimath/src/main/native/cpp/geometry/Rotation3d.cpp +++ b/wpimath/src/main/native/cpp/geometry/Rotation3d.cpp @@ -5,8 +5,7 @@ #include "frc/geometry/Rotation3d.h" #include - -#include +#include #include "Eigen/Core" #include "Eigen/LU" @@ -205,7 +204,7 @@ units::radian_t Rotation3d::Y() const { // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Quaternion_to_Euler_angles_conversion double ratio = 2.0 * (w * y - z * x); if (std::abs(ratio) >= 1.0) { - return units::radian_t{std::copysign(wpi::numbers::pi / 2.0, ratio)}; + return units::radian_t{std::copysign(std::numbers::pi / 2.0, ratio)}; } else { return units::radian_t{std::asin(ratio)}; } diff --git a/wpimath/src/main/native/cpp/jni/WPIMathJNI.cpp b/wpimath/src/main/native/cpp/jni/WPIMathJNI.cpp index e7ed5b36262..fd8a2236461 100644 --- a/wpimath/src/main/native/cpp/jni/WPIMathJNI.cpp +++ b/wpimath/src/main/native/cpp/jni/WPIMathJNI.cpp @@ -71,7 +71,7 @@ std::vector GetElementsFromTrajectory( return elements; } -frc::Trajectory CreateTrajectoryFromElements(wpi::span elements) { +frc::Trajectory CreateTrajectoryFromElements(std::span elements) { // Make sure that the elements have the correct length. assert(elements.size() % 7 == 0); diff --git a/wpimath/src/main/native/include/frc/MathUtil.h b/wpimath/src/main/native/include/frc/MathUtil.h index 377117170f3..24bf857b27e 100644 --- a/wpimath/src/main/native/include/frc/MathUtil.h +++ b/wpimath/src/main/native/include/frc/MathUtil.h @@ -4,8 +4,9 @@ #pragma once +#include + #include -#include #include "units/angle.h" #include "units/base.h" @@ -112,8 +113,8 @@ constexpr T InputModulus(T input, T minimumInput, T maximumInput) { WPILIB_DLLEXPORT constexpr units::radian_t AngleModulus(units::radian_t angle) { return InputModulus(angle, - units::radian_t{-wpi::numbers::pi}, - units::radian_t{wpi::numbers::pi}); + units::radian_t{-std::numbers::pi}, + units::radian_t{std::numbers::pi}); } } // namespace frc diff --git a/wpimath/src/main/native/include/frc/estimator/AngleStatistics.h b/wpimath/src/main/native/include/frc/estimator/AngleStatistics.h index e2e326b4723..0512c68cceb 100644 --- a/wpimath/src/main/native/include/frc/estimator/AngleStatistics.h +++ b/wpimath/src/main/native/include/frc/estimator/AngleStatistics.h @@ -4,7 +4,7 @@ #pragma once -#include +#include #include "frc/EigenCore.h" #include "frc/MathUtil.h" @@ -58,7 +58,7 @@ Vectord AngleAdd(const Vectord& a, const Vectord& b, int angleStateIdx) { Vectord ret = a + b; ret[angleStateIdx] = - InputModulus(ret[angleStateIdx], -wpi::numbers::pi, wpi::numbers::pi); + InputModulus(ret[angleStateIdx], -std::numbers::pi, std::numbers::pi); return ret; } diff --git a/wpimath/src/main/native/include/frc/filter/LinearFilter.h b/wpimath/src/main/native/include/frc/filter/LinearFilter.h index 303fd9bbd28..0fb4f48bbc6 100644 --- a/wpimath/src/main/native/include/frc/filter/LinearFilter.h +++ b/wpimath/src/main/native/include/frc/filter/LinearFilter.h @@ -7,12 +7,12 @@ #include #include #include +#include #include #include #include #include -#include #include "Eigen/QR" #include "frc/EigenCore.h" @@ -80,7 +80,7 @@ class LinearFilter { * @param ffGains The "feedforward" or FIR gains. * @param fbGains The "feedback" or IIR gains. */ - LinearFilter(wpi::span ffGains, wpi::span fbGains) + LinearFilter(std::span ffGains, std::span fbGains) : m_inputs(ffGains.size()), m_outputs(fbGains.size()), m_inputGains(ffGains.begin(), ffGains.end()), diff --git a/wpimath/src/main/native/include/frc/geometry/Rotation2d.h b/wpimath/src/main/native/include/frc/geometry/Rotation2d.h index 3b09fa003b0..4f9ecab4705 100644 --- a/wpimath/src/main/native/include/frc/geometry/Rotation2d.h +++ b/wpimath/src/main/native/include/frc/geometry/Rotation2d.h @@ -53,7 +53,7 @@ class WPILIB_DLLEXPORT Rotation2d { * pi. * * For example, Rotation2d{30_deg} + Rotation2d{60_deg} equals - * Rotation2d{units::radian_t{wpi::numbers::pi/2.0}} + * Rotation2d{units::radian_t{std::numbers::pi/2.0}} * * @param other The rotation to add. * @@ -66,7 +66,7 @@ class WPILIB_DLLEXPORT Rotation2d { * rotation. * * For example, Rotation2d{10_deg} - Rotation2d{100_deg} equals - * Rotation2d{units::radian_t{-wpi::numbers::pi/2.0}} + * Rotation2d{units::radian_t{-std::numbers::pi/2.0}} * * @param other The rotation to subtract. * diff --git a/wpimath/src/test/native/cpp/MathUtilTest.cpp b/wpimath/src/test/native/cpp/MathUtilTest.cpp index f226556b763..a836a77ca99 100644 --- a/wpimath/src/test/native/cpp/MathUtilTest.cpp +++ b/wpimath/src/test/native/cpp/MathUtilTest.cpp @@ -100,20 +100,20 @@ TEST(MathUtilTest, InputModulus) { TEST(MathUtilTest, AngleModulus) { EXPECT_UNITS_NEAR( - frc::AngleModulus(units::radian_t{-2000 * wpi::numbers::pi / 180}), - units::radian_t{160 * wpi::numbers::pi / 180}, 1e-10); + frc::AngleModulus(units::radian_t{-2000 * std::numbers::pi / 180}), + units::radian_t{160 * std::numbers::pi / 180}, 1e-10); EXPECT_UNITS_NEAR( - frc::AngleModulus(units::radian_t{358 * wpi::numbers::pi / 180}), - units::radian_t{-2 * wpi::numbers::pi / 180}, 1e-10); - EXPECT_UNITS_NEAR(frc::AngleModulus(units::radian_t{2.0 * wpi::numbers::pi}), + frc::AngleModulus(units::radian_t{358 * std::numbers::pi / 180}), + units::radian_t{-2 * std::numbers::pi / 180}, 1e-10); + EXPECT_UNITS_NEAR(frc::AngleModulus(units::radian_t{2.0 * std::numbers::pi}), 0_rad, 1e-10); - EXPECT_UNITS_EQ(frc::AngleModulus(units::radian_t{5 * wpi::numbers::pi}), - units::radian_t{wpi::numbers::pi}); - EXPECT_UNITS_EQ(frc::AngleModulus(units::radian_t{-5 * wpi::numbers::pi}), - units::radian_t{wpi::numbers::pi}); - EXPECT_UNITS_EQ(frc::AngleModulus(units::radian_t{wpi::numbers::pi / 2}), - units::radian_t{wpi::numbers::pi / 2}); - EXPECT_UNITS_EQ(frc::AngleModulus(units::radian_t{-wpi::numbers::pi / 2}), - units::radian_t{-wpi::numbers::pi / 2}); + EXPECT_UNITS_EQ(frc::AngleModulus(units::radian_t{5 * std::numbers::pi}), + units::radian_t{std::numbers::pi}); + EXPECT_UNITS_EQ(frc::AngleModulus(units::radian_t{-5 * std::numbers::pi}), + units::radian_t{std::numbers::pi}); + EXPECT_UNITS_EQ(frc::AngleModulus(units::radian_t{std::numbers::pi / 2}), + units::radian_t{std::numbers::pi / 2}); + EXPECT_UNITS_EQ(frc::AngleModulus(units::radian_t{-std::numbers::pi / 2}), + units::radian_t{-std::numbers::pi / 2}); } diff --git a/wpimath/src/test/native/cpp/controller/HolonomicDriveControllerTest.cpp b/wpimath/src/test/native/cpp/controller/HolonomicDriveControllerTest.cpp index cb4d793c19e..134a4e04dbd 100644 --- a/wpimath/src/test/native/cpp/controller/HolonomicDriveControllerTest.cpp +++ b/wpimath/src/test/native/cpp/controller/HolonomicDriveControllerTest.cpp @@ -2,7 +2,7 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include +#include #include "frc/MathUtil.h" #include "frc/controller/HolonomicDriveController.h" @@ -16,7 +16,7 @@ EXPECT_LE(units::math::abs(val1 - val2), eps) static constexpr units::meter_t kTolerance{1 / 12.0}; -static constexpr units::radian_t kAngularTolerance{2.0 * wpi::numbers::pi / +static constexpr units::radian_t kAngularTolerance{2.0 * std::numbers::pi / 180.0}; TEST(HolonomicDriveControllerTest, ReachesReference) { @@ -25,8 +25,8 @@ TEST(HolonomicDriveControllerTest, ReachesReference) { frc::ProfiledPIDController{ 1.0, 0.0, 0.0, frc::TrapezoidProfile::Constraints{ - units::radians_per_second_t{2.0 * wpi::numbers::pi}, - units::radians_per_second_squared_t{wpi::numbers::pi}}}}; + units::radians_per_second_t{2.0 * std::numbers::pi}, + units::radians_per_second_squared_t{std::numbers::pi}}}}; frc::Pose2d robotPose{2.7_m, 23_m, 0_deg}; diff --git a/wpimath/src/test/native/cpp/controller/LTVDifferentialDriveControllerTest.cpp b/wpimath/src/test/native/cpp/controller/LTVDifferentialDriveControllerTest.cpp index 9656a4e5bb1..753ea34a403 100644 --- a/wpimath/src/test/native/cpp/controller/LTVDifferentialDriveControllerTest.cpp +++ b/wpimath/src/test/native/cpp/controller/LTVDifferentialDriveControllerTest.cpp @@ -16,7 +16,7 @@ EXPECT_LE(units::math::abs(val1 - val2), eps) static constexpr units::meter_t kTolerance{1 / 12.0}; -static constexpr units::radian_t kAngularTolerance{2.0 * wpi::numbers::pi / +static constexpr units::radian_t kAngularTolerance{2.0 * std::numbers::pi / 180.0}; /** diff --git a/wpimath/src/test/native/cpp/controller/LTVUnicycleControllerTest.cpp b/wpimath/src/test/native/cpp/controller/LTVUnicycleControllerTest.cpp index 24e69ae2abc..56faf1d6f09 100644 --- a/wpimath/src/test/native/cpp/controller/LTVUnicycleControllerTest.cpp +++ b/wpimath/src/test/native/cpp/controller/LTVUnicycleControllerTest.cpp @@ -12,7 +12,7 @@ EXPECT_LE(units::math::abs(val1 - val2), eps) static constexpr units::meter_t kTolerance{1 / 12.0}; -static constexpr units::radian_t kAngularTolerance{2.0 * wpi::numbers::pi / +static constexpr units::radian_t kAngularTolerance{2.0 * std::numbers::pi / 180.0}; TEST(LTVUnicycleControllerTest, ReachesReference) { diff --git a/wpimath/src/test/native/cpp/controller/ProfiledPIDInputOutputTest.cpp b/wpimath/src/test/native/cpp/controller/ProfiledPIDInputOutputTest.cpp index da402ae026a..44d1f415c9f 100644 --- a/wpimath/src/test/native/cpp/controller/ProfiledPIDInputOutputTest.cpp +++ b/wpimath/src/test/native/cpp/controller/ProfiledPIDInputOutputTest.cpp @@ -2,7 +2,7 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include +#include #include "frc/controller/ProfiledPIDController.h" #include "gtest/gtest.h" @@ -40,8 +40,8 @@ TEST_F(ProfiledPIDInputOutputTest, ContinuousInput1) { TEST_F(ProfiledPIDInputOutputTest, ContinuousInput2) { controller->SetP(1); - controller->EnableContinuousInput(-units::radian_t{wpi::numbers::pi}, - units::radian_t{wpi::numbers::pi}); + controller->EnableContinuousInput(-units::radian_t{std::numbers::pi}, + units::radian_t{std::numbers::pi}); static constexpr units::radian_t kSetpoint{-3.4826633343199735}; static constexpr units::radian_t kMeasurement{-3.1352207333939606}; @@ -52,13 +52,13 @@ TEST_F(ProfiledPIDInputOutputTest, ContinuousInput2) { // Error must be less than half the input range at all times EXPECT_LT(units::math::abs(controller->GetSetpoint().position - kMeasurement), - units::radian_t{wpi::numbers::pi}); + units::radian_t{std::numbers::pi}); } TEST_F(ProfiledPIDInputOutputTest, ContinuousInput3) { controller->SetP(1); - controller->EnableContinuousInput(-units::radian_t{wpi::numbers::pi}, - units::radian_t{wpi::numbers::pi}); + controller->EnableContinuousInput(-units::radian_t{std::numbers::pi}, + units::radian_t{std::numbers::pi}); static constexpr units::radian_t kSetpoint{-3.5176604690006377}; static constexpr units::radian_t kMeasurement{3.1191729343822456}; @@ -69,13 +69,13 @@ TEST_F(ProfiledPIDInputOutputTest, ContinuousInput3) { // Error must be less than half the input range at all times EXPECT_LT(units::math::abs(controller->GetSetpoint().position - kMeasurement), - units::radian_t{wpi::numbers::pi}); + units::radian_t{std::numbers::pi}); } TEST_F(ProfiledPIDInputOutputTest, ContinuousInput4) { controller->SetP(1); controller->EnableContinuousInput(0_rad, - units::radian_t{2.0 * wpi::numbers::pi}); + units::radian_t{2.0 * std::numbers::pi}); static constexpr units::radian_t kSetpoint{2.78}; static constexpr units::radian_t kMeasurement{3.12}; @@ -86,7 +86,7 @@ TEST_F(ProfiledPIDInputOutputTest, ContinuousInput4) { // Error must be less than half the input range at all times EXPECT_LT(units::math::abs(controller->GetSetpoint().position - kMeasurement), - units::radian_t{wpi::numbers::pi}); + units::radian_t{std::numbers::pi}); } TEST_F(ProfiledPIDInputOutputTest, ProportionalGainOutput) { diff --git a/wpimath/src/test/native/cpp/controller/RamseteControllerTest.cpp b/wpimath/src/test/native/cpp/controller/RamseteControllerTest.cpp index e5f24a368fb..2fd26bbfc17 100644 --- a/wpimath/src/test/native/cpp/controller/RamseteControllerTest.cpp +++ b/wpimath/src/test/native/cpp/controller/RamseteControllerTest.cpp @@ -12,7 +12,7 @@ EXPECT_LE(units::math::abs(val1 - val2), eps) static constexpr units::meter_t kTolerance{1 / 12.0}; -static constexpr units::radian_t kAngularTolerance{2.0 * wpi::numbers::pi / +static constexpr units::radian_t kAngularTolerance{2.0 * std::numbers::pi / 180.0}; TEST(RamseteControllerTest, ReachesReference) { diff --git a/wpimath/src/test/native/cpp/estimator/AngleStatisticsTest.cpp b/wpimath/src/test/native/cpp/estimator/AngleStatisticsTest.cpp index e050cd7bb8f..b2ee87dc5ae 100644 --- a/wpimath/src/test/native/cpp/estimator/AngleStatisticsTest.cpp +++ b/wpimath/src/test/native/cpp/estimator/AngleStatisticsTest.cpp @@ -4,7 +4,7 @@ #include -#include +#include #include "frc/EigenCore.h" #include "frc/estimator/AngleStatistics.h" @@ -12,7 +12,7 @@ TEST(AngleStatisticsTest, Mean) { frc::Matrixd<3, 3> sigmas{ {1, 1.2, 0}, - {359 * wpi::numbers::pi / 180, 3 * wpi::numbers::pi / 180, 0}, + {359 * std::numbers::pi / 180, 3 * std::numbers::pi / 180, 0}, {1, 2, 0}}; // Weights need to produce the mean of the sigmas Eigen::Vector3d weights; @@ -23,16 +23,16 @@ TEST(AngleStatisticsTest, Mean) { } TEST(AngleStatisticsTest, Residual) { - Eigen::Vector3d a{1, 1 * wpi::numbers::pi / 180, 2}; - Eigen::Vector3d b{1, 359 * wpi::numbers::pi / 180, 1}; + Eigen::Vector3d a{1, 1 * std::numbers::pi / 180, 2}; + Eigen::Vector3d b{1, 359 * std::numbers::pi / 180, 1}; EXPECT_TRUE(frc::AngleResidual<3>(a, b, 1).isApprox( - Eigen::Vector3d{0, 2 * wpi::numbers::pi / 180, 1})); + Eigen::Vector3d{0, 2 * std::numbers::pi / 180, 1})); } TEST(AngleStatisticsTest, Add) { - Eigen::Vector3d a{1, 1 * wpi::numbers::pi / 180, 2}; - Eigen::Vector3d b{1, 359 * wpi::numbers::pi / 180, 1}; + Eigen::Vector3d a{1, 1 * std::numbers::pi / 180, 2}; + Eigen::Vector3d b{1, 359 * std::numbers::pi / 180, 1}; EXPECT_TRUE(frc::AngleAdd<3>(a, b, 1).isApprox(Eigen::Vector3d{2, 0, 3})); } diff --git a/wpimath/src/test/native/cpp/filter/LinearFilterNoiseTest.cpp b/wpimath/src/test/native/cpp/filter/LinearFilterNoiseTest.cpp index 5ccd829d0d8..8299a7106f2 100644 --- a/wpimath/src/test/native/cpp/filter/LinearFilterNoiseTest.cpp +++ b/wpimath/src/test/native/cpp/filter/LinearFilterNoiseTest.cpp @@ -5,10 +5,9 @@ #include "frc/filter/LinearFilter.h" // NOLINT(build/include_order) #include +#include #include -#include - #include "gtest/gtest.h" #include "units/time.h" @@ -21,7 +20,7 @@ static constexpr int32_t kMovAvgTaps = 6; enum LinearFilterNoiseTestType { kTestSinglePoleIIR, kTestMovAvg }; static double GetData(double t) { - return 100.0 * std::sin(2.0 * wpi::numbers::pi * t); + return 100.0 * std::sin(2.0 * std::numbers::pi * t); } class LinearFilterNoiseTest diff --git a/wpimath/src/test/native/cpp/filter/LinearFilterOutputTest.cpp b/wpimath/src/test/native/cpp/filter/LinearFilterOutputTest.cpp index 4f6c7d16de7..152737d3690 100644 --- a/wpimath/src/test/native/cpp/filter/LinearFilterOutputTest.cpp +++ b/wpimath/src/test/native/cpp/filter/LinearFilterOutputTest.cpp @@ -7,10 +7,10 @@ #include #include #include +#include #include #include -#include #include "gtest/gtest.h" #include "units/time.h" @@ -33,8 +33,8 @@ enum LinearFilterOutputTestType { }; static double GetData(double t) { - return 100.0 * std::sin(2.0 * wpi::numbers::pi * t) + - 20.0 * std::cos(50.0 * wpi::numbers::pi * t); + return 100.0 * std::sin(2.0 * std::numbers::pi * t) + + 20.0 * std::cos(50.0 * std::numbers::pi * t); } static double GetPulseData(double t) { diff --git a/wpimath/src/test/native/cpp/geometry/QuaternionTest.cpp b/wpimath/src/test/native/cpp/geometry/QuaternionTest.cpp index 3f235b78bd8..5b95abb7472 100644 --- a/wpimath/src/test/native/cpp/geometry/QuaternionTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/QuaternionTest.cpp @@ -2,7 +2,7 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include +#include #include "frc/geometry/Quaternion.h" #include "gtest/gtest.h" diff --git a/wpimath/src/test/native/cpp/geometry/Rotation2dTest.cpp b/wpimath/src/test/native/cpp/geometry/Rotation2dTest.cpp index 4401703a7b9..8f9e14c56b5 100644 --- a/wpimath/src/test/native/cpp/geometry/Rotation2dTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/Rotation2dTest.cpp @@ -3,8 +3,7 @@ // the WPILib BSD license file in the root directory of this project. #include - -#include +#include #include "frc/geometry/Rotation2d.h" #include "gtest/gtest.h" @@ -12,8 +11,8 @@ using namespace frc; TEST(Rotation2dTest, RadiansToDegrees) { - const Rotation2d rot1{units::radian_t{wpi::numbers::pi / 3.0}}; - const Rotation2d rot2{units::radian_t{wpi::numbers::pi / 4.0}}; + const Rotation2d rot1{units::radian_t{std::numbers::pi / 3.0}}; + const Rotation2d rot2{units::radian_t{std::numbers::pi / 4.0}}; EXPECT_DOUBLE_EQ(60.0, rot1.Degrees().value()); EXPECT_DOUBLE_EQ(45.0, rot2.Degrees().value()); @@ -23,15 +22,15 @@ TEST(Rotation2dTest, DegreesToRadians) { const auto rot1 = Rotation2d{45_deg}; const auto rot2 = Rotation2d{30_deg}; - EXPECT_DOUBLE_EQ(wpi::numbers::pi / 4.0, rot1.Radians().value()); - EXPECT_DOUBLE_EQ(wpi::numbers::pi / 6.0, rot2.Radians().value()); + EXPECT_DOUBLE_EQ(std::numbers::pi / 4.0, rot1.Radians().value()); + EXPECT_DOUBLE_EQ(std::numbers::pi / 6.0, rot2.Radians().value()); } TEST(Rotation2dTest, RotateByFromZero) { const Rotation2d zero; auto rotated = zero + Rotation2d{90_deg}; - EXPECT_DOUBLE_EQ(wpi::numbers::pi / 2.0, rotated.Radians().value()); + EXPECT_DOUBLE_EQ(std::numbers::pi / 2.0, rotated.Radians().value()); EXPECT_DOUBLE_EQ(90.0, rotated.Degrees().value()); } diff --git a/wpimath/src/test/native/cpp/geometry/Rotation3dTest.cpp b/wpimath/src/test/native/cpp/geometry/Rotation3dTest.cpp index e37abeb2f4a..4709ed0d0b0 100644 --- a/wpimath/src/test/native/cpp/geometry/Rotation3dTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/Rotation3dTest.cpp @@ -3,9 +3,9 @@ // the WPILib BSD license file in the root directory of this project. #include +#include #include -#include #include "frc/EigenCore.h" #include "frc/geometry/Rotation3d.h" @@ -15,18 +15,18 @@ using namespace frc; TEST(Rotation3dTest, InitAxisAngleAndRollPitchYaw) { const Eigen::Vector3d xAxis{1.0, 0.0, 0.0}; - const Rotation3d rot1{xAxis, units::radian_t{wpi::numbers::pi / 3}}; - const Rotation3d rot2{units::radian_t{wpi::numbers::pi / 3}, 0_rad, 0_rad}; + const Rotation3d rot1{xAxis, units::radian_t{std::numbers::pi / 3}}; + const Rotation3d rot2{units::radian_t{std::numbers::pi / 3}, 0_rad, 0_rad}; EXPECT_EQ(rot1, rot2); const Eigen::Vector3d yAxis{0.0, 1.0, 0.0}; - const Rotation3d rot3{yAxis, units::radian_t{wpi::numbers::pi / 3}}; - const Rotation3d rot4{0_rad, units::radian_t{wpi::numbers::pi / 3}, 0_rad}; + const Rotation3d rot3{yAxis, units::radian_t{std::numbers::pi / 3}}; + const Rotation3d rot4{0_rad, units::radian_t{std::numbers::pi / 3}, 0_rad}; EXPECT_EQ(rot3, rot4); const Eigen::Vector3d zAxis{0.0, 0.0, 1.0}; - const Rotation3d rot5{zAxis, units::radian_t{wpi::numbers::pi / 3}}; - const Rotation3d rot6{0_rad, 0_rad, units::radian_t{wpi::numbers::pi / 3}}; + const Rotation3d rot5{zAxis, units::radian_t{std::numbers::pi / 3}}; + const Rotation3d rot6{0_rad, 0_rad, units::radian_t{std::numbers::pi / 3}}; EXPECT_EQ(rot5, rot6); } @@ -61,12 +61,12 @@ TEST(Rotation3dTest, InitTwoVector) { // 90 degree CW rotation around y-axis const Rotation3d rot1{xAxis, zAxis}; - const Rotation3d expected1{yAxis, units::radian_t{-wpi::numbers::pi / 2.0}}; + const Rotation3d expected1{yAxis, units::radian_t{-std::numbers::pi / 2.0}}; EXPECT_EQ(expected1, rot1); // 45 degree CCW rotation around z-axis const Rotation3d rot2{xAxis, Eigen::Vector3d{1.0, 1.0, 0.0}}; - const Rotation3d expected2{zAxis, units::radian_t{wpi::numbers::pi / 4.0}}; + const Rotation3d expected2{zAxis, units::radian_t{std::numbers::pi / 4.0}}; EXPECT_EQ(expected2, rot2); // 0 degree rotation of x-axes @@ -107,12 +107,12 @@ TEST(Rotation3dTest, InitTwoVector) { TEST(Rotation3dTest, RadiansToDegrees) { const Eigen::Vector3d zAxis{0.0, 0.0, 1.0}; - const Rotation3d rot1{zAxis, units::radian_t{wpi::numbers::pi / 3}}; + const Rotation3d rot1{zAxis, units::radian_t{std::numbers::pi / 3}}; EXPECT_DOUBLE_EQ(0.0, rot1.X().value()); EXPECT_DOUBLE_EQ(0.0, rot1.Y().value()); EXPECT_DOUBLE_EQ(units::radian_t{60_deg}.value(), rot1.Z().value()); - const Rotation3d rot2{zAxis, units::radian_t{wpi::numbers::pi / 4}}; + const Rotation3d rot2{zAxis, units::radian_t{std::numbers::pi / 4}}; EXPECT_DOUBLE_EQ(0.0, rot2.X().value()); EXPECT_DOUBLE_EQ(0.0, rot2.Y().value()); EXPECT_DOUBLE_EQ(units::radian_t{45_deg}.value(), rot2.Z().value()); @@ -124,12 +124,12 @@ TEST(Rotation3dTest, DegreesToRadians) { const auto rot1 = Rotation3d{zAxis, 45_deg}; EXPECT_DOUBLE_EQ(0.0, rot1.X().value()); EXPECT_DOUBLE_EQ(0.0, rot1.Y().value()); - EXPECT_DOUBLE_EQ(wpi::numbers::pi / 4.0, rot1.Z().value()); + EXPECT_DOUBLE_EQ(std::numbers::pi / 4.0, rot1.Z().value()); const auto rot2 = Rotation3d{zAxis, 30_deg}; EXPECT_DOUBLE_EQ(0.0, rot2.X().value()); EXPECT_DOUBLE_EQ(0.0, rot2.Y().value()); - EXPECT_DOUBLE_EQ(wpi::numbers::pi / 6.0, rot2.Z().value()); + EXPECT_DOUBLE_EQ(std::numbers::pi / 6.0, rot2.Z().value()); } TEST(Rotation3dTest, RotationLoop) { @@ -228,15 +228,15 @@ TEST(Rotation3dTest, AxisAngle) { Rotation3d rot1{xAxis, 90_deg}; EXPECT_EQ(xAxis, rot1.Axis()); - EXPECT_DOUBLE_EQ(wpi::numbers::pi / 2.0, rot1.Angle().value()); + EXPECT_DOUBLE_EQ(std::numbers::pi / 2.0, rot1.Angle().value()); Rotation3d rot2{yAxis, 45_deg}; EXPECT_EQ(yAxis, rot2.Axis()); - EXPECT_DOUBLE_EQ(wpi::numbers::pi / 4.0, rot2.Angle().value()); + EXPECT_DOUBLE_EQ(std::numbers::pi / 4.0, rot2.Angle().value()); Rotation3d rot3{zAxis, 60_deg}; EXPECT_EQ(zAxis, rot3.Axis()); - EXPECT_DOUBLE_EQ(wpi::numbers::pi / 3.0, rot3.Angle().value()); + EXPECT_DOUBLE_EQ(std::numbers::pi / 3.0, rot3.Angle().value()); } TEST(Rotation3dTest, ToRotation2d) { diff --git a/wpimath/src/test/native/cpp/geometry/Twist2dTest.cpp b/wpimath/src/test/native/cpp/geometry/Twist2dTest.cpp index f10d0265e24..5e5c4609aa5 100644 --- a/wpimath/src/test/native/cpp/geometry/Twist2dTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/Twist2dTest.cpp @@ -3,8 +3,7 @@ // the WPILib BSD license file in the root directory of this project. #include - -#include +#include #include "frc/geometry/Pose2d.h" #include "gtest/gtest.h" @@ -21,8 +20,8 @@ TEST(Twist2dTest, Straight) { } TEST(Twist2dTest, QuarterCircle) { - const Twist2d quarterCircle{5_m / 2.0 * wpi::numbers::pi, 0_m, - units::radian_t{wpi::numbers::pi / 2.0}}; + const Twist2d quarterCircle{5_m / 2.0 * std::numbers::pi, 0_m, + units::radian_t{std::numbers::pi / 2.0}}; const auto quarterCirclePose = Pose2d{}.Exp(quarterCircle); EXPECT_DOUBLE_EQ(5.0, quarterCirclePose.X().value()); @@ -57,8 +56,8 @@ TEST(Twist2dTest, Pose2dLog) { const auto twist = start.Log(end); - Twist2d expected{units::meter_t{5.0 / 2.0 * wpi::numbers::pi}, 0_m, - units::radian_t{wpi::numbers::pi / 2.0}}; + Twist2d expected{units::meter_t{5.0 / 2.0 * std::numbers::pi}, 0_m, + units::radian_t{std::numbers::pi / 2.0}}; EXPECT_EQ(expected, twist); // Make sure computed twist gives back original end pose diff --git a/wpimath/src/test/native/cpp/geometry/Twist3dTest.cpp b/wpimath/src/test/native/cpp/geometry/Twist3dTest.cpp index da53d730e24..559b7225cc7 100644 --- a/wpimath/src/test/native/cpp/geometry/Twist3dTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/Twist3dTest.cpp @@ -3,8 +3,7 @@ // the WPILib BSD license file in the root directory of this project. #include - -#include +#include #include "frc/geometry/Pose3d.h" #include "gtest/gtest.h" @@ -39,8 +38,8 @@ TEST(Twist3dTest, QuarterCircle) { Eigen::Vector3d zAxis{0.0, 0.0, 1.0}; const Twist3d quarterCircle{ - 5_m / 2.0 * wpi::numbers::pi, 0_m, 0_m, 0_rad, 0_rad, - units::radian_t{wpi::numbers::pi / 2.0}}; + 5_m / 2.0 * std::numbers::pi, 0_m, 0_m, 0_rad, 0_rad, + units::radian_t{std::numbers::pi / 2.0}}; const auto quarterCirclePose = Pose3d{}.Exp(quarterCircle); Pose3d expected{5_m, 5_m, 0_m, Rotation3d{zAxis, 90_deg}}; @@ -73,7 +72,7 @@ TEST(Twist3dTest, Pose3dLogX) { const auto twist = start.Log(end); - Twist3d expected{0_m, units::meter_t{5.0 / 2.0 * wpi::numbers::pi}, + Twist3d expected{0_m, units::meter_t{5.0 / 2.0 * std::numbers::pi}, 0_m, 90_deg, 0_deg, 0_deg}; EXPECT_EQ(expected, twist); @@ -89,7 +88,7 @@ TEST(Twist3dTest, Pose3dLogY) { const auto twist = start.Log(end); - Twist3d expected{0_m, 0_m, units::meter_t{5.0 / 2.0 * wpi::numbers::pi}, + Twist3d expected{0_m, 0_m, units::meter_t{5.0 / 2.0 * std::numbers::pi}, 0_deg, 90_deg, 0_deg}; EXPECT_EQ(expected, twist); @@ -104,7 +103,7 @@ TEST(Twist3dTest, Pose3dLogZ) { const auto twist = start.Log(end); - Twist3d expected{units::meter_t{5.0 / 2.0 * wpi::numbers::pi}, + Twist3d expected{units::meter_t{5.0 / 2.0 * std::numbers::pi}, 0_m, 0_m, 0_deg, diff --git a/wpimath/src/test/native/cpp/kinematics/DifferentialDriveKinematicsTest.cpp b/wpimath/src/test/native/cpp/kinematics/DifferentialDriveKinematicsTest.cpp index 321e356236b..4af5ac8a49e 100644 --- a/wpimath/src/test/native/cpp/kinematics/DifferentialDriveKinematicsTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/DifferentialDriveKinematicsTest.cpp @@ -2,7 +2,7 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include +#include #include "frc/kinematics/ChassisSpeeds.h" #include "frc/kinematics/DifferentialDriveKinematics.h" @@ -56,21 +56,21 @@ TEST(DifferentialDriveKinematicsTest, ForwardKinematicsForStraightLine) { TEST(DifferentialDriveKinematicsTest, InverseKinematicsForRotateInPlace) { const DifferentialDriveKinematics kinematics{0.381_m * 2}; const ChassisSpeeds chassisSpeeds{ - 0.0_mps, 0.0_mps, units::radians_per_second_t{wpi::numbers::pi}}; + 0.0_mps, 0.0_mps, units::radians_per_second_t{std::numbers::pi}}; const auto wheelSpeeds = kinematics.ToWheelSpeeds(chassisSpeeds); - EXPECT_NEAR(wheelSpeeds.left.value(), -0.381 * wpi::numbers::pi, kEpsilon); - EXPECT_NEAR(wheelSpeeds.right.value(), +0.381 * wpi::numbers::pi, kEpsilon); + EXPECT_NEAR(wheelSpeeds.left.value(), -0.381 * std::numbers::pi, kEpsilon); + EXPECT_NEAR(wheelSpeeds.right.value(), +0.381 * std::numbers::pi, kEpsilon); } TEST(DifferentialDriveKinematicsTest, ForwardKinematicsForRotateInPlace) { const DifferentialDriveKinematics kinematics{0.381_m * 2}; const DifferentialDriveWheelSpeeds wheelSpeeds{ - units::meters_per_second_t{+0.381 * wpi::numbers::pi}, - units::meters_per_second_t{-0.381 * wpi::numbers::pi}}; + units::meters_per_second_t{+0.381 * std::numbers::pi}, + units::meters_per_second_t{-0.381 * std::numbers::pi}}; const auto chassisSpeeds = kinematics.ToChassisSpeeds(wheelSpeeds); EXPECT_NEAR(chassisSpeeds.vx.value(), 0, kEpsilon); EXPECT_NEAR(chassisSpeeds.vy.value(), 0, kEpsilon); - EXPECT_NEAR(chassisSpeeds.omega.value(), -wpi::numbers::pi, kEpsilon); + EXPECT_NEAR(chassisSpeeds.omega.value(), -std::numbers::pi, kEpsilon); } diff --git a/wpimath/src/test/native/cpp/kinematics/DifferentialDriveOdometryTest.cpp b/wpimath/src/test/native/cpp/kinematics/DifferentialDriveOdometryTest.cpp index a74723c04f8..276f89d8d48 100644 --- a/wpimath/src/test/native/cpp/kinematics/DifferentialDriveOdometryTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/DifferentialDriveOdometryTest.cpp @@ -2,7 +2,7 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include +#include #include "frc/kinematics/DifferentialDriveKinematics.h" #include "frc/kinematics/DifferentialDriveOdometry.h" @@ -16,7 +16,7 @@ TEST(DifferentialDriveOdometryTest, EncoderDistances) { DifferentialDriveOdometry odometry{45_deg}; const auto& pose = - odometry.Update(135_deg, 0_m, units::meter_t{5 * wpi::numbers::pi}); + odometry.Update(135_deg, 0_m, units::meter_t{5 * std::numbers::pi}); EXPECT_NEAR(pose.X().value(), 5.0, kEpsilon); EXPECT_NEAR(pose.Y().value(), 5.0, kEpsilon); diff --git a/wpimath/src/test/native/cpp/kinematics/MecanumDriveKinematicsTest.cpp b/wpimath/src/test/native/cpp/kinematics/MecanumDriveKinematicsTest.cpp index 05766a52a74..91c88de40f6 100644 --- a/wpimath/src/test/native/cpp/kinematics/MecanumDriveKinematicsTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/MecanumDriveKinematicsTest.cpp @@ -2,7 +2,7 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include +#include #include "frc/geometry/Translation2d.h" #include "frc/kinematics/MecanumDriveKinematics.h" @@ -61,7 +61,7 @@ TEST_F(MecanumDriveKinematicsTest, StrafeForwardKinematics) { TEST_F(MecanumDriveKinematicsTest, RotationInverseKinematics) { ChassisSpeeds speeds{0_mps, 0_mps, - units::radians_per_second_t{2 * wpi::numbers::pi}}; + units::radians_per_second_t{2 * std::numbers::pi}}; auto moduleStates = kinematics.ToWheelSpeeds(speeds); EXPECT_NEAR(-150.79644737, moduleStates.frontLeft.value(), 0.1); @@ -77,7 +77,7 @@ TEST_F(MecanumDriveKinematicsTest, RotationForwardKinematics) { EXPECT_NEAR(0.0, chassisSpeeds.vx.value(), 0.1); EXPECT_NEAR(0.0, chassisSpeeds.vy.value(), 0.1); - EXPECT_NEAR(2 * wpi::numbers::pi, chassisSpeeds.omega.value(), 0.1); + EXPECT_NEAR(2 * std::numbers::pi, chassisSpeeds.omega.value(), 0.1); } TEST_F(MecanumDriveKinematicsTest, MixedRotationTranslationInverseKinematics) { diff --git a/wpimath/src/test/native/cpp/kinematics/SwerveDriveKinematicsTest.cpp b/wpimath/src/test/native/cpp/kinematics/SwerveDriveKinematicsTest.cpp index 6aafbc2a528..b958b76b169 100644 --- a/wpimath/src/test/native/cpp/kinematics/SwerveDriveKinematicsTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/SwerveDriveKinematicsTest.cpp @@ -2,7 +2,7 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include +#include #include "frc/geometry/Translation2d.h" #include "frc/kinematics/SwerveDriveKinematics.h" @@ -75,7 +75,7 @@ TEST_F(SwerveDriveKinematicsTest, StraightStrafeForwardKinematics) { TEST_F(SwerveDriveKinematicsTest, TurnInPlaceInverseKinematics) { ChassisSpeeds speeds{0_mps, 0_mps, - units::radians_per_second_t{2 * wpi::numbers::pi}}; + units::radians_per_second_t{2 * std::numbers::pi}}; auto [fl, fr, bl, br] = m_kinematics.ToSwerveModuleStates(speeds); EXPECT_NEAR(fl.speed.value(), 106.63, kEpsilon); @@ -91,7 +91,7 @@ TEST_F(SwerveDriveKinematicsTest, TurnInPlaceInverseKinematics) { TEST_F(SwerveDriveKinematicsTest, ConserveWheelAngle) { ChassisSpeeds speeds{0_mps, 0_mps, - units::radians_per_second_t{2 * wpi::numbers::pi}}; + units::radians_per_second_t{2 * std::numbers::pi}}; m_kinematics.ToSwerveModuleStates(speeds); auto [fl, fr, bl, br] = m_kinematics.ToSwerveModuleStates(ChassisSpeeds{}); @@ -116,12 +116,12 @@ TEST_F(SwerveDriveKinematicsTest, TurnInPlaceForwardKinematics) { EXPECT_NEAR(chassisSpeeds.vx.value(), 0.0, kEpsilon); EXPECT_NEAR(chassisSpeeds.vy.value(), 0.0, kEpsilon); - EXPECT_NEAR(chassisSpeeds.omega.value(), 2 * wpi::numbers::pi, kEpsilon); + EXPECT_NEAR(chassisSpeeds.omega.value(), 2 * std::numbers::pi, kEpsilon); } TEST_F(SwerveDriveKinematicsTest, OffCenterCORRotationInverseKinematics) { ChassisSpeeds speeds{0_mps, 0_mps, - units::radians_per_second_t{2 * wpi::numbers::pi}}; + units::radians_per_second_t{2 * std::numbers::pi}}; auto [fl, fr, bl, br] = m_kinematics.ToSwerveModuleStates(speeds, m_fl); EXPECT_NEAR(fl.speed.value(), 0.0, kEpsilon); @@ -145,7 +145,7 @@ TEST_F(SwerveDriveKinematicsTest, OffCenterCORRotationForwardKinematics) { EXPECT_NEAR(chassisSpeeds.vx.value(), 75.398, kEpsilon); EXPECT_NEAR(chassisSpeeds.vy.value(), -75.398, kEpsilon); - EXPECT_NEAR(chassisSpeeds.omega.value(), 2 * wpi::numbers::pi, kEpsilon); + EXPECT_NEAR(chassisSpeeds.omega.value(), 2 * std::numbers::pi, kEpsilon); } TEST_F(SwerveDriveKinematicsTest, diff --git a/wpinet/CMakeLists.txt b/wpinet/CMakeLists.txt index 7fd19c753b7..3994f8bd5d9 100644 --- a/wpinet/CMakeLists.txt +++ b/wpinet/CMakeLists.txt @@ -122,7 +122,7 @@ set_target_properties(wpinet PROPERTIES DEBUG_POSTFIX "d") set_property(TARGET wpinet PROPERTY FOLDER "libraries") -target_compile_features(wpinet PUBLIC cxx_std_17) +target_compile_features(wpinet PUBLIC cxx_std_20) wpilib_target_warnings(wpinet) target_link_libraries(wpinet PUBLIC wpiutil) diff --git a/wpinet/src/main/native/cpp/HttpServerConnection.cpp b/wpinet/src/main/native/cpp/HttpServerConnection.cpp index 99670175279..313ee2b0678 100644 --- a/wpinet/src/main/native/cpp/HttpServerConnection.cpp +++ b/wpinet/src/main/native/cpp/HttpServerConnection.cpp @@ -85,7 +85,7 @@ void HttpServerConnection::BuildHeader(raw_ostream& os, int code, os << "\r\n"; // header ends with a blank line } -void HttpServerConnection::SendData(span bufs, +void HttpServerConnection::SendData(std::span bufs, bool closeAfter) { m_stream.Write(bufs, [closeAfter, stream = &m_stream](auto bufs, uv::Error) { for (auto&& buf : bufs) { diff --git a/wpinet/src/main/native/cpp/HttpUtil.cpp b/wpinet/src/main/native/cpp/HttpUtil.cpp index c4de9d06728..12ff0841bfe 100644 --- a/wpinet/src/main/native/cpp/HttpUtil.cpp +++ b/wpinet/src/main/native/cpp/HttpUtil.cpp @@ -132,7 +132,7 @@ HttpPath::HttpPath(std::string_view path) { } bool HttpPath::startswith(size_t start, - span match) const { + std::span match) const { if (m_pathEnds.size() < (start + match.size())) { return false; } diff --git a/wpinet/src/main/native/cpp/ParallelTcpConnector.cpp b/wpinet/src/main/native/cpp/ParallelTcpConnector.cpp index f60a3ca6c97..69a3cb3f259 100644 --- a/wpinet/src/main/native/cpp/ParallelTcpConnector.cpp +++ b/wpinet/src/main/native/cpp/ParallelTcpConnector.cpp @@ -40,7 +40,7 @@ void ParallelTcpConnector::Close() { } void ParallelTcpConnector::SetServers( - wpi::span> servers) { + std::span> servers) { m_servers.assign(servers.begin(), servers.end()); if (!IsConnected()) { Connect(); diff --git a/wpinet/src/main/native/cpp/UDPClient.cpp b/wpinet/src/main/native/cpp/UDPClient.cpp index e13463c5b56..b2f29e0938b 100644 --- a/wpinet/src/main/native/cpp/UDPClient.cpp +++ b/wpinet/src/main/native/cpp/UDPClient.cpp @@ -134,7 +134,7 @@ void UDPClient::shutdown() { } } -int UDPClient::send(span data, std::string_view server, +int UDPClient::send(std::span data, std::string_view server, int port) { // server must be a resolvable IP address struct sockaddr_in addr; diff --git a/wpinet/src/main/native/cpp/WebSocket.cpp b/wpinet/src/main/native/cpp/WebSocket.cpp index 369722d9639..ba57925a552 100644 --- a/wpinet/src/main/native/cpp/WebSocket.cpp +++ b/wpinet/src/main/native/cpp/WebSocket.cpp @@ -24,7 +24,7 @@ namespace { class WebSocketWriteReq : public uv::WriteReq { public: explicit WebSocketWriteReq( - std::function, uv::Error)> callback) + std::function, uv::Error)> callback) : m_callback{std::move(callback)} { finish.connect([this](uv::Error err) { for (auto&& buf : m_internalBufs) { @@ -34,7 +34,7 @@ class WebSocketWriteReq : public uv::WriteReq { }); } - std::function, uv::Error)> m_callback; + std::function, uv::Error)> m_callback; SmallVector m_internalBufs; SmallVector m_userBufs; }; @@ -105,7 +105,7 @@ WebSocket::~WebSocket() = default; std::shared_ptr WebSocket::CreateClient( uv::Stream& stream, std::string_view uri, std::string_view host, - span protocols, const ClientOptions& options) { + std::span protocols, const ClientOptions& options) { auto ws = std::make_shared(stream, false, private_init{}); stream.SetData(ws); ws->StartClient(uri, host, protocols, options); @@ -147,7 +147,7 @@ void WebSocket::Terminate(uint16_t code, std::string_view reason) { } void WebSocket::StartClient(std::string_view uri, std::string_view host, - span protocols, + std::span protocols, const ClientOptions& options) { // Create client handshake data m_clientHandshake = std::make_unique(); @@ -323,7 +323,7 @@ void WebSocket::SendClose(uint16_t code, std::string_view reason) { raw_uv_ostream os{bufs, 4096}; const uint8_t codeMsb[] = {static_cast((code >> 8) & 0xff), static_cast(code & 0xff)}; - os << span{codeMsb}; + os << std::span{codeMsb}; os << reason; } Send(kFlagFin | kOpClose, bufs, [](auto bufs, uv::Error) { @@ -465,7 +465,7 @@ void WebSocket::HandleIncoming(uv::Buffer& buf, size_t size) { m_header[m_headerSize - 4], m_header[m_headerSize - 3], m_header[m_headerSize - 2], m_header[m_headerSize - 1]}; int n = 0; - for (uint8_t& ch : span{m_payload}.subspan(m_frameStart)) { + for (uint8_t& ch : std::span{m_payload}.subspan(m_frameStart)) { ch ^= key[n++]; if (n >= 4) { n = 0; @@ -596,7 +596,7 @@ void WebSocket::HandleIncoming(uv::Buffer& buf, size_t size) { static void WriteFrame(WebSocketWriteReq& req, SmallVectorImpl& bufs, bool server, - uint8_t opcode, span data) { + uint8_t opcode, std::span data) { SmallVector internalBufs; raw_uv_ostream os{internalBufs, 4096}; @@ -633,7 +633,7 @@ static void WriteFrame(WebSocketWriteReq& req, os << static_cast((server ? 0x00 : kFlagMasking) | 126); const uint8_t sizeMsb[] = {static_cast((size >> 8) & 0xff), static_cast(size & 0xff)}; - os << span{sizeMsb}; + os << std::span{sizeMsb}; } else { os << static_cast((server ? 0x00 : kFlagMasking) | 127); const uint8_t sizeMsb[] = {static_cast((size >> 56) & 0xff), @@ -644,7 +644,7 @@ static void WriteFrame(WebSocketWriteReq& req, static_cast((size >> 16) & 0xff), static_cast((size >> 8) & 0xff), static_cast(size & 0xff)}; - os << span{sizeMsb}; + os << std::span{sizeMsb}; } // clients need to mask the input data @@ -657,7 +657,7 @@ static void WriteFrame(WebSocketWriteReq& req, for (uint8_t& v : key) { v = dist(gen); } - os << span{key, 4}; + os << std::span{key, 4}; // copy and mask data int n = 0; for (auto&& buf : data) { @@ -680,8 +680,8 @@ static void WriteFrame(WebSocketWriteReq& req, } void WebSocket::SendFrames( - span frames, - std::function, uv::Error)> callback) { + std::span frames, + std::function, uv::Error)> callback) { // If we're not open, emit an error and don't send the data if (m_state != OPEN) { int err; diff --git a/wpinet/src/main/native/cpp/WebSocketServer.cpp b/wpinet/src/main/native/cpp/WebSocketServer.cpp index 6a87d8f6339..09424bb3112 100644 --- a/wpinet/src/main/native/cpp/WebSocketServer.cpp +++ b/wpinet/src/main/native/cpp/WebSocketServer.cpp @@ -47,7 +47,7 @@ WebSocketServerHelper::WebSocketServerHelper(HttpParser& req) { } std::pair WebSocketServerHelper::MatchProtocol( - span protocols) { + std::span protocols) { if (protocols.empty() && m_protocols.empty()) { return {true, {}}; } @@ -62,7 +62,7 @@ std::pair WebSocketServerHelper::MatchProtocol( } WebSocketServer::WebSocketServer(uv::Stream& stream, - span protocols, + std::span protocols, ServerOptions options, const private_init&) : m_stream{stream}, m_helper{m_req}, @@ -139,7 +139,7 @@ WebSocketServer::WebSocketServer(uv::Stream& stream, } std::shared_ptr WebSocketServer::Create( - uv::Stream& stream, span protocols, + uv::Stream& stream, std::span protocols, const ServerOptions& options) { auto server = std::make_shared(stream, protocols, options, private_init{}); diff --git a/wpinet/src/main/native/cpp/uv/Process.cpp b/wpinet/src/main/native/cpp/uv/Process.cpp index b97d9fc02dc..3c10db60321 100644 --- a/wpinet/src/main/native/cpp/uv/Process.cpp +++ b/wpinet/src/main/native/cpp/uv/Process.cpp @@ -12,7 +12,7 @@ namespace wpi::uv { std::shared_ptr Process::SpawnArray(Loop& loop, std::string_view file, - span options) { + std::span options) { // convert Option array to libuv structure uv_process_options_t coptions; diff --git a/wpinet/src/main/native/cpp/uv/Stream.cpp b/wpinet/src/main/native/cpp/uv/Stream.cpp index 3b00040b1c4..e7f6031a3d0 100644 --- a/wpinet/src/main/native/cpp/uv/Stream.cpp +++ b/wpinet/src/main/native/cpp/uv/Stream.cpp @@ -12,8 +12,8 @@ using namespace wpi::uv; namespace { class CallbackWriteReq : public WriteReq { public: - CallbackWriteReq(span bufs, - std::function, Error)> callback) + CallbackWriteReq(std::span bufs, + std::function, Error)> callback) : m_bufs{bufs.begin(), bufs.end()} { finish.connect( [this, f = std::move(callback)](Error err) { f(m_bufs, err); }); @@ -77,7 +77,7 @@ void Stream::StartRead() { }); } -void Stream::Write(span bufs, +void Stream::Write(std::span bufs, const std::shared_ptr& req) { if (Invoke(&uv_write, req->GetRaw(), GetRawStream(), bufs.data(), bufs.size(), [](uv_write_t* r, int status) { @@ -92,12 +92,12 @@ void Stream::Write(span bufs, } } -void Stream::Write(span bufs, - std::function, Error)> callback) { +void Stream::Write(std::span bufs, + std::function, Error)> callback) { Write(bufs, std::make_shared(bufs, std::move(callback))); } -int Stream::TryWrite(span bufs) { +int Stream::TryWrite(std::span bufs) { int val = uv_try_write(GetRawStream(), bufs.data(), bufs.size()); if (val < 0) { this->ReportError(val); @@ -106,7 +106,7 @@ int Stream::TryWrite(span bufs) { return val; } -int Stream::TryWrite2(span bufs, Stream& send) { +int Stream::TryWrite2(std::span bufs, Stream& send) { int val = uv_try_write2(GetRawStream(), bufs.data(), bufs.size(), send.GetRawStream()); if (val < 0) { diff --git a/wpinet/src/main/native/cpp/uv/Udp.cpp b/wpinet/src/main/native/cpp/uv/Udp.cpp index 2e580201002..689d5a72f5f 100644 --- a/wpinet/src/main/native/cpp/uv/Udp.cpp +++ b/wpinet/src/main/native/cpp/uv/Udp.cpp @@ -18,8 +18,8 @@ using namespace wpi::uv; class CallbackUdpSendReq : public UdpSendReq { public: - CallbackUdpSendReq(span bufs, - std::function, Error)> callback) + CallbackUdpSendReq(std::span bufs, + std::function, Error)> callback) : m_bufs{bufs.begin(), bufs.end()} { complete.connect( [this, f = std::move(callback)](Error err) { f(m_bufs, err); }); @@ -133,7 +133,7 @@ void Udp::SetMulticastInterface(std::string_view interfaceAddr) { Invoke(&uv_udp_set_multicast_interface, GetRaw(), interfaceAddrBuf.c_str()); } -void Udp::Send(const sockaddr& addr, span bufs, +void Udp::Send(const sockaddr& addr, std::span bufs, const std::shared_ptr& req) { if (Invoke(&uv_udp_send, req->GetRaw(), GetRaw(), bufs.data(), bufs.size(), &addr, [](uv_udp_send_t* r, int status) { @@ -148,13 +148,13 @@ void Udp::Send(const sockaddr& addr, span bufs, } } -void Udp::Send(const sockaddr& addr, span bufs, - std::function, Error)> callback) { +void Udp::Send(const sockaddr& addr, std::span bufs, + std::function, Error)> callback) { Send(addr, bufs, std::make_shared(bufs, std::move(callback))); } -void Udp::Send(span bufs, +void Udp::Send(std::span bufs, const std::shared_ptr& req) { if (Invoke(&uv_udp_send, req->GetRaw(), GetRaw(), bufs.data(), bufs.size(), nullptr, [](uv_udp_send_t* r, int status) { @@ -169,8 +169,8 @@ void Udp::Send(span bufs, } } -void Udp::Send(span bufs, - std::function, Error)> callback) { +void Udp::Send(std::span bufs, + std::function, Error)> callback) { Send(bufs, std::make_shared(bufs, std::move(callback))); } diff --git a/wpinet/src/main/native/include/wpinet/HttpServerConnection.h b/wpinet/src/main/native/include/wpinet/HttpServerConnection.h index 4e3b509e567..486f36ed647 100644 --- a/wpinet/src/main/native/include/wpinet/HttpServerConnection.h +++ b/wpinet/src/main/native/include/wpinet/HttpServerConnection.h @@ -6,10 +6,9 @@ #define WPINET_HTTPSERVERCONNECTION_H_ #include +#include #include -#include - #include "wpinet/HttpParser.h" #include "wpinet/uv/Stream.h" @@ -79,7 +78,7 @@ class HttpServerConnection { * is desired, call m_stream.Write() directly instead. * @param closeAfter close the connection after the write completes */ - void SendData(span bufs, bool closeAfter = false); + void SendData(std::span bufs, bool closeAfter = false); /** * Send HTTP response, along with other header information like mimetype. diff --git a/wpinet/src/main/native/include/wpinet/HttpUtil.h b/wpinet/src/main/native/include/wpinet/HttpUtil.h index e3d65bf8ec6..fcf68871a4c 100644 --- a/wpinet/src/main/native/include/wpinet/HttpUtil.h +++ b/wpinet/src/main/native/include/wpinet/HttpUtil.h @@ -8,6 +8,7 @@ #include #include #include +#include #include #include #include @@ -17,7 +18,6 @@ #include #include #include -#include #include "wpinet/NetworkStream.h" #include "wpinet/raw_socket_istream.h" @@ -146,7 +146,7 @@ class HttpPath { bool equals(std::initializer_list match) const { return equals(0, {match.begin(), match.end()}); } - bool equals(span match) const { + bool equals(std::span match) const { return equals(0, match); } bool equals(std::string_view match) const { return equals(0, {match}); } @@ -163,7 +163,7 @@ class HttpPath { std::initializer_list match) const { return equals(start, {match.begin(), match.end()}); } - bool equals(size_t start, span match) const { + bool equals(size_t start, std::span match) const { if (m_pathEnds.size() != (start + match.size())) { return false; } @@ -183,7 +183,7 @@ class HttpPath { bool startswith(std::initializer_list match) const { return startswith(0, {match.begin(), match.end()}); } - bool startswith(span match) const { + bool startswith(std::span match) const { return startswith(0, match); } bool startswith(std::string_view match) const { @@ -203,7 +203,7 @@ class HttpPath { return startswith(start, {match.begin(), match.end()}); } - bool startswith(size_t start, span match) const; + bool startswith(size_t start, std::span match) const; bool startswith(size_t start, std::string_view match) const { return startswith(start, {match}); @@ -241,7 +241,7 @@ class HttpPathRef { bool equals(std::initializer_list match) const { return equals(0, {match.begin(), match.end()}); } - bool equals(span match) const { + bool equals(std::span match) const { return equals(0, match); } bool equals(std::string_view match) const { return equals(0, {match}); } @@ -250,7 +250,7 @@ class HttpPathRef { std::initializer_list match) const { return equals(start, {match.begin(), match.end()}); } - bool equals(size_t start, span match) const { + bool equals(size_t start, std::span match) const { return m_path ? m_path->equals(m_start + start, match) : false; } bool equals(size_t start, std::string_view match) const { @@ -260,7 +260,7 @@ class HttpPathRef { bool startswith(std::initializer_list match) const { return startswith(0, {match.begin(), match.end()}); } - bool startswith(span match) const { + bool startswith(std::span match) const { return startswith(0, match); } bool startswith(std::string_view match) const { @@ -271,7 +271,7 @@ class HttpPathRef { std::initializer_list match) const { return startswith(start, {match.begin(), match.end()}); } - bool startswith(size_t start, span match) const { + bool startswith(size_t start, std::span match) const { return m_path ? m_path->startswith(m_start + start, match) : false; } bool startswith(size_t start, std::string_view match) const { diff --git a/wpinet/src/main/native/include/wpinet/HttpWebSocketServerConnection.h b/wpinet/src/main/native/include/wpinet/HttpWebSocketServerConnection.h index f860e91e19e..4095a9ca460 100644 --- a/wpinet/src/main/native/include/wpinet/HttpWebSocketServerConnection.h +++ b/wpinet/src/main/native/include/wpinet/HttpWebSocketServerConnection.h @@ -7,11 +7,11 @@ #include #include +#include #include #include #include -#include #include "wpinet/HttpServerConnection.h" #include "wpinet/WebSocket.h" @@ -37,7 +37,7 @@ class HttpWebSocketServerConnection * @param protocols Acceptable subprotocols */ HttpWebSocketServerConnection(std::shared_ptr stream, - span protocols); + std::span protocols); /** * Constructor. diff --git a/wpinet/src/main/native/include/wpinet/HttpWebSocketServerConnection.inc b/wpinet/src/main/native/include/wpinet/HttpWebSocketServerConnection.inc index c26c864a0eb..750439de2d9 100644 --- a/wpinet/src/main/native/include/wpinet/HttpWebSocketServerConnection.inc +++ b/wpinet/src/main/native/include/wpinet/HttpWebSocketServerConnection.inc @@ -13,7 +13,8 @@ namespace wpi { template HttpWebSocketServerConnection::HttpWebSocketServerConnection( - std::shared_ptr stream, span protocols) + std::shared_ptr stream, + std::span protocols) : HttpServerConnection{stream}, m_helper{m_request}, m_protocols{protocols.begin(), protocols.end()} { diff --git a/wpinet/src/main/native/include/wpinet/MulticastServiceAnnouncer.h b/wpinet/src/main/native/include/wpinet/MulticastServiceAnnouncer.h index 68bcb672a0b..2892919e036 100644 --- a/wpinet/src/main/native/include/wpinet/MulticastServiceAnnouncer.h +++ b/wpinet/src/main/native/include/wpinet/MulticastServiceAnnouncer.h @@ -8,20 +8,19 @@ #ifdef __cplusplus #include +#include #include #include #include - -#include namespace wpi { class MulticastServiceAnnouncer { public: MulticastServiceAnnouncer( std::string_view serviceName, std::string_view serviceType, int port, - wpi::span> txt); + std::span> txt); MulticastServiceAnnouncer( std::string_view serviceName, std::string_view serviceType, int port, - wpi::span> txt); + std::span> txt); MulticastServiceAnnouncer(std::string_view serviceName, std::string_view serviceType, int port); ~MulticastServiceAnnouncer() noexcept; @@ -34,9 +33,6 @@ class MulticastServiceAnnouncer { std::unique_ptr pImpl; }; } // namespace wpi -#endif - -#ifdef __cplusplus extern "C" { #endif diff --git a/wpinet/src/main/native/include/wpinet/MulticastServiceResolver.h b/wpinet/src/main/native/include/wpinet/MulticastServiceResolver.h index 57835dc0f8f..f46a8e4bd8c 100644 --- a/wpinet/src/main/native/include/wpinet/MulticastServiceResolver.h +++ b/wpinet/src/main/native/include/wpinet/MulticastServiceResolver.h @@ -15,7 +15,6 @@ #include #include -#include namespace wpi { class MulticastServiceResolver { public: @@ -56,9 +55,6 @@ class MulticastServiceResolver { std::unique_ptr pImpl; }; } // namespace wpi -#endif - -#ifdef __cplusplus extern "C" { #endif diff --git a/wpinet/src/main/native/include/wpinet/ParallelTcpConnector.h b/wpinet/src/main/native/include/wpinet/ParallelTcpConnector.h index fbcec185f66..e7bc953d62c 100644 --- a/wpinet/src/main/native/include/wpinet/ParallelTcpConnector.h +++ b/wpinet/src/main/native/include/wpinet/ParallelTcpConnector.h @@ -8,12 +8,11 @@ #include #include +#include #include #include #include -#include - #include "wpinet/uv/Timer.h" namespace wpi { @@ -85,7 +84,7 @@ class ParallelTcpConnector * @param servers array of server/port pairs */ void SetServers( - wpi::span> servers); + std::span> servers); /** * Tells the parallel connector that the current connection has terminated and diff --git a/wpinet/src/main/native/include/wpinet/UDPClient.h b/wpinet/src/main/native/include/wpinet/UDPClient.h index aa776cbf247..55e5702f309 100644 --- a/wpinet/src/main/native/include/wpinet/UDPClient.h +++ b/wpinet/src/main/native/include/wpinet/UDPClient.h @@ -5,12 +5,12 @@ #ifndef WPINET_UDPCLIENT_H_ #define WPINET_UDPCLIENT_H_ +#include #include #include #include #include -#include namespace wpi { @@ -36,7 +36,7 @@ class UDPClient { int start(int port); void shutdown(); // The passed in address MUST be a resolved IP address. - int send(span data, std::string_view server, int port); + int send(std::span data, std::string_view server, int port); int send(std::string_view data, std::string_view server, int port); int receive(uint8_t* data_received, int receive_len); int receive(uint8_t* data_received, int receive_len, diff --git a/wpinet/src/main/native/include/wpinet/WebSocket.h b/wpinet/src/main/native/include/wpinet/WebSocket.h index 931910668c1..1f295c95de2 100644 --- a/wpinet/src/main/native/include/wpinet/WebSocket.h +++ b/wpinet/src/main/native/include/wpinet/WebSocket.h @@ -10,13 +10,13 @@ #include #include #include +#include #include #include #include #include #include -#include #include "wpinet/uv/Buffer.h" #include "wpinet/uv/Error.h" @@ -77,7 +77,7 @@ class WebSocket : public std::enable_shared_from_this { uv::Timer::Time handshakeTimeout; // NOLINT /** Additional headers to include in handshake. */ - span> extraHeaders; + std::span> extraHeaders; }; /** @@ -93,11 +93,11 @@ class WebSocket : public std::enable_shared_from_this { static constexpr uint8_t kPing = kFlagFin | kOpPing; static constexpr uint8_t kPong = kFlagFin | kOpPong; - Frame(uint8_t opcode, span data) + Frame(uint8_t opcode, std::span data) : opcode{opcode}, data{data} {} uint8_t opcode; - span data; + std::span data; }; /** @@ -112,7 +112,7 @@ class WebSocket : public std::enable_shared_from_this { */ static std::shared_ptr CreateClient( uv::Stream& stream, std::string_view uri, std::string_view host, - span protocols = {}, + std::span protocols = {}, const ClientOptions& options = {}); /** @@ -200,8 +200,9 @@ class WebSocket : public std::enable_shared_from_this { * @param data UTF-8 encoded data to send * @param callback Callback which is invoked when the write completes. */ - void SendText(span data, - std::function, uv::Error)> callback) { + void SendText( + std::span data, + std::function, uv::Error)> callback) { Send(kFlagFin | kOpText, data, std::move(callback)); } @@ -210,8 +211,9 @@ class WebSocket : public std::enable_shared_from_this { * @param data UTF-8 encoded data to send * @param callback Callback which is invoked when the write completes. */ - void SendText(std::initializer_list data, - std::function, uv::Error)> callback) { + void SendText( + std::initializer_list data, + std::function, uv::Error)> callback) { SendText({data.begin(), data.end()}, std::move(callback)); } @@ -220,8 +222,9 @@ class WebSocket : public std::enable_shared_from_this { * @param data Data to send * @param callback Callback which is invoked when the write completes. */ - void SendBinary(span data, - std::function, uv::Error)> callback) { + void SendBinary( + std::span data, + std::function, uv::Error)> callback) { Send(kFlagFin | kOpBinary, data, std::move(callback)); } @@ -230,8 +233,9 @@ class WebSocket : public std::enable_shared_from_this { * @param data Data to send * @param callback Callback which is invoked when the write completes. */ - void SendBinary(std::initializer_list data, - std::function, uv::Error)> callback) { + void SendBinary( + std::initializer_list data, + std::function, uv::Error)> callback) { SendBinary({data.begin(), data.end()}, std::move(callback)); } @@ -243,8 +247,8 @@ class WebSocket : public std::enable_shared_from_this { * @param callback Callback which is invoked when the write completes. */ void SendTextFragment( - span data, - std::function, uv::Error)> callback) { + std::span data, + std::function, uv::Error)> callback) { Send(kOpText, data, std::move(callback)); } @@ -257,7 +261,7 @@ class WebSocket : public std::enable_shared_from_this { */ void SendTextFragment( std::initializer_list data, - std::function, uv::Error)> callback) { + std::function, uv::Error)> callback) { SendTextFragment({data.begin(), data.end()}, std::move(callback)); } @@ -269,8 +273,8 @@ class WebSocket : public std::enable_shared_from_this { * @param callback Callback which is invoked when the write completes. */ void SendBinaryFragment( - span data, - std::function, uv::Error)> callback) { + std::span data, + std::function, uv::Error)> callback) { Send(kOpBinary, data, std::move(callback)); } @@ -283,7 +287,7 @@ class WebSocket : public std::enable_shared_from_this { */ void SendBinaryFragment( std::initializer_list data, - std::function, uv::Error)> callback) { + std::function, uv::Error)> callback) { SendBinaryFragment({data.begin(), data.end()}, std::move(callback)); } @@ -294,8 +298,9 @@ class WebSocket : public std::enable_shared_from_this { * @param fin Set to true if this is the final fragment of the message * @param callback Callback which is invoked when the write completes. */ - void SendFragment(span data, bool fin, - std::function, uv::Error)> callback) { + void SendFragment( + std::span data, bool fin, + std::function, uv::Error)> callback) { Send(kOpCont | (fin ? kFlagFin : 0), data, std::move(callback)); } @@ -306,8 +311,9 @@ class WebSocket : public std::enable_shared_from_this { * @param fin Set to true if this is the final fragment of the message * @param callback Callback which is invoked when the write completes. */ - void SendFragment(std::initializer_list data, bool fin, - std::function, uv::Error)> callback) { + void SendFragment( + std::initializer_list data, bool fin, + std::function, uv::Error)> callback) { SendFragment({data.begin(), data.end()}, fin, std::move(callback)); } @@ -330,8 +336,9 @@ class WebSocket : public std::enable_shared_from_this { * @param callback Callback which is invoked when the ping frame * write completes. */ - void SendPing(span data, - std::function, uv::Error)> callback) { + void SendPing( + std::span data, + std::function, uv::Error)> callback) { Send(kFlagFin | kOpPing, data, std::move(callback)); } @@ -341,8 +348,9 @@ class WebSocket : public std::enable_shared_from_this { * @param callback Callback which is invoked when the ping frame * write completes. */ - void SendPing(std::initializer_list data, - std::function, uv::Error)> callback) { + void SendPing( + std::initializer_list data, + std::function, uv::Error)> callback) { SendPing({data.begin(), data.end()}, std::move(callback)); } @@ -365,8 +373,9 @@ class WebSocket : public std::enable_shared_from_this { * @param callback Callback which is invoked when the pong frame * write completes. */ - void SendPong(span data, - std::function, uv::Error)> callback) { + void SendPong( + std::span data, + std::function, uv::Error)> callback) { Send(kFlagFin | kOpPong, data, std::move(callback)); } @@ -376,8 +385,9 @@ class WebSocket : public std::enable_shared_from_this { * @param callback Callback which is invoked when the pong frame * write completes. */ - void SendPong(std::initializer_list data, - std::function, uv::Error)> callback) { + void SendPong( + std::initializer_list data, + std::function, uv::Error)> callback) { SendPong({data.begin(), data.end()}, std::move(callback)); } @@ -387,8 +397,9 @@ class WebSocket : public std::enable_shared_from_this { * @param frames Frame type/data pairs * @param callback Callback which is invoked when the write completes. */ - void SendFrames(span frames, - std::function, uv::Error)> callback); + void SendFrames( + std::span frames, + std::function, uv::Error)> callback); /** * Fail the connection. @@ -446,17 +457,17 @@ class WebSocket : public std::enable_shared_from_this { * The first parameter is the data, the second parameter is true if the * data is the last fragment of the message. */ - sig::Signal, bool> binary; + sig::Signal, bool> binary; /** * Ping event. Emitted when a ping message is received. */ - sig::Signal> ping; + sig::Signal> ping; /** * Pong event. Emitted when a pong message is received. */ - sig::Signal> pong; + sig::Signal> pong; private: // user data @@ -489,15 +500,15 @@ class WebSocket : public std::enable_shared_from_this { std::unique_ptr m_clientHandshake; void StartClient(std::string_view uri, std::string_view host, - span protocols, + std::span protocols, const ClientOptions& options); void StartServer(std::string_view key, std::string_view version, std::string_view protocol); void SendClose(uint16_t code, std::string_view reason); void SetClosed(uint16_t code, std::string_view reason, bool failed = false); void HandleIncoming(uv::Buffer& buf, size_t size); - void Send(uint8_t opcode, span data, - std::function, uv::Error)> callback) { + void Send(uint8_t opcode, std::span data, + std::function, uv::Error)> callback) { SendFrames({{Frame{opcode, data}}}, std::move(callback)); } }; diff --git a/wpinet/src/main/native/include/wpinet/WebSocketServer.h b/wpinet/src/main/native/include/wpinet/WebSocketServer.h index 65e7cf3c757..9d655d37dc0 100644 --- a/wpinet/src/main/native/include/wpinet/WebSocketServer.h +++ b/wpinet/src/main/native/include/wpinet/WebSocketServer.h @@ -8,6 +8,7 @@ #include #include #include +#include #include #include #include @@ -15,7 +16,6 @@ #include #include #include -#include #include "wpinet/HttpParser.h" #include "wpinet/WebSocket.h" @@ -54,7 +54,7 @@ class WebSocketServerHelper { * is empty. */ std::pair MatchProtocol( - span protocols); + std::span protocols); /** * Try to find a match to the list of sub-protocols provided by the client. @@ -123,7 +123,8 @@ class WebSocketServer : public std::enable_shared_from_this { /** * Private constructor. */ - WebSocketServer(uv::Stream& stream, span protocols, + WebSocketServer(uv::Stream& stream, + std::span protocols, ServerOptions options, const private_init&); /** @@ -136,7 +137,7 @@ class WebSocketServer : public std::enable_shared_from_this { * @param options Handshake options */ static std::shared_ptr Create( - uv::Stream& stream, span protocols = {}, + uv::Stream& stream, std::span protocols = {}, const ServerOptions& options = {}); /** diff --git a/wpinet/src/main/native/include/wpinet/raw_uv_ostream.h b/wpinet/src/main/native/include/wpinet/raw_uv_ostream.h index 54ee4208c20..aa45297b75a 100644 --- a/wpinet/src/main/native/include/wpinet/raw_uv_ostream.h +++ b/wpinet/src/main/native/include/wpinet/raw_uv_ostream.h @@ -6,11 +6,11 @@ #define WPINET_RAW_UV_OSTREAM_H_ #include +#include #include #include #include -#include #include "wpinet/uv/Buffer.h" @@ -50,7 +50,7 @@ class raw_uv_ostream : public raw_ostream { /** * Returns an span to the buffers. */ - span bufs() { return m_bufs; } + std::span bufs() { return m_bufs; } void flush() = delete; diff --git a/wpinet/src/main/native/include/wpinet/uv/Buffer.h b/wpinet/src/main/native/include/wpinet/uv/Buffer.h index b22753d746a..4b58b0f2b02 100644 --- a/wpinet/src/main/native/include/wpinet/uv/Buffer.h +++ b/wpinet/src/main/native/include/wpinet/uv/Buffer.h @@ -9,11 +9,11 @@ #include #include +#include #include #include #include -#include namespace wpi::uv { @@ -32,7 +32,7 @@ class Buffer : public uv_buf_t { } /*implicit*/ Buffer(std::string_view str) // NOLINT : Buffer{str.data(), str.size()} {} - /*implicit*/ Buffer(span arr) // NOLINT + /*implicit*/ Buffer(std::span arr) // NOLINT : Buffer{reinterpret_cast(arr.data()), arr.size()} {} Buffer(char* base_, size_t len_) { base = base_; @@ -43,11 +43,11 @@ class Buffer : public uv_buf_t { len = static_cast(len_); } - span data() const { return {base, len}; } - span data() { return {base, len}; } + std::span data() const { return {base, len}; } + std::span data() { return {base, len}; } - operator span() const { return data(); } // NOLINT - operator span() { return data(); } // NOLINT + operator std::span() const { return data(); } // NOLINT + operator std::span() { return data(); } // NOLINT static Buffer Allocate(size_t size) { return Buffer{new char[size], size}; } @@ -57,9 +57,9 @@ class Buffer : public uv_buf_t { return buf; } - static Buffer Dup(span in) { + static Buffer Dup(std::span in) { Buffer buf = Allocate(in.size()); - std::memcpy(buf.base, in.begin(), in.size()); + std::memcpy(buf.base, in.data(), in.size()); return buf; } @@ -131,7 +131,7 @@ class SimpleBufferPool { * This is NOT safe to use with arbitrary buffers unless they were * allocated with the same size as the buffer pool allocation size. */ - void Release(span bufs) { + void Release(std::span bufs) { for (auto& buf : bufs) { m_pool.emplace_back(buf.Move()); } diff --git a/wpinet/src/main/native/include/wpinet/uv/Process.h b/wpinet/src/main/native/include/wpinet/uv/Process.h index 153ee377faa..3d84bde0b62 100644 --- a/wpinet/src/main/native/include/wpinet/uv/Process.h +++ b/wpinet/src/main/native/include/wpinet/uv/Process.h @@ -9,12 +9,12 @@ #include #include +#include #include #include #include #include -#include #include "wpinet/uv/Handle.h" @@ -233,7 +233,7 @@ class Process final : public HandleImpl { * @param options Process options */ static std::shared_ptr SpawnArray(Loop& loop, std::string_view file, - span options); + std::span options); static std::shared_ptr SpawnArray( Loop& loop, std::string_view file, @@ -262,7 +262,7 @@ class Process final : public HandleImpl { */ static std::shared_ptr SpawnArray(const std::shared_ptr& loop, std::string_view file, - span options) { + std::span options) { return SpawnArray(*loop, file, options); } diff --git a/wpinet/src/main/native/include/wpinet/uv/Stream.h b/wpinet/src/main/native/include/wpinet/uv/Stream.h index 6aa77c82ec8..95684555123 100644 --- a/wpinet/src/main/native/include/wpinet/uv/Stream.h +++ b/wpinet/src/main/native/include/wpinet/uv/Stream.h @@ -11,10 +11,10 @@ #include #include #include +#include #include #include -#include #include "wpinet/uv/Buffer.h" #include "wpinet/uv/Handle.h" @@ -128,7 +128,8 @@ class Stream : public Handle { * @param bufs The buffers to be written to the stream. * @param req write request */ - void Write(span bufs, const std::shared_ptr& req); + void Write(std::span bufs, + const std::shared_ptr& req); /** * Write data to the stream. @@ -164,8 +165,8 @@ class Stream : public Handle { * @param bufs The buffers to be written to the stream. * @param callback Callback function to call when the write completes */ - void Write(span bufs, - std::function, Error)> callback); + void Write(std::span bufs, + std::function, Error)> callback); /** * Write data to the stream. @@ -181,7 +182,7 @@ class Stream : public Handle { * @param callback Callback function to call when the write completes */ void Write(std::initializer_list bufs, - std::function, Error)> callback) { + std::function, Error)> callback) { Write({bufs.begin(), bufs.end()}, std::move(callback)); } @@ -195,7 +196,7 @@ class Stream : public Handle { * @param bufs The buffers to be written to the stream. * @return Number of bytes written. */ - int TryWrite(span bufs); + int TryWrite(std::span bufs); /** * Queue a write request if it can be completed immediately. @@ -222,7 +223,7 @@ class Stream : public Handle { * @param send send stream * @return Number of bytes written. */ - int TryWrite2(span bufs, Stream& send); + int TryWrite2(std::span bufs, Stream& send); /** * Same as TryWrite() and extended write function for sending handles over a diff --git a/wpinet/src/main/native/include/wpinet/uv/Udp.h b/wpinet/src/main/native/include/wpinet/uv/Udp.h index e6ccb53ded4..cfa245f6723 100644 --- a/wpinet/src/main/native/include/wpinet/uv/Udp.h +++ b/wpinet/src/main/native/include/wpinet/uv/Udp.h @@ -9,11 +9,11 @@ #include #include +#include #include #include #include -#include #include "wpinet/uv/Handle.h" #include "wpinet/uv/Request.h" @@ -245,15 +245,15 @@ class Udp final : public HandleImpl { * @param bufs The buffers to be written to the stream. * @param req write request */ - void Send(const sockaddr& addr, span bufs, + void Send(const sockaddr& addr, std::span bufs, const std::shared_ptr& req); - void Send(const sockaddr_in& addr, span bufs, + void Send(const sockaddr_in& addr, std::span bufs, const std::shared_ptr& req) { Send(reinterpret_cast(addr), bufs, req); } - void Send(const sockaddr_in6& addr, span bufs, + void Send(const sockaddr_in6& addr, std::span bufs, const std::shared_ptr& req) { Send(reinterpret_cast(addr), bufs, req); } @@ -265,7 +265,8 @@ class Udp final : public HandleImpl { * @param bufs The buffers to be written to the stream. * @param req write request */ - void Send(span bufs, const std::shared_ptr& req); + void Send(std::span bufs, + const std::shared_ptr& req); /** * Send data over the UDP socket. If the socket has not previously been bound @@ -284,16 +285,16 @@ class Udp final : public HandleImpl { * @param bufs The buffers to be sent. * @param callback Callback function to call when the data has been sent. */ - void Send(const sockaddr& addr, span bufs, - std::function, Error)> callback); + void Send(const sockaddr& addr, std::span bufs, + std::function, Error)> callback); - void Send(const sockaddr_in& addr, span bufs, - std::function, Error)> callback) { + void Send(const sockaddr_in& addr, std::span bufs, + std::function, Error)> callback) { Send(reinterpret_cast(addr), bufs, std::move(callback)); } - void Send(const sockaddr_in6& addr, span bufs, - std::function, Error)> callback) { + void Send(const sockaddr_in6& addr, std::span bufs, + std::function, Error)> callback) { Send(reinterpret_cast(addr), bufs, std::move(callback)); } @@ -304,8 +305,8 @@ class Udp final : public HandleImpl { * @param bufs The buffers to be written to the stream. * @param callback Callback function to call when the data has been sent. */ - void Send(span bufs, - std::function, Error)> callback); + void Send(std::span bufs, + std::function, Error)> callback); /** * Same as Send(), but won't queue a send request if it can't be completed @@ -316,7 +317,7 @@ class Udp final : public HandleImpl { * @param bufs The buffers to be send. * @return Number of bytes sent. */ - int TrySend(const sockaddr& addr, span bufs) { + int TrySend(const sockaddr& addr, std::span bufs) { int val = uv_udp_try_send(GetRaw(), bufs.data(), static_cast(bufs.size()), &addr); if (val < 0) { @@ -326,11 +327,11 @@ class Udp final : public HandleImpl { return val; } - int TrySend(const sockaddr_in& addr, span bufs) { + int TrySend(const sockaddr_in& addr, std::span bufs) { return TrySend(reinterpret_cast(addr), bufs); } - int TrySend(const sockaddr_in6& addr, span bufs) { + int TrySend(const sockaddr_in6& addr, std::span bufs) { return TrySend(reinterpret_cast(addr), bufs); } @@ -341,7 +342,7 @@ class Udp final : public HandleImpl { * @param bufs The buffers to be written to the stream. * @return Number of bytes sent. */ - int TrySend(span bufs) { + int TrySend(std::span bufs) { int val = uv_udp_try_send(GetRaw(), bufs.data(), static_cast(bufs.size()), nullptr); if (val < 0) { diff --git a/wpinet/src/main/native/linux/MulticastServiceAnnouncer.cpp b/wpinet/src/main/native/linux/MulticastServiceAnnouncer.cpp index c6f493288e2..d04711fa57c 100644 --- a/wpinet/src/main/native/linux/MulticastServiceAnnouncer.cpp +++ b/wpinet/src/main/native/linux/MulticastServiceAnnouncer.cpp @@ -31,13 +31,13 @@ struct MulticastServiceAnnouncer::Impl { template Impl(std::string_view serviceName, std::string_view serviceType, int port, - wpi::span> txt); + std::span> txt); }; template MulticastServiceAnnouncer::Impl::Impl(std::string_view serviceName, std::string_view serviceType, int port, - wpi::span> txt) { + std::span> txt) { if (!this->table.IsValid()) { return; } @@ -135,19 +135,19 @@ static void ClientCallback(AvahiClient* client, AvahiClientState state, MulticastServiceAnnouncer::MulticastServiceAnnouncer( std::string_view serviceName, std::string_view serviceType, int port) { - wpi::span> txt; + std::span> txt; pImpl = std::make_unique(serviceName, serviceType, port, txt); } MulticastServiceAnnouncer::MulticastServiceAnnouncer( std::string_view serviceName, std::string_view serviceType, int port, - wpi::span> txt) { + std::span> txt) { pImpl = std::make_unique(serviceName, serviceType, port, txt); } MulticastServiceAnnouncer::MulticastServiceAnnouncer( std::string_view serviceName, std::string_view serviceType, int port, - wpi::span> txt) { + std::span> txt) { pImpl = std::make_unique(serviceName, serviceType, port, txt); } diff --git a/wpinet/src/main/native/macOS/MulticastServiceAnnouncer.cpp b/wpinet/src/main/native/macOS/MulticastServiceAnnouncer.cpp index b897c0c1d5e..8c31a3b22fe 100644 --- a/wpinet/src/main/native/macOS/MulticastServiceAnnouncer.cpp +++ b/wpinet/src/main/native/macOS/MulticastServiceAnnouncer.cpp @@ -34,7 +34,7 @@ MulticastServiceAnnouncer::MulticastServiceAnnouncer( MulticastServiceAnnouncer::MulticastServiceAnnouncer( std::string_view serviceName, std::string_view serviceType, int port, - wpi::span> txt) { + std::span> txt) { pImpl = std::make_unique(); pImpl->serviceName = serviceName; pImpl->serviceType = serviceType; @@ -48,7 +48,7 @@ MulticastServiceAnnouncer::MulticastServiceAnnouncer( MulticastServiceAnnouncer::MulticastServiceAnnouncer( std::string_view serviceName, std::string_view serviceType, int port, - wpi::span> txt) { + std::span> txt) { pImpl = std::make_unique(); pImpl->serviceName = serviceName; pImpl->serviceType = serviceType; diff --git a/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPConnector_parallel.cpp b/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPConnector_parallel.cpp index f1f89c68624..1d979cb4847 100644 --- a/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPConnector_parallel.cpp +++ b/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPConnector_parallel.cpp @@ -24,7 +24,7 @@ using namespace wpi; #endif std::unique_ptr TCPConnector::connect_parallel( - span> servers, Logger& logger, + std::span> servers, Logger& logger, int timeout) { if (servers.empty()) { return nullptr; diff --git a/wpinet/src/main/native/thirdparty/tcpsockets/include/wpinet/TCPConnector.h b/wpinet/src/main/native/thirdparty/tcpsockets/include/wpinet/TCPConnector.h index 6da4c7bb213..d9c3ad98196 100644 --- a/wpinet/src/main/native/thirdparty/tcpsockets/include/wpinet/TCPConnector.h +++ b/wpinet/src/main/native/thirdparty/tcpsockets/include/wpinet/TCPConnector.h @@ -25,10 +25,9 @@ #define WPINET_TCPCONNECTOR_H_ #include +#include #include -#include - #include "wpinet/NetworkStream.h" namespace wpi { @@ -41,7 +40,7 @@ class TCPConnector { Logger& logger, int timeout = 0); static std::unique_ptr connect_parallel( - span> servers, Logger& logger, + std::span> servers, Logger& logger, int timeout = 0); }; diff --git a/wpinet/src/main/native/windows/MulticastServiceAnnouncer.cpp b/wpinet/src/main/native/windows/MulticastServiceAnnouncer.cpp index 8f5daefd0f3..c1ed58d480a 100644 --- a/wpinet/src/main/native/windows/MulticastServiceAnnouncer.cpp +++ b/wpinet/src/main/native/windows/MulticastServiceAnnouncer.cpp @@ -39,13 +39,13 @@ struct MulticastServiceAnnouncer::Impl : ImplBase { template Impl(std::string_view serviceName, std::string_view serviceType, int port, - wpi::span> txt); + std::span> txt); }; template MulticastServiceAnnouncer::Impl::Impl(std::string_view serviceName, std::string_view serviceType, int port, - wpi::span> txt) { + std::span> txt) { if (!dynamicDns.CanDnsAnnounce) { return; } @@ -105,19 +105,19 @@ MulticastServiceAnnouncer::Impl::Impl(std::string_view serviceName, MulticastServiceAnnouncer::MulticastServiceAnnouncer( std::string_view serviceName, std::string_view serviceType, int port) { - wpi::span> txt; + std::span> txt; pImpl = std::make_unique(serviceName, serviceType, port, txt); } MulticastServiceAnnouncer::MulticastServiceAnnouncer( std::string_view serviceName, std::string_view serviceType, int port, - wpi::span> txt) { + std::span> txt) { pImpl = std::make_unique(serviceName, serviceType, port, txt); } MulticastServiceAnnouncer::MulticastServiceAnnouncer( std::string_view serviceName, std::string_view serviceType, int port, - wpi::span> txt) { + std::span> txt) { pImpl = std::make_unique(serviceName, serviceType, port, txt); } diff --git a/wpinet/src/main/native/windows/MulticastServiceResolver.cpp b/wpinet/src/main/native/windows/MulticastServiceResolver.cpp index a3d45c5332c..79fc7b5ef71 100644 --- a/wpinet/src/main/native/windows/MulticastServiceResolver.cpp +++ b/wpinet/src/main/native/windows/MulticastServiceResolver.cpp @@ -128,7 +128,7 @@ static _Function_class_(DNS_QUERY_COMPLETION_ROUTINE) VOID WINAPI continue; } storage.clear(); - wpi::span wideStr{ + std::span wideStr{ reinterpret_cast(wideView.data()), splitIndex}; wpi::convertUTF16ToUTF8String(wideStr, storage); @@ -136,7 +136,7 @@ static _Function_class_(DNS_QUERY_COMPLETION_ROUTINE) VOID WINAPI data.txt.emplace_back(std::pair{ std::string{storage}, {}}); storage.clear(); - wideStr = wpi::span{ + wideStr = std::span{ reinterpret_cast(wideView.data() + splitIndex + 1), wideView.size() - splitIndex - 1}; @@ -147,7 +147,7 @@ static _Function_class_(DNS_QUERY_COMPLETION_ROUTINE) VOID WINAPI } storage.clear(); - wpi::span wideHostName{ + std::span wideHostName{ reinterpret_cast(A->pName), wcslen(A->pName)}; wpi::convertUTF16ToUTF8String(wideHostName, storage); storage.append("."); @@ -156,7 +156,7 @@ static _Function_class_(DNS_QUERY_COMPLETION_ROUTINE) VOID WINAPI storage.clear(); int len = nameHost.find(impl->serviceType.c_str()); - wpi::span wideServiceName{ + std::span wideServiceName{ reinterpret_cast(nameHost.data()), nameHost.size()}; if (len != nameHost.npos) { diff --git a/wpinet/src/netconsoleServer/native/cpp/main.cpp b/wpinet/src/netconsoleServer/native/cpp/main.cpp index c30e8e5e727..0271e36482f 100644 --- a/wpinet/src/netconsoleServer/native/cpp/main.cpp +++ b/wpinet/src/netconsoleServer/native/cpp/main.cpp @@ -58,7 +58,7 @@ static bool NewlineBuffer(std::string& rem, uv::Buffer& buf, size_t len, static_cast(ts & 0xff), static_cast((tcpSeq >> 8) & 0xff), static_cast(tcpSeq & 0xff)}; - out << wpi::span(header); + out << std::span(header); } out << rem << toCopy; diff --git a/wpinet/src/netconsoleTee/native/cpp/main.cpp b/wpinet/src/netconsoleTee/native/cpp/main.cpp index 371f27026b8..a6bdff44401 100644 --- a/wpinet/src/netconsoleTee/native/cpp/main.cpp +++ b/wpinet/src/netconsoleTee/native/cpp/main.cpp @@ -49,7 +49,7 @@ static bool NewlineBuffer(std::string& rem, uv::Buffer& buf, size_t len, static_cast(ts & 0xff), static_cast((tcpSeq >> 8) & 0xff), static_cast(tcpSeq & 0xff)}; - out << wpi::span(header); + out << std::span(header); } out << rem << toCopy; diff --git a/wpinet/src/test/native/cpp/HttpWebSocketServerConnectionTest.cpp b/wpinet/src/test/native/cpp/HttpWebSocketServerConnectionTest.cpp index 3eabab8dc05..9c2d8749c9c 100644 --- a/wpinet/src/test/native/cpp/HttpWebSocketServerConnectionTest.cpp +++ b/wpinet/src/test/native/cpp/HttpWebSocketServerConnectionTest.cpp @@ -12,7 +12,7 @@ class HttpWebSocketServerConnectionTest : public HttpWebSocketServerConnection { public: HttpWebSocketServerConnectionTest(std::shared_ptr stream, - span protocols) + std::span protocols) : HttpWebSocketServerConnection{stream, protocols} {} void ProcessRequest() override { ++gotRequest; } diff --git a/wpinet/src/test/native/cpp/WebSocketTest.cpp b/wpinet/src/test/native/cpp/WebSocketTest.cpp index 08518951dbc..e5f03de2254 100644 --- a/wpinet/src/test/native/cpp/WebSocketTest.cpp +++ b/wpinet/src/test/native/cpp/WebSocketTest.cpp @@ -47,9 +47,8 @@ std::vector WebSocketTest::BuildHeader(uint8_t opcode, bool fin, return data; } -std::vector WebSocketTest::BuildMessage(uint8_t opcode, bool fin, - bool masking, - span data) { +std::vector WebSocketTest::BuildMessage( + uint8_t opcode, bool fin, bool masking, std::span data) { auto finalData = BuildHeader(opcode, fin, masking, data.size()); size_t headerSize = finalData.size(); finalData.insert(finalData.end(), data.begin(), data.end()); @@ -69,7 +68,7 @@ std::vector WebSocketTest::BuildMessage(uint8_t opcode, bool fin, // If the message is masked, changes the mask to match the mask set by // BuildHeader() by unmasking and remasking. -void WebSocketTest::AdjustMasking(span message) { +void WebSocketTest::AdjustMasking(std::span message) { if (message.size() < 2) { return; } diff --git a/wpinet/src/test/native/cpp/WebSocketTest.h b/wpinet/src/test/native/cpp/WebSocketTest.h index 4fedb21238d..903ce00a87b 100644 --- a/wpinet/src/test/native/cpp/WebSocketTest.h +++ b/wpinet/src/test/native/cpp/WebSocketTest.h @@ -6,10 +6,9 @@ #include #include +#include #include -#include - #include "gtest/gtest.h" #include "wpinet/uv/Loop.h" #include "wpinet/uv/Pipe.h" @@ -61,8 +60,8 @@ class WebSocketTest : public ::testing::Test { bool masking, uint64_t len); static std::vector BuildMessage(uint8_t opcode, bool fin, bool masking, - span data); - static void AdjustMasking(span message); + std::span data); + static void AdjustMasking(std::span message); static const uint8_t testMask[4]; std::shared_ptr loop; diff --git a/wpiutil/.styleguide b/wpiutil/.styleguide index 68288c93838..9c1196ebef3 100644 --- a/wpiutil/.styleguide +++ b/wpiutil/.styleguide @@ -12,6 +12,10 @@ cppSrcFileInclude { \.cpp$ } +modifiableFileExclude { + src/main/native/include/wpi/MulticastServiceAnnouncer\.h$ +} + generatedFileExclude { src/main/native/thirdparty/ diff --git a/wpiutil/CMakeLists.txt b/wpiutil/CMakeLists.txt index 8fb023a59d1..db9a3ed38b9 100644 --- a/wpiutil/CMakeLists.txt +++ b/wpiutil/CMakeLists.txt @@ -105,7 +105,7 @@ set_target_properties(wpiutil PROPERTIES DEBUG_POSTFIX "d") set_property(TARGET wpiutil PROPERTY FOLDER "libraries") -target_compile_features(wpiutil PUBLIC cxx_std_17) +target_compile_features(wpiutil PUBLIC cxx_std_20) if (MSVC) target_compile_options(wpiutil PUBLIC /permissive- /Zc:throwingNew /MP /bigobj) target_compile_definitions(wpiutil PRIVATE -D_CRT_SECURE_NO_WARNINGS) diff --git a/wpiutil/src/main/native/cpp/Base64.cpp b/wpiutil/src/main/native/cpp/Base64.cpp index 8f1f81020b1..bc1d3bae696 100644 --- a/wpiutil/src/main/native/cpp/Base64.cpp +++ b/wpiutil/src/main/native/cpp/Base64.cpp @@ -138,8 +138,8 @@ size_t Base64Decode(std::string_view encoded, std::vector* plain) { return Base64Decode(os, encoded); } -span Base64Decode(std::string_view encoded, size_t* num_read, - SmallVectorImpl& buf) { +std::span Base64Decode(std::string_view encoded, size_t* num_read, + SmallVectorImpl& buf) { buf.clear(); raw_usvector_ostream os(buf); *num_read = Base64Decode(os, encoded); @@ -193,19 +193,19 @@ std::string_view Base64Encode(std::string_view plain, return os.str(); } -void Base64Encode(raw_ostream& os, span plain) { +void Base64Encode(raw_ostream& os, std::span plain) { Base64Encode(os, std::string_view{reinterpret_cast(plain.data()), plain.size()}); } -void Base64Encode(span plain, std::string* encoded) { +void Base64Encode(std::span plain, std::string* encoded) { encoded->resize(0); raw_string_ostream os(*encoded); Base64Encode(os, plain); os.flush(); } -std::string_view Base64Encode(span plain, +std::string_view Base64Encode(std::span plain, SmallVectorImpl& buf) { buf.clear(); raw_svector_ostream os(buf); diff --git a/wpiutil/src/main/native/cpp/DataLog.cpp b/wpiutil/src/main/native/cpp/DataLog.cpp index 81e64048db1..b628429920b 100644 --- a/wpiutil/src/main/native/cpp/DataLog.cpp +++ b/wpiutil/src/main/native/cpp/DataLog.cpp @@ -109,8 +109,8 @@ class DataLog::Buffer { size_t GetRemaining() const { return m_maxLen - m_len; } - wpi::span GetData() { return {m_buf, m_len}; } - wpi::span GetData() const { return {m_buf, m_len}; } + std::span GetData() { return {m_buf, m_len}; } + std::span GetData() const { return {m_buf, m_len}; } private: uint8_t* m_buf; @@ -142,12 +142,12 @@ DataLog::DataLog(wpi::Logger& msglog, std::string_view dir, m_newFilename{filename}, m_thread{[this, dir = std::string{dir}] { WriterThreadMain(dir); }} {} -DataLog::DataLog(std::function data)> write, +DataLog::DataLog(std::function data)> write, double period, std::string_view extraHeader) : DataLog{defaultMessageLog, std::move(write), period, extraHeader} {} DataLog::DataLog(wpi::Logger& msglog, - std::function data)> write, + std::function data)> write, double period, std::string_view extraHeader) : m_msglog{msglog}, m_period{period}, @@ -192,7 +192,7 @@ void DataLog::Resume() { m_paused = false; } -static void WriteToFile(fs::file_t f, wpi::span data, +static void WriteToFile(fs::file_t f, std::span data, std::string_view filename, wpi::Logger& msglog) { do { #ifdef _WIN32 @@ -365,7 +365,7 @@ void DataLog::WriterThreadMain(std::string_view dir) { } void DataLog::WriterThreadMain( - std::function data)> write) { + std::function data)> write) { std::chrono::duration periodTime{m_period}; // write header (version 1.0) @@ -509,7 +509,7 @@ uint8_t* DataLog::StartRecord(uint32_t entry, uint64_t timestamp, return buf; } -void DataLog::AppendImpl(wpi::span data) { +void DataLog::AppendImpl(std::span data) { while (data.size() > kBlockSize) { uint8_t* buf = Reserve(kBlockSize); std::memcpy(buf, data.data(), kBlockSize); @@ -525,7 +525,7 @@ void DataLog::AppendStringImpl(std::string_view str) { AppendImpl({reinterpret_cast(str.data()), str.size()}); } -void DataLog::AppendRaw(int entry, wpi::span data, +void DataLog::AppendRaw(int entry, std::span data, int64_t timestamp) { if (entry <= 0) { return; @@ -539,7 +539,7 @@ void DataLog::AppendRaw(int entry, wpi::span data, } void DataLog::AppendRaw2(int entry, - wpi::span> data, + std::span> data, int64_t timestamp) { if (entry <= 0) { return; @@ -623,7 +623,7 @@ void DataLog::AppendString(int entry, std::string_view value, timestamp); } -void DataLog::AppendBooleanArray(int entry, wpi::span arr, +void DataLog::AppendBooleanArray(int entry, std::span arr, int64_t timestamp) { if (entry <= 0) { return; @@ -647,7 +647,7 @@ void DataLog::AppendBooleanArray(int entry, wpi::span arr, } } -void DataLog::AppendBooleanArray(int entry, wpi::span arr, +void DataLog::AppendBooleanArray(int entry, std::span arr, int64_t timestamp) { if (entry <= 0) { return; @@ -671,12 +671,12 @@ void DataLog::AppendBooleanArray(int entry, wpi::span arr, } } -void DataLog::AppendBooleanArray(int entry, wpi::span arr, +void DataLog::AppendBooleanArray(int entry, std::span arr, int64_t timestamp) { AppendRaw(entry, arr, timestamp); } -void DataLog::AppendIntegerArray(int entry, wpi::span arr, +void DataLog::AppendIntegerArray(int entry, std::span arr, int64_t timestamp) { if constexpr (wpi::support::endian::system_endianness() == wpi::support::little) { @@ -709,7 +709,7 @@ void DataLog::AppendIntegerArray(int entry, wpi::span arr, } } -void DataLog::AppendFloatArray(int entry, wpi::span arr, +void DataLog::AppendFloatArray(int entry, std::span arr, int64_t timestamp) { if constexpr (wpi::support::endian::system_endianness() == wpi::support::little) { @@ -742,7 +742,7 @@ void DataLog::AppendFloatArray(int entry, wpi::span arr, } } -void DataLog::AppendDoubleArray(int entry, wpi::span arr, +void DataLog::AppendDoubleArray(int entry, std::span arr, int64_t timestamp) { if constexpr (wpi::support::endian::system_endianness() == wpi::support::little) { @@ -775,7 +775,7 @@ void DataLog::AppendDoubleArray(int entry, wpi::span arr, } } -void DataLog::AppendStringArray(int entry, wpi::span arr, +void DataLog::AppendStringArray(int entry, std::span arr, int64_t timestamp) { if (entry <= 0) { return; @@ -798,7 +798,7 @@ void DataLog::AppendStringArray(int entry, wpi::span arr, } void DataLog::AppendStringArray(int entry, - wpi::span arr, + std::span arr, int64_t timestamp) { if (entry <= 0) { return; diff --git a/wpiutil/src/main/native/cpp/DataLogReader.cpp b/wpiutil/src/main/native/cpp/DataLogReader.cpp index be7317cd7cb..96f66893638 100644 --- a/wpiutil/src/main/native/cpp/DataLogReader.cpp +++ b/wpiutil/src/main/native/cpp/DataLogReader.cpp @@ -10,7 +10,7 @@ using namespace wpi::log; -static bool ReadString(wpi::span* buf, std::string_view* str) { +static bool ReadString(std::span* buf, std::string_view* str) { if (buf->size() < 4) { *str = {}; return false; @@ -241,7 +241,7 @@ DataLogReader::iterator DataLogReader::begin() const { return DataLogIterator{this, 12 + size}; } -static uint64_t ReadVarInt(wpi::span buf) { +static uint64_t ReadVarInt(std::span buf) { uint64_t val = 0; int shift = 0; for (auto v : buf) { diff --git a/wpiutil/src/main/native/cpp/Synchronization.cpp b/wpiutil/src/main/native/cpp/Synchronization.cpp index a2b4b12defd..f9ac75b812a 100644 --- a/wpiutil/src/main/native/cpp/Synchronization.cpp +++ b/wpiutil/src/main/native/cpp/Synchronization.cpp @@ -166,20 +166,20 @@ bool wpi::WaitForObject(WPI_Handle handle) { bool wpi::WaitForObject(WPI_Handle handle, double timeout, bool* timedOut) { WPI_Handle signaledValue; auto signaled = WaitForObjects( - wpi::span(&handle, 1), wpi::span(&signaledValue, 1), timeout, timedOut); + std::span(&handle, 1), std::span(&signaledValue, 1), timeout, timedOut); if (signaled.empty()) { return false; } return (signaled[0] & 0x80000000ul) == 0; } -wpi::span wpi::WaitForObjects(wpi::span handles, - wpi::span signaled) { +std::span wpi::WaitForObjects(std::span handles, + std::span signaled) { return WaitForObjects(handles, signaled, -1, nullptr); } -wpi::span wpi::WaitForObjects(wpi::span handles, - wpi::span signaled, +std::span wpi::WaitForObjects(std::span handles, + std::span signaled, double timeout, bool* timedOut) { auto& manager = GetManager(); if (gShutdown) { @@ -368,8 +368,8 @@ int WPI_WaitForObjectTimeout(WPI_Handle handle, double timeout, int WPI_WaitForObjects(const WPI_Handle* handles, int handles_count, WPI_Handle* signaled) { - return wpi::WaitForObjects(wpi::span(handles, handles_count), - wpi::span(signaled, handles_count)) + return wpi::WaitForObjects(std::span(handles, handles_count), + std::span(signaled, handles_count)) .size(); } @@ -377,8 +377,8 @@ int WPI_WaitForObjectsTimeout(const WPI_Handle* handles, int handles_count, WPI_Handle* signaled, double timeout, int* timed_out) { bool timedOutBool; - auto signaledResult = wpi::WaitForObjects(wpi::span(handles, handles_count), - wpi::span(signaled, handles_count), + auto signaledResult = wpi::WaitForObjects(std::span(handles, handles_count), + std::span(signaled, handles_count), timeout, &timedOutBool); *timed_out = timedOutBool ? 1 : 0; return signaledResult.size(); diff --git a/wpiutil/src/main/native/cpp/jni/WPIUtilJNI.cpp b/wpiutil/src/main/native/cpp/jni/WPIUtilJNI.cpp index 15b18957189..5fa4ddf5f5e 100644 --- a/wpiutil/src/main/native/cpp/jni/WPIUtilJNI.cpp +++ b/wpiutil/src/main/native/cpp/jni/WPIUtilJNI.cpp @@ -247,7 +247,7 @@ Java_edu_wpi_first_util_WPIUtilJNI_waitForObjects JIntArrayRef handlesArr{env, handles}; wpi::SmallVector signaledBuf; signaledBuf.resize(handlesArr.size()); - wpi::span handlesArr2{ + std::span handlesArr2{ reinterpret_cast(handlesArr.array().data()), handlesArr.size()}; @@ -271,7 +271,7 @@ Java_edu_wpi_first_util_WPIUtilJNI_waitForObjectsTimeout JIntArrayRef handlesArr{env, handles}; wpi::SmallVector signaledBuf; signaledBuf.resize(handlesArr.size()); - wpi::span handlesArr2{ + std::span handlesArr2{ reinterpret_cast(handlesArr.array().data()), handlesArr.size()}; diff --git a/wpiutil/src/main/native/cpp/leb128.cpp b/wpiutil/src/main/native/cpp/leb128.cpp index 965788332e6..17fbeb9d468 100644 --- a/wpiutil/src/main/native/cpp/leb128.cpp +++ b/wpiutil/src/main/native/cpp/leb128.cpp @@ -7,7 +7,6 @@ #include "wpi/SpanExtras.h" #include "wpi/raw_istream.h" #include "wpi/raw_ostream.h" -#include "wpi/span.h" namespace wpi { @@ -98,7 +97,7 @@ bool ReadUleb128(raw_istream& is, uint64_t* ret) { return true; } -std::optional Uleb128Reader::ReadOne(span* in) { +std::optional Uleb128Reader::ReadOne(std::span* in) { while (!in->empty()) { uint8_t byte = in->front(); *in = wpi::drop_front(*in); diff --git a/wpiutil/src/main/native/cpp/sha1.cpp b/wpiutil/src/main/native/cpp/sha1.cpp index 8ec7cb13965..98dc5433cb6 100644 --- a/wpiutil/src/main/native/cpp/sha1.cpp +++ b/wpiutil/src/main/native/cpp/sha1.cpp @@ -217,7 +217,7 @@ SHA1::SHA1() { } void SHA1::Update(std::string_view s) { - raw_mem_istream is(span(s.data(), s.size())); + raw_mem_istream is(std::span(s.data(), s.size())); Update(is); } diff --git a/wpiutil/src/main/native/include/wpi/Base64.h b/wpiutil/src/main/native/include/wpi/Base64.h index 41b0062408a..c410bd0c26a 100644 --- a/wpiutil/src/main/native/include/wpi/Base64.h +++ b/wpiutil/src/main/native/include/wpi/Base64.h @@ -6,12 +6,11 @@ #define WPIUTIL_WPI_BASE64_H_ #include +#include #include #include #include -#include "wpi/span.h" - namespace wpi { template class SmallVectorImpl; @@ -26,8 +25,8 @@ std::string_view Base64Decode(std::string_view encoded, size_t* num_read, size_t Base64Decode(std::string_view encoded, std::vector* plain); -span Base64Decode(std::string_view encoded, size_t* num_read, - SmallVectorImpl& buf); +std::span Base64Decode(std::string_view encoded, size_t* num_read, + SmallVectorImpl& buf); void Base64Encode(raw_ostream& os, std::string_view plain); @@ -36,11 +35,11 @@ void Base64Encode(std::string_view plain, std::string* encoded); std::string_view Base64Encode(std::string_view plain, SmallVectorImpl& buf); -void Base64Encode(raw_ostream& os, span plain); +void Base64Encode(raw_ostream& os, std::span plain); -void Base64Encode(span plain, std::string* encoded); +void Base64Encode(std::span plain, std::string* encoded); -std::string_view Base64Encode(span plain, +std::string_view Base64Encode(std::span plain, SmallVectorImpl& buf); } // namespace wpi diff --git a/wpiutil/src/main/native/include/wpi/DataLog.h b/wpiutil/src/main/native/include/wpi/DataLog.h index c66cd10cc64..cac273cdb6a 100644 --- a/wpiutil/src/main/native/include/wpi/DataLog.h +++ b/wpiutil/src/main/native/include/wpi/DataLog.h @@ -9,6 +9,7 @@ #include #include #include +#include #include #include #include @@ -18,7 +19,6 @@ #include "wpi/StringMap.h" #include "wpi/condition_variable.h" #include "wpi/mutex.h" -#include "wpi/span.h" namespace wpi { class Logger; @@ -106,7 +106,7 @@ class DataLog final { * this is a time/storage tradeoff * @param extraHeader extra header data */ - explicit DataLog(std::function data)> write, + explicit DataLog(std::function data)> write, double period = 0.25, std::string_view extraHeader = ""); /** @@ -122,7 +122,7 @@ class DataLog final { * @param extraHeader extra header data */ explicit DataLog(wpi::Logger& msglog, - std::function data)> write, + std::function data)> write, double period = 0.25, std::string_view extraHeader = ""); ~DataLog(); @@ -196,7 +196,7 @@ class DataLog final { * @param data Data to record * @param timestamp Time stamp (may be 0 to indicate now) */ - void AppendRaw(int entry, wpi::span data, int64_t timestamp); + void AppendRaw(int entry, std::span data, int64_t timestamp); /** * Appends a record to the log. @@ -205,7 +205,7 @@ class DataLog final { * @param data Data to record * @param timestamp Time stamp (may be 0 to indicate now) */ - void AppendRaw2(int entry, wpi::span> data, + void AppendRaw2(int entry, std::span> data, int64_t timestamp); void AppendBoolean(int entry, bool value, int64_t timestamp); @@ -213,33 +213,33 @@ class DataLog final { void AppendFloat(int entry, float value, int64_t timestamp); void AppendDouble(int entry, double value, int64_t timestamp); void AppendString(int entry, std::string_view value, int64_t timestamp); - void AppendBooleanArray(int entry, wpi::span arr, + void AppendBooleanArray(int entry, std::span arr, int64_t timestamp); - void AppendBooleanArray(int entry, wpi::span arr, + void AppendBooleanArray(int entry, std::span arr, int64_t timestamp); - void AppendBooleanArray(int entry, wpi::span arr, + void AppendBooleanArray(int entry, std::span arr, int64_t timestamp); - void AppendIntegerArray(int entry, wpi::span arr, + void AppendIntegerArray(int entry, std::span arr, int64_t timestamp); - void AppendFloatArray(int entry, wpi::span arr, + void AppendFloatArray(int entry, std::span arr, int64_t timestamp); - void AppendDoubleArray(int entry, wpi::span arr, + void AppendDoubleArray(int entry, std::span arr, int64_t timestamp); - void AppendStringArray(int entry, wpi::span arr, + void AppendStringArray(int entry, std::span arr, int64_t timestamp); - void AppendStringArray(int entry, wpi::span arr, + void AppendStringArray(int entry, std::span arr, int64_t timestamp); private: void WriterThreadMain(std::string_view dir); void WriterThreadMain( - std::function data)> write); + std::function data)> write); // must be called with m_mutex held uint8_t* StartRecord(uint32_t entry, uint64_t timestamp, uint32_t payloadSize, size_t reserveSize); uint8_t* Reserve(size_t size); - void AppendImpl(wpi::span data); + void AppendImpl(std::span data); void AppendStringImpl(std::string_view str); wpi::Logger& m_msglog; @@ -338,7 +338,7 @@ class RawLogEntry : public DataLogEntry { * @param data Data to record * @param timestamp Time stamp (may be 0 to indicate now) */ - void Append(wpi::span data, int64_t timestamp = 0) { + void Append(std::span data, int64_t timestamp = 0) { m_log->AppendRaw(m_entry, data, timestamp); } }; @@ -493,7 +493,7 @@ class BooleanArrayLogEntry : public DataLogEntry { * @param arr Values to record * @param timestamp Time stamp (may be 0 to indicate now) */ - void Append(wpi::span arr, int64_t timestamp = 0) { + void Append(std::span arr, int64_t timestamp = 0) { m_log->AppendBooleanArray(m_entry, arr, timestamp); } @@ -504,7 +504,7 @@ class BooleanArrayLogEntry : public DataLogEntry { * @param timestamp Time stamp (may be 0 to indicate now) */ void Append(std::initializer_list arr, int64_t timestamp = 0) { - Append(wpi::span{arr.begin(), arr.end()}, timestamp); + Append(std::span{arr.begin(), arr.end()}, timestamp); } /** @@ -513,7 +513,7 @@ class BooleanArrayLogEntry : public DataLogEntry { * @param arr Values to record * @param timestamp Time stamp (may be 0 to indicate now) */ - void Append(wpi::span arr, int64_t timestamp = 0) { + void Append(std::span arr, int64_t timestamp = 0) { m_log->AppendBooleanArray(m_entry, arr, timestamp); } @@ -524,7 +524,7 @@ class BooleanArrayLogEntry : public DataLogEntry { * @param timestamp Time stamp (may be 0 to indicate now) */ void Append(std::initializer_list arr, int64_t timestamp = 0) { - Append(wpi::span{arr.begin(), arr.end()}, timestamp); + Append(std::span{arr.begin(), arr.end()}, timestamp); } /** @@ -533,7 +533,7 @@ class BooleanArrayLogEntry : public DataLogEntry { * @param arr Values to record * @param timestamp Time stamp (may be 0 to indicate now) */ - void Append(wpi::span arr, int64_t timestamp = 0) { + void Append(std::span arr, int64_t timestamp = 0) { m_log->AppendBooleanArray(m_entry, arr, timestamp); } }; @@ -559,7 +559,7 @@ class IntegerArrayLogEntry : public DataLogEntry { * @param arr Values to record * @param timestamp Time stamp (may be 0 to indicate now) */ - void Append(wpi::span arr, int64_t timestamp = 0) { + void Append(std::span arr, int64_t timestamp = 0) { m_log->AppendIntegerArray(m_entry, arr, timestamp); } @@ -594,7 +594,7 @@ class FloatArrayLogEntry : public DataLogEntry { * @param arr Values to record * @param timestamp Time stamp (may be 0 to indicate now) */ - void Append(wpi::span arr, int64_t timestamp = 0) { + void Append(std::span arr, int64_t timestamp = 0) { m_log->AppendFloatArray(m_entry, arr, timestamp); } @@ -630,7 +630,7 @@ class DoubleArrayLogEntry : public DataLogEntry { * @param arr Values to record * @param timestamp Time stamp (may be 0 to indicate now) */ - void Append(wpi::span arr, int64_t timestamp = 0) { + void Append(std::span arr, int64_t timestamp = 0) { m_log->AppendDoubleArray(m_entry, arr, timestamp); } @@ -666,7 +666,7 @@ class StringArrayLogEntry : public DataLogEntry { * @param arr Values to record * @param timestamp Time stamp (may be 0 to indicate now) */ - void Append(wpi::span arr, int64_t timestamp = 0) { + void Append(std::span arr, int64_t timestamp = 0) { m_log->AppendStringArray(m_entry, arr, timestamp); } @@ -676,7 +676,7 @@ class StringArrayLogEntry : public DataLogEntry { * @param arr Values to record * @param timestamp Time stamp (may be 0 to indicate now) */ - void Append(wpi::span arr, int64_t timestamp = 0) { + void Append(std::span arr, int64_t timestamp = 0) { m_log->AppendStringArray(m_entry, arr, timestamp); } @@ -688,7 +688,7 @@ class StringArrayLogEntry : public DataLogEntry { */ void Append(std::initializer_list arr, int64_t timestamp = 0) { - Append(wpi::span{arr.begin(), arr.end()}, + Append(std::span{arr.begin(), arr.end()}, timestamp); } }; diff --git a/wpiutil/src/main/native/include/wpi/DataLogReader.h b/wpiutil/src/main/native/include/wpi/DataLogReader.h index 6883bcd733c..b1153e4228d 100644 --- a/wpiutil/src/main/native/include/wpi/DataLogReader.h +++ b/wpiutil/src/main/native/include/wpi/DataLogReader.h @@ -8,11 +8,11 @@ #include #include +#include #include #include #include "wpi/MemoryBuffer.h" -#include "wpi/span.h" namespace wpi::log { @@ -54,7 +54,7 @@ struct MetadataRecordData { class DataLogRecord { public: DataLogRecord() = default; - DataLogRecord(int entry, int64_t timestamp, wpi::span data) + DataLogRecord(int entry, int64_t timestamp, std::span data) : m_timestamp{timestamp}, m_data{data}, m_entry{entry} {} /** @@ -82,7 +82,7 @@ class DataLogRecord { * Gets the raw data. Use the GetX functions to decode based on the data type * in the entry's start record. */ - wpi::span GetRaw() const { return m_data; } + std::span GetRaw() const { return m_data; } /** * Returns true if the record is a control record. @@ -241,7 +241,7 @@ class DataLogRecord { private: int64_t m_timestamp{0}; - wpi::span m_data; + std::span m_data; int m_entry{-1}; }; diff --git a/wpiutil/src/main/native/include/wpi/MessagePack.h b/wpiutil/src/main/native/include/wpi/MessagePack.h index e32be7f6a75..e1f54e52578 100644 --- a/wpiutil/src/main/native/include/wpi/MessagePack.h +++ b/wpiutil/src/main/native/include/wpi/MessagePack.h @@ -6,11 +6,11 @@ #include +#include #include #include #include "wpi/mpack.h" -#include "wpi/span.h" namespace mpack { @@ -19,13 +19,13 @@ inline void mpack_write_str(mpack_writer_t* writer, std::string_view str) { } inline void mpack_write_bytes(mpack_writer_t* writer, - wpi::span data) { + std::span data) { mpack_write_bytes(writer, reinterpret_cast(data.data()), data.size()); } inline void mpack_reader_init_data(mpack_reader_t* reader, - wpi::span data) { + std::span data) { mpack_reader_init_data(reader, reinterpret_cast(data.data()), data.size()); } diff --git a/wpiutil/src/main/native/include/wpi/SpanExtras.h b/wpiutil/src/main/native/include/wpi/SpanExtras.h index 41e40146748..aa7b9abcf50 100644 --- a/wpiutil/src/main/native/include/wpi/SpanExtras.h +++ b/wpiutil/src/main/native/include/wpi/SpanExtras.h @@ -5,21 +5,22 @@ #pragma once #include - -#include "wpi/span.h" +#include namespace wpi { /// Drop the first \p N elements of the array. template -constexpr span drop_front(span in, typename span::size_type n = 1) { +constexpr std::span drop_front(std::span in, + typename std::span::size_type n = 1) { assert(in.size() >= n && "Dropping more elements than exist"); return in.subspan(n, in.size() - n); } /// Drop the last \p N elements of the array. template -constexpr span drop_back(span in, typename span::size_type n = 1) { +constexpr std::span drop_back(std::span in, + typename std::span::size_type n = 1) { assert(in.size() >= n && "Dropping more elements than exist"); return in.subspan(0, in.size() - n); } diff --git a/wpiutil/src/main/native/include/wpi/Synchronization.h b/wpiutil/src/main/native/include/wpi/Synchronization.h index b2aaac88a5d..774f17ea9ba 100644 --- a/wpiutil/src/main/native/include/wpi/Synchronization.h +++ b/wpiutil/src/main/native/include/wpi/Synchronization.h @@ -8,8 +8,7 @@ #ifdef __cplusplus #include - -#include "wpi/span.h" +#include #endif /** @@ -149,8 +148,8 @@ bool WaitForObject(WPI_Handle handle, double timeout, bool* timedOut); * least the size of the handles input array * @return array of signaled handles (points into signaled array) */ -wpi::span WaitForObjects(wpi::span handles, - wpi::span signaled); +std::span WaitForObjects(std::span handles, + std::span signaled); /** * Waits for one or more handles to be signaled. @@ -163,9 +162,9 @@ wpi::span WaitForObjects(wpi::span handles, * least the size of the handles input array * @return array of signaled handles (points into signaled array) */ -inline wpi::span WaitForObjects( - std::initializer_list handles, wpi::span signaled) { - return WaitForObjects(wpi::span{handles.begin(), handles.size()}, signaled); +inline std::span WaitForObjects( + std::initializer_list handles, std::span signaled) { + return WaitForObjects(std::span{handles.begin(), handles.size()}, signaled); } /** @@ -182,8 +181,8 @@ inline wpi::span WaitForObjects( * handle being signaled; set to false otherwise (output) * @return array of signaled handles (points into signaled array) */ -wpi::span WaitForObjects(wpi::span handles, - wpi::span signaled, +std::span WaitForObjects(std::span handles, + std::span signaled, double timeout, bool* timedOut); /** * Waits for one or more handles to be signaled, with timeout. @@ -199,10 +198,10 @@ wpi::span WaitForObjects(wpi::span handles, * handle being signaled; set to false otherwise (output) * @return array of signaled handles (points into signaled array) */ -inline wpi::span WaitForObjects( - std::initializer_list handles, wpi::span signaled, +inline std::span WaitForObjects( + std::initializer_list handles, std::span signaled, double timeout, bool* timedOut) { - return WaitForObjects(wpi::span{handles.begin(), handles.size()}, signaled, + return WaitForObjects(std::span{handles.begin(), handles.size()}, signaled, timeout, timedOut); } diff --git a/wpiutil/src/main/native/include/wpi/jni_util.h b/wpiutil/src/main/native/include/wpi/jni_util.h index 6ee26262176..8d50fdd11eb 100644 --- a/wpiutil/src/main/native/include/wpi/jni_util.h +++ b/wpiutil/src/main/native/include/wpi/jni_util.h @@ -8,6 +8,7 @@ #include #include +#include #include #include #include @@ -21,7 +22,6 @@ #include "wpi/StringExtras.h" #include "wpi/mutex.h" #include "wpi/raw_ostream.h" -#include "wpi/span.h" /** Java Native Interface (JNI) utility functions */ namespace wpi::java { @@ -154,7 +154,7 @@ class JStringRef { jsize size = env->GetStringLength(str); const jchar* chars = env->GetStringCritical(str, nullptr); if (chars) { - convertUTF16ToUTF8String(wpi::span(chars, size), m_str); + convertUTF16ToUTF8String(std::span(chars, size), m_str); env->ReleaseStringCritical(str, chars); } } else { @@ -181,7 +181,7 @@ namespace detail { template class JArrayRefInner { public: - operator span() const { // NOLINT + operator std::span() const { // NOLINT return static_cast(this)->array(); } }; @@ -203,7 +203,7 @@ class JArrayRefInner { return {reinterpret_cast(arr.data()), arr.size()}; } - span uarray() const { + std::span uarray() const { auto arr = static_cast(this)->array(); if (arr.empty()) { return {}; @@ -222,7 +222,7 @@ class JArrayRefInner { template >> - operator span() const { // NOLINT + operator std::span() const { // NOLINT auto arr = static_cast(this)->array(); if (arr.empty()) { return {}; @@ -239,7 +239,7 @@ class JArrayRefBase : public JArrayRefInner, T> { public: explicit operator bool() const { return this->m_elements != nullptr; } - span array() const { + std::span array() const { if (!this->m_elements) { return {}; } @@ -406,7 +406,7 @@ namespace detail { template ::value && sizeof(jint) == sizeof(T))> struct ConvertIntArray { - static jintArray ToJava(JNIEnv* env, span arr) { + static jintArray ToJava(JNIEnv* env, std::span arr) { jintArray jarr = env->NewIntArray(arr.size()); if (!jarr) { return nullptr; @@ -429,7 +429,7 @@ struct ConvertIntArray { */ template struct ConvertIntArray { - static jintArray ToJava(JNIEnv* env, span arr) { + static jintArray ToJava(JNIEnv* env, std::span arr) { jintArray jarr = env->NewIntArray(arr.size()); if (!jarr) { return nullptr; @@ -449,7 +449,7 @@ struct ConvertIntArray { * @param arr Span to convert. */ template -inline jintArray MakeJIntArray(JNIEnv* env, span arr) { +inline jintArray MakeJIntArray(JNIEnv* env, std::span arr) { return detail::ConvertIntArray::ToJava(env, arr); } @@ -460,7 +460,7 @@ inline jintArray MakeJIntArray(JNIEnv* env, span arr) { * @param arr Span to convert. */ template -inline jintArray MakeJIntArray(JNIEnv* env, span arr) { +inline jintArray MakeJIntArray(JNIEnv* env, std::span arr) { return detail::ConvertIntArray::ToJava(env, arr); } @@ -498,7 +498,7 @@ inline jintArray MakeJIntArray(JNIEnv* env, const std::vector& arr) { * @param env JRE environment. * @param str span to convert. */ -inline jbyteArray MakeJByteArray(JNIEnv* env, span str) { +inline jbyteArray MakeJByteArray(JNIEnv* env, std::span str) { jbyteArray jarr = env->NewByteArray(str.size()); if (!jarr) { return nullptr; @@ -514,7 +514,7 @@ inline jbyteArray MakeJByteArray(JNIEnv* env, span str) { * @param env JRE environment. * @param arr Array to convert. */ -inline jbooleanArray MakeJBooleanArray(JNIEnv* env, span arr) { +inline jbooleanArray MakeJBooleanArray(JNIEnv* env, std::span arr) { jbooleanArray jarr = env->NewBooleanArray(arr.size()); if (!jarr) { return nullptr; @@ -537,7 +537,7 @@ inline jbooleanArray MakeJBooleanArray(JNIEnv* env, span arr) { * @param env JRE environment. * @param arr Array to convert. */ -inline jbooleanArray MakeJBooleanArray(JNIEnv* env, span arr) { +inline jbooleanArray MakeJBooleanArray(JNIEnv* env, std::span arr) { jbooleanArray jarr = env->NewBooleanArray(arr.size()); if (!jarr) { return nullptr; @@ -556,14 +556,14 @@ inline jbooleanArray MakeJBooleanArray(JNIEnv* env, span arr) { // Other MakeJ*Array conversions. -#define WPI_JNI_MAKEJARRAY(T, F) \ - inline T##Array MakeJ##F##Array(JNIEnv* env, span arr) { \ - T##Array jarr = env->New##F##Array(arr.size()); \ - if (!jarr) { \ - return nullptr; \ - } \ - env->Set##F##ArrayRegion(jarr, 0, arr.size(), arr.data()); \ - return jarr; \ +#define WPI_JNI_MAKEJARRAY(T, F) \ + inline T##Array MakeJ##F##Array(JNIEnv* env, std::span arr) { \ + T##Array jarr = env->New##F##Array(arr.size()); \ + if (!jarr) { \ + return nullptr; \ + } \ + env->Set##F##ArrayRegion(jarr, 0, arr.size(), arr.data()); \ + return jarr; \ } WPI_JNI_MAKEJARRAY(jboolean, Boolean) @@ -593,7 +593,8 @@ inline jlongArray MakeJLongArray(JNIEnv* env, const T& arr) { * @param env JRE environment. * @param arr Array to convert. */ -inline jobjectArray MakeJStringArray(JNIEnv* env, span arr) { +inline jobjectArray MakeJStringArray(JNIEnv* env, + std::span arr) { static JClass stringCls{env, "java/lang/String"}; if (!stringCls) { return nullptr; @@ -615,7 +616,8 @@ inline jobjectArray MakeJStringArray(JNIEnv* env, span arr) { * @param env JRE environment. * @param arr Array to convert. */ -inline jobjectArray MakeJStringArray(JNIEnv* env, span arr) { +inline jobjectArray MakeJStringArray(JNIEnv* env, + std::span arr) { static JClass stringCls{env, "java/lang/String"}; if (!stringCls) { return nullptr; diff --git a/wpiutil/src/main/native/include/wpi/leb128.h b/wpiutil/src/main/native/include/wpi/leb128.h index 04752c6f6f4..e89d5055440 100644 --- a/wpiutil/src/main/native/include/wpi/leb128.h +++ b/wpiutil/src/main/native/include/wpi/leb128.h @@ -8,8 +8,7 @@ #include #include - -#include "wpi/span.h" +#include namespace wpi { @@ -100,7 +99,7 @@ class Uleb128Reader { * is left when function returns). * @return value (in std::optional) */ - std::optional ReadOne(span* in); + std::optional ReadOne(std::span* in); private: uint64_t m_result = 0; diff --git a/wpiutil/src/main/native/include/wpi/math b/wpiutil/src/main/native/include/wpi/math deleted file mode 100644 index 25f2a64aac8..00000000000 --- a/wpiutil/src/main/native/include/wpi/math +++ /dev/null @@ -1,20 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#pragma once - -#include "wpi/numbers" - -// clang-format off -#ifdef _MSC_VER -#pragma message("warning: Use and wpi::numbers instead to reflect C++20 and std::numbers") -#else -#warning "Use and wpi::numbers instead to reflect C++20 and std::numbers" -#endif - -// clang-format on - -namespace wpi::math { -using namespace wpi::numbers; -} // namespace wpi::math diff --git a/wpiutil/src/main/native/include/wpi/numbers b/wpiutil/src/main/native/include/wpi/numbers deleted file mode 100644 index d45aee04208..00000000000 --- a/wpiutil/src/main/native/include/wpi/numbers +++ /dev/null @@ -1,64 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#pragma once - -#include - -namespace wpi::numbers { - -template >> -inline constexpr T e_v = 2.718281828459045235360287471352662498L; - -template >> -inline constexpr T log2e_v = 1.442695040888963407359924681001892137L; - -template >> -inline constexpr T log10e_v = 0.434294481903251827651128918916605082L; - -template >> -inline constexpr T pi_v = 3.141592653589793238462643383279502884L; - -template >> -inline constexpr T inv_pi_v = 0.318309886183790671537767526745028724L; - -template >> -inline constexpr T inv_sqrtpi_v = 0.564189583547756286948079451560772586L; - -template >> -inline constexpr T ln2_v = 0.693147180559945309417232121458176568L; - -template >> -inline constexpr T ln10_v = 2.302585092994045684017991454684364208L; - -template >> -inline constexpr T sqrt2_v = 1.414213562373095048801688724209698078L; - -template >> -inline constexpr T sqrt3_v = 1.732050807568877293527446341505872366L; - -template >> -inline constexpr T inv_sqrt3_v = 0.577350269189625764509148780501957456L; - -template >> -inline constexpr T egamma_v = 0.577215664901532860606512090082402431L; - -template >> -inline constexpr T phi_v = 1.618033988749894848204586834365638117L; - -inline constexpr double e = e_v; -inline constexpr double log2e = log2e_v; -inline constexpr double log10e = log10e_v; -inline constexpr double pi = pi_v; -inline constexpr double inv_pi = inv_pi_v; -inline constexpr double inv_sqrtpi = inv_sqrtpi_v; -inline constexpr double ln2 = ln2_v; -inline constexpr double ln10 = ln10_v; -inline constexpr double sqrt2 = sqrt2_v; -inline constexpr double sqrt3 = sqrt3_v; -inline constexpr double inv_sqrt3 = inv_sqrt3_v; -inline constexpr double egamma = egamma_v; -inline constexpr double phi = phi_v; - -} // namespace wpi::numbers diff --git a/wpiutil/src/main/native/include/wpi/raw_istream.h b/wpiutil/src/main/native/include/wpi/raw_istream.h index 2371fc666c4..2f278c86a03 100644 --- a/wpiutil/src/main/native/include/wpi/raw_istream.h +++ b/wpiutil/src/main/native/include/wpi/raw_istream.h @@ -9,13 +9,13 @@ #include #include +#include #include #include #include #include #include "wpi/SmallVector.h" -#include "wpi/span.h" namespace wpi { @@ -133,9 +133,9 @@ class raw_mem_istream : public raw_istream { // not const as we don't want to allow temporaries explicit raw_mem_istream(std::string& str) : raw_mem_istream(str.data(), str.size()) {} - explicit raw_mem_istream(span mem) + explicit raw_mem_istream(std::span mem) : raw_mem_istream(mem.data(), mem.size()) {} - explicit raw_mem_istream(span mem) + explicit raw_mem_istream(std::span mem) : raw_mem_istream(reinterpret_cast(mem.data()), mem.size()) { } explicit raw_mem_istream(const char* str) diff --git a/wpiutil/src/main/native/include/wpi/sendable/SendableBuilder.h b/wpiutil/src/main/native/include/wpi/sendable/SendableBuilder.h index 8b2c3041229..2287b731cc0 100644 --- a/wpiutil/src/main/native/include/wpi/sendable/SendableBuilder.h +++ b/wpiutil/src/main/native/include/wpi/sendable/SendableBuilder.h @@ -6,12 +6,12 @@ #include #include +#include #include #include #include #include "wpi/SmallVector.h" -#include "wpi/span.h" namespace wpi { @@ -112,7 +112,7 @@ class SendableBuilder { */ virtual void AddBooleanArrayProperty( std::string_view key, std::function()> getter, - std::function)> setter) = 0; + std::function)> setter) = 0; /** * Add an integer array property. @@ -123,7 +123,7 @@ class SendableBuilder { */ virtual void AddIntegerArrayProperty( std::string_view key, std::function()> getter, - std::function)> setter) = 0; + std::function)> setter) = 0; /** * Add a float array property. @@ -134,7 +134,7 @@ class SendableBuilder { */ virtual void AddFloatArrayProperty( std::string_view key, std::function()> getter, - std::function)> setter) = 0; + std::function)> setter) = 0; /** * Add a double array property. @@ -145,7 +145,7 @@ class SendableBuilder { */ virtual void AddDoubleArrayProperty( std::string_view key, std::function()> getter, - std::function)> setter) = 0; + std::function)> setter) = 0; /** * Add a string array property. @@ -156,7 +156,7 @@ class SendableBuilder { */ virtual void AddStringArrayProperty( std::string_view key, std::function()> getter, - std::function)> setter) = 0; + std::function)> setter) = 0; /** * Add a raw property. @@ -169,7 +169,7 @@ class SendableBuilder { virtual void AddRawProperty( std::string_view key, std::string_view typeString, std::function()> getter, - std::function)> setter) = 0; + std::function)> setter) = 0; /** * Add a string property (SmallString form). @@ -192,9 +192,9 @@ class SendableBuilder { */ virtual void AddSmallBooleanArrayProperty( std::string_view key, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::SmallVectorImpl& buf)> getter, - std::function)> setter) = 0; + std::function)> setter) = 0; /** * Add an integer array property (SmallVector form). @@ -206,9 +206,9 @@ class SendableBuilder { virtual void AddSmallIntegerArrayProperty( std::string_view key, std::function< - wpi::span(wpi::SmallVectorImpl& buf)> + std::span(wpi::SmallVectorImpl& buf)> getter, - std::function)> setter) = 0; + std::function)> setter) = 0; /** * Add a float array property (SmallVector form). @@ -219,9 +219,9 @@ class SendableBuilder { */ virtual void AddSmallFloatArrayProperty( std::string_view key, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::SmallVectorImpl& buf)> getter, - std::function)> setter) = 0; + std::function)> setter) = 0; /** * Add a double array property (SmallVector form). @@ -232,9 +232,9 @@ class SendableBuilder { */ virtual void AddSmallDoubleArrayProperty( std::string_view key, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::SmallVectorImpl& buf)> getter, - std::function)> setter) = 0; + std::function)> setter) = 0; /** * Add a string array property (SmallVector form). @@ -246,9 +246,9 @@ class SendableBuilder { virtual void AddSmallStringArrayProperty( std::string_view key, std::function< - wpi::span(wpi::SmallVectorImpl& buf)> + std::span(wpi::SmallVectorImpl& buf)> getter, - std::function)> setter) = 0; + std::function)> setter) = 0; /** * Add a raw property (SmallVector form). @@ -260,9 +260,9 @@ class SendableBuilder { */ virtual void AddSmallRawProperty( std::string_view key, std::string_view typeString, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::SmallVectorImpl& buf)> getter, - std::function)> setter) = 0; + std::function)> setter) = 0; /** * Gets the kind of backend being used. diff --git a/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/core.h b/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/core.h index f6a37af9e35..5c210bcb842 100644 --- a/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/core.h +++ b/wpiutil/src/main/native/thirdparty/fmtlib/include/fmt/core.h @@ -2952,7 +2952,7 @@ class format_string_checker { basic_string_view format_str, ErrorHandler eh) : context_(format_str, num_args, types_, eh), parse_funcs_{&parse_format_specs...}, - types_{ + types_{ // NOLINT(clang-analyzer-optin.cplusplus.UninitializedObject) mapped_type_constant>::value...} { } diff --git a/wpiutil/src/main/native/thirdparty/json/cpp/json_binary_reader.cpp b/wpiutil/src/main/native/thirdparty/json/cpp/json_binary_reader.cpp index cee5e3942a5..2081359dbc3 100644 --- a/wpiutil/src/main/native/thirdparty/json/cpp/json_binary_reader.cpp +++ b/wpiutil/src/main/native/thirdparty/json/cpp/json_binary_reader.cpp @@ -1384,7 +1384,7 @@ json json::from_cbor(raw_istream& is, const bool strict) return binary_reader(is).parse_cbor(strict); } -json json::from_cbor(span arr, const bool strict) +json json::from_cbor(std::span arr, const bool strict) { raw_mem_istream is(arr); return from_cbor(is, strict); @@ -1395,7 +1395,7 @@ json json::from_msgpack(raw_istream& is, const bool strict) return binary_reader(is).parse_msgpack(strict); } -json json::from_msgpack(span arr, const bool strict) +json json::from_msgpack(std::span arr, const bool strict) { raw_mem_istream is(arr); return from_msgpack(is, strict); @@ -1406,7 +1406,7 @@ json json::from_ubjson(raw_istream& is, const bool strict) return binary_reader(is).parse_ubjson(strict); } -json json::from_ubjson(span arr, const bool strict) +json json::from_ubjson(std::span arr, const bool strict) { raw_mem_istream is(arr); return from_ubjson(is, strict); diff --git a/wpiutil/src/main/native/thirdparty/json/cpp/json_binary_writer.cpp b/wpiutil/src/main/native/thirdparty/json/cpp/json_binary_writer.cpp index db23f8dda1d..e25d478860a 100644 --- a/wpiutil/src/main/native/thirdparty/json/cpp/json_binary_writer.cpp +++ b/wpiutil/src/main/native/thirdparty/json/cpp/json_binary_writer.cpp @@ -813,7 +813,7 @@ void json::binary_writer::write_number(const NumberType n) std::reverse(vec.begin(), vec.end()); } - o << span{vec.data(), sizeof(NumberType)}; + o << std::span{vec.data(), sizeof(NumberType)}; } template json::to_cbor(const json& j) return result; } -span json::to_cbor(const json& j, std::vector& buf) +std::span json::to_cbor(const json& j, std::vector& buf) { buf.clear(); raw_uvector_ostream os(buf); @@ -1012,7 +1012,7 @@ span json::to_cbor(const json& j, std::vector& buf) return os.array(); } -span json::to_cbor(const json& j, SmallVectorImpl& buf) +std::span json::to_cbor(const json& j, SmallVectorImpl& buf) { buf.clear(); raw_usvector_ostream os(buf); @@ -1033,7 +1033,7 @@ std::vector json::to_msgpack(const json& j) return result; } -span json::to_msgpack(const json& j, std::vector& buf) +std::span json::to_msgpack(const json& j, std::vector& buf) { buf.clear(); raw_uvector_ostream os(buf); @@ -1041,7 +1041,7 @@ span json::to_msgpack(const json& j, std::vector& buf) return os.array(); } -span json::to_msgpack(const json& j, SmallVectorImpl& buf) +std::span json::to_msgpack(const json& j, SmallVectorImpl& buf) { buf.clear(); raw_usvector_ostream os(buf); @@ -1064,7 +1064,7 @@ std::vector json::to_ubjson(const json& j, return result; } -span json::to_ubjson(const json& j, std::vector& buf, +std::span json::to_ubjson(const json& j, std::vector& buf, const bool use_size, const bool use_type) { buf.clear(); @@ -1073,7 +1073,7 @@ span json::to_ubjson(const json& j, std::vector& buf, return os.array(); } -span json::to_ubjson(const json& j, SmallVectorImpl& buf, +std::span json::to_ubjson(const json& j, SmallVectorImpl& buf, const bool use_size, const bool use_type) { buf.clear(); diff --git a/wpiutil/src/main/native/thirdparty/json/cpp/json_parser.cpp b/wpiutil/src/main/native/thirdparty/json/cpp/json_parser.cpp index db1ed11d423..3c294896c98 100644 --- a/wpiutil/src/main/native/thirdparty/json/cpp/json_parser.cpp +++ b/wpiutil/src/main/native/thirdparty/json/cpp/json_parser.cpp @@ -1921,11 +1921,11 @@ json json::parse(std::string_view s, const parser_callback_t cb, const bool allow_exceptions) { - raw_mem_istream is(span(s.data(), s.size())); + raw_mem_istream is(std::span(s.data(), s.size())); return parse(is, cb, allow_exceptions); } -json json::parse(span arr, +json json::parse(std::span arr, const parser_callback_t cb, const bool allow_exceptions) { @@ -1944,11 +1944,11 @@ json json::parse(raw_istream& i, bool json::accept(std::string_view s) { - raw_mem_istream is(span(s.data(), s.size())); + raw_mem_istream is(std::span(s.data(), s.size())); return parser(is).accept(true); } -bool json::accept(span arr) +bool json::accept(std::span arr) { raw_mem_istream is(arr); return parser(is).accept(true); diff --git a/wpiutil/src/main/native/thirdparty/json/include/wpi/json.h b/wpiutil/src/main/native/thirdparty/json/include/wpi/json.h index 1a4e410f418..1c07deb7d50 100644 --- a/wpiutil/src/main/native/thirdparty/json/include/wpi/json.h +++ b/wpiutil/src/main/native/thirdparty/json/include/wpi/json.h @@ -43,7 +43,6 @@ SOFTWARE. #include // all_of, copy, find, for_each, generate_n, min, reverse, remove, fill, none_of, transform #include // array #include // assert -#include // and, not, or #include // nullptr_t, ptrdiff_t, size_t #include // uint8_t, uint16_t, uint32_t, uint64_t #include // exception @@ -52,6 +51,7 @@ SOFTWARE. #include #include // numeric_limits #include // allocator, shared_ptr, make_shared, addressof +#include #include // runtime_error #include // string, char_traits, stoi, to_string #include @@ -61,7 +61,6 @@ SOFTWARE. #include // vector #include "wpi/StringMap.h" -#include "wpi/span.h" namespace wpi { @@ -1126,7 +1125,7 @@ struct external_constructor } template - static void construct(BasicJsonType& j, span arr) + static void construct(BasicJsonType& j, std::span arr) { using std::begin; using std::end; @@ -7015,7 +7014,7 @@ class json const parser_callback_t cb = nullptr, const bool allow_exceptions = true); - static json parse(span arr, + static json parse(std::span arr, const parser_callback_t cb = nullptr, const bool allow_exceptions = true); @@ -7028,7 +7027,7 @@ class json static bool accept(std::string_view s); - static bool accept(span arr); + static bool accept(std::span arr); static bool accept(raw_istream& i); @@ -7206,8 +7205,8 @@ class json @since version 2.0.9 */ static std::vector to_cbor(const json& j); - static span to_cbor(const json& j, std::vector& buf); - static span to_cbor(const json& j, SmallVectorImpl& buf); + static std::span to_cbor(const json& j, std::vector& buf); + static std::span to_cbor(const json& j, SmallVectorImpl& buf); static void to_cbor(raw_ostream& os, const json& j); /*! @@ -7291,8 +7290,8 @@ class json @since version 2.0.9 */ static std::vector to_msgpack(const json& j); - static span to_msgpack(const json& j, std::vector& buf); - static span to_msgpack(const json& j, SmallVectorImpl& buf); + static std::span to_msgpack(const json& j, std::vector& buf); + static std::span to_msgpack(const json& j, SmallVectorImpl& buf); static void to_msgpack(raw_ostream& os, const json& j); /*! @@ -7378,9 +7377,9 @@ class json static std::vector to_ubjson(const json& j, const bool use_size = false, const bool use_type = false); - static span to_ubjson(const json& j, std::vector& buf, + static std::span to_ubjson(const json& j, std::vector& buf, const bool use_size = false, const bool use_type = false); - static span to_ubjson(const json& j, SmallVectorImpl& buf, + static std::span to_ubjson(const json& j, SmallVectorImpl& buf, const bool use_size = false, const bool use_type = false); static void to_ubjson(raw_ostream& os, const json& j, const bool use_size = false, const bool use_type = false); @@ -7484,7 +7483,7 @@ class json /*! @copydoc from_cbor(raw_istream&, const bool) */ - static json from_cbor(span arr, const bool strict = true); + static json from_cbor(std::span arr, const bool strict = true); /*! @brief create a JSON value from an input in MessagePack format @@ -7565,7 +7564,7 @@ class json /*! @copydoc from_msgpack(raw_istream&, const bool) */ - static json from_msgpack(span arr, const bool strict = true); + static json from_msgpack(std::span arr, const bool strict = true); /*! @brief create a JSON value from an input in UBJSON format @@ -7623,7 +7622,7 @@ class json static json from_ubjson(raw_istream& is, const bool strict = true); - static json from_ubjson(span arr, const bool strict = true); + static json from_ubjson(std::span arr, const bool strict = true); /// @} diff --git a/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/ConvertUTFWrapper.cpp b/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/ConvertUTFWrapper.cpp index 09a98264612..e95c04fba97 100644 --- a/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/ConvertUTFWrapper.cpp +++ b/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/ConvertUTFWrapper.cpp @@ -6,7 +6,7 @@ // //===----------------------------------------------------------------------===// -#include "wpi/span.h" +#include #include "wpi/ConvertUTF.h" #include "wpi/SmallVector.h" #include "wpi/ErrorHandling.h" @@ -21,7 +21,7 @@ bool ConvertUTF8toWide(unsigned WideCharWidth, std::string_view Source, char *&ResultPtr, const UTF8 *&ErrorPtr) { assert(WideCharWidth == 1 || WideCharWidth == 2 || WideCharWidth == 4); ConversionResult result = conversionOK; - // Copy the character span over. + // Copy the character std::span over. if (WideCharWidth == 1) { const UTF8 *Pos = reinterpret_cast(Source.data()); if (!isLegalUTF8String(&Pos, reinterpret_cast(Source.data() + Source.size()))) { @@ -78,13 +78,13 @@ bool ConvertCodePointToUTF8(unsigned Source, char *&ResultPtr) { return true; } -bool hasUTF16ByteOrderMark(span S) { +bool hasUTF16ByteOrderMark(std::span S) { return (S.size() >= 2 && ((S[0] == '\xff' && S[1] == '\xfe') || (S[0] == '\xfe' && S[1] == '\xff'))); } -bool convertUTF16ToUTF8String(span SrcBytes, SmallVectorImpl &Out) { +bool convertUTF16ToUTF8String(std::span SrcBytes, SmallVectorImpl &Out) { assert(Out.empty()); // Error out on an uneven byte count. @@ -95,8 +95,8 @@ bool convertUTF16ToUTF8String(span SrcBytes, SmallVectorImpl & if (SrcBytes.empty()) return true; - const UTF16 *Src = reinterpret_cast(SrcBytes.begin()); - const UTF16 *SrcEnd = reinterpret_cast(SrcBytes.end()); + const UTF16 *Src = reinterpret_cast(&*SrcBytes.begin()); + const UTF16 *SrcEnd = reinterpret_cast(&*SrcBytes.begin() + SrcBytes.size()); assert((uintptr_t)Src % sizeof(UTF16) == 0); @@ -135,10 +135,10 @@ bool convertUTF16ToUTF8String(span SrcBytes, SmallVectorImpl & return true; } -bool convertUTF16ToUTF8String(span Src, SmallVectorImpl &Out) +bool convertUTF16ToUTF8String(std::span Src, SmallVectorImpl &Out) { return convertUTF16ToUTF8String( - span(reinterpret_cast(Src.data()), + std::span(reinterpret_cast(Src.data()), Src.size() * sizeof(UTF16)), Out); } @@ -225,7 +225,7 @@ bool convertWideToUTF8(const std::wstring &Source, SmallVectorImpl &Result return true; } else if (sizeof(wchar_t) == 2) { return convertUTF16ToUTF8String( - span(reinterpret_cast(Source.data()), + std::span(reinterpret_cast(Source.data()), Source.size()), Result); } else if (sizeof(wchar_t) == 4) { diff --git a/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/MemoryBuffer.cpp b/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/MemoryBuffer.cpp index a1adadb2004..ac2fbf5d454 100644 --- a/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/MemoryBuffer.cpp +++ b/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/MemoryBuffer.cpp @@ -104,8 +104,8 @@ namespace { template class MemoryBufferMem : public MB { public: - explicit MemoryBufferMem(span inputData) { - MemoryBuffer::Init(inputData.begin(), inputData.end()); + explicit MemoryBufferMem(std::span inputData) { + MemoryBuffer::Init(&*inputData.begin(), &*inputData.end()); } /// Disable sized deallocation for MemoryBufferMem, because it has @@ -129,7 +129,7 @@ static std::unique_ptr GetFileAux(std::string_view filename, uint64_t mapSize, uint64_t offset); std::unique_ptr MemoryBuffer::GetMemBuffer( - span inputData, std::string_view bufferName) { + std::span inputData, std::string_view bufferName) { auto* ret = new (NamedBufferAlloc(bufferName)) MemoryBufferMem(inputData); return std::unique_ptr(ret); @@ -141,7 +141,7 @@ std::unique_ptr MemoryBuffer::GetMemBuffer(MemoryBufferRef ref) { } static std::unique_ptr GetMemBufferCopyImpl( - span inputData, std::string_view bufferName, + std::span inputData, std::string_view bufferName, std::error_code& ec) { auto buf = WritableMemoryBuffer::GetNewUninitMemBuffer(inputData.size(), bufferName); @@ -154,7 +154,7 @@ static std::unique_ptr GetMemBufferCopyImpl( } std::unique_ptr MemoryBuffer::GetMemBufferCopy( - span inputData, std::string_view bufferName) { + std::span inputData, std::string_view bufferName) { std::error_code ec; return GetMemBufferCopyImpl(inputData, bufferName, ec); } diff --git a/wpiutil/src/main/native/thirdparty/llvm/include/wpi/ConvertUTF.h b/wpiutil/src/main/native/thirdparty/llvm/include/wpi/ConvertUTF.h index a5f80468b80..436bc6d58b5 100644 --- a/wpiutil/src/main/native/thirdparty/llvm/include/wpi/ConvertUTF.h +++ b/wpiutil/src/main/native/thirdparty/llvm/include/wpi/ConvertUTF.h @@ -89,7 +89,7 @@ #ifndef WPIUTIL_WPI_CONVERTUTF_H #define WPIUTIL_WPI_CONVERTUTF_H -#include "wpi/span.h" +#include #include #include @@ -259,7 +259,7 @@ inline ConversionResult convertUTF8Sequence(const UTF8 **source, * Returns true if a blob of text starts with a UTF-16 big or little endian byte * order mark. */ -bool hasUTF16ByteOrderMark(span SrcBytes); +bool hasUTF16ByteOrderMark(std::span SrcBytes); /** * Converts a stream of raw bytes assumed to be UTF16 into a UTF8 std::string. @@ -268,7 +268,7 @@ bool hasUTF16ByteOrderMark(span SrcBytes); * \param [out] Out Converted UTF-8 is stored here on success. * \returns true on success */ -bool convertUTF16ToUTF8String(span SrcBytes, SmallVectorImpl &Out); +bool convertUTF16ToUTF8String(std::span SrcBytes, SmallVectorImpl &Out); /** * Converts a UTF16 string into a UTF8 std::string. @@ -277,7 +277,7 @@ bool convertUTF16ToUTF8String(span SrcBytes, SmallVectorImpl & * \param [out] Out Converted UTF-8 is stored here on success. * \returns true on success */ -bool convertUTF16ToUTF8String(span Src, SmallVectorImpl &Out); +bool convertUTF16ToUTF8String(std::span Src, SmallVectorImpl &Out); /** * Converts a UTF-8 string into a UTF-16 string with native endianness. diff --git a/wpiutil/src/main/native/thirdparty/llvm/include/wpi/MemoryBuffer.h b/wpiutil/src/main/native/thirdparty/llvm/include/wpi/MemoryBuffer.h index 330d1b19b46..7907c07d678 100644 --- a/wpiutil/src/main/native/thirdparty/llvm/include/wpi/MemoryBuffer.h +++ b/wpiutil/src/main/native/thirdparty/llvm/include/wpi/MemoryBuffer.h @@ -21,11 +21,10 @@ #include #include +#include #include #include -#include "wpi/span.h" - // Duplicated from fs.h to avoid a dependency namespace fs { #if defined(_WIN32) @@ -61,7 +60,7 @@ class MemoryBuffer { const uint8_t* end() const { return m_bufferEnd; } size_t size() const { return m_bufferEnd - m_bufferStart; } - span GetBuffer() const { return {begin(), end()}; } + std::span GetBuffer() const { return {begin(), end()}; } /// Return an identifier for this buffer, typically the filename it was read /// from. @@ -98,14 +97,14 @@ class MemoryBuffer { /// Open the specified memory range as a MemoryBuffer. static std::unique_ptr GetMemBuffer( - span inputData, std::string_view bufferName = ""); + std::span inputData, std::string_view bufferName = ""); static std::unique_ptr GetMemBuffer(MemoryBufferRef ref); /// Open the specified memory range as a MemoryBuffer, copying the contents /// and taking ownership of it. static std::unique_ptr GetMemBufferCopy( - span inputData, std::string_view bufferName = ""); + std::span inputData, std::string_view bufferName = ""); /// Map a subrange of the specified file as a MemoryBuffer. static std::unique_ptr GetFileSlice(std::string_view filename, @@ -145,7 +144,7 @@ class WritableMemoryBuffer : public MemoryBuffer { // guaranteed to have been initialized with a mutable buffer. uint8_t* begin() { return const_cast(MemoryBuffer::begin()); } uint8_t* end() { return const_cast(MemoryBuffer::end()); } - span GetBuffer() { return {begin(), end()}; } + std::span GetBuffer() { return {begin(), end()}; } static std::unique_ptr GetFile( std::string_view filename, std::error_code& ec, int64_t fileSize = -1); @@ -196,7 +195,7 @@ class WriteThroughMemoryBuffer : public MemoryBuffer { // guaranteed to have been initialized with a mutable buffer. uint8_t* begin() { return const_cast(MemoryBuffer::begin()); } uint8_t* end() { return const_cast(MemoryBuffer::end()); } - span GetBuffer() { return {begin(), end()}; } + std::span GetBuffer() { return {begin(), end()}; } static std::unique_ptr GetFile( std::string_view filename, std::error_code& ec, int64_t fileSize = -1); @@ -218,22 +217,22 @@ class WriteThroughMemoryBuffer : public MemoryBuffer { }; class MemoryBufferRef { - span m_buffer; + std::span m_buffer; std::string_view m_id; public: MemoryBufferRef() = default; MemoryBufferRef(MemoryBuffer& buffer) // NOLINT : m_buffer(buffer.GetBuffer()), m_id(buffer.GetBufferIdentifier()) {} - MemoryBufferRef(span buffer, std::string_view id) + MemoryBufferRef(std::span buffer, std::string_view id) : m_buffer(buffer), m_id(id) {} - span GetBuffer() const { return m_buffer; } + std::span GetBuffer() const { return m_buffer; } std::string_view GetBufferIdentifier() const { return m_id; } - const uint8_t* begin() const { return m_buffer.begin(); } - const uint8_t* end() const { return m_buffer.end(); } + const uint8_t* begin() const { return &*m_buffer.begin(); } + const uint8_t* end() const { return &*m_buffer.end(); } size_t size() const { return m_buffer.size(); } }; diff --git a/wpiutil/src/main/native/thirdparty/llvm/include/wpi/raw_ostream.h b/wpiutil/src/main/native/thirdparty/llvm/include/wpi/raw_ostream.h index 83854f61413..350262bdfcf 100644 --- a/wpiutil/src/main/native/thirdparty/llvm/include/wpi/raw_ostream.h +++ b/wpiutil/src/main/native/thirdparty/llvm/include/wpi/raw_ostream.h @@ -14,7 +14,7 @@ #define WPIUTIL_WPI_RAW_OSTREAM_H #include "wpi/SmallVector.h" -#include "wpi/span.h" +#include #include #include #include @@ -199,7 +199,7 @@ class raw_ostream { return *this; } - raw_ostream &operator<<(span Arr) { + raw_ostream &operator<<(std::span Arr) { // Inline fast path, particularly for arrays with a known length. size_t Size = Arr.size(); @@ -675,9 +675,9 @@ class raw_usvector_ostream : public raw_pwrite_stream { void flush() = delete; - /// Return an span for the vector contents. - span array() { return {OS.data(), OS.size()}; } - span array() const { return {OS.data(), OS.size()}; } + /// Return an std::span for the vector contents. + std::span array() { return {OS.data(), OS.size()}; } + std::span array() const { return {OS.data(), OS.size()}; } }; /// A raw_ostream that writes to a vector. This is a @@ -709,9 +709,9 @@ class raw_uvector_ostream : public raw_pwrite_stream { void flush() = delete; - /// Return a span for the vector contents. - span array() { return {OS.data(), OS.size()}; } - span array() const { return {OS.data(), OS.size()}; } + /// Return a std::span for the vector contents. + std::span array() { return {OS.data(), OS.size()}; } + std::span array() const { return {OS.data(), OS.size()}; } }; diff --git a/wpiutil/src/main/native/thirdparty/tcb_span/include/wpi/span.h b/wpiutil/src/main/native/thirdparty/tcb_span/include/wpi/span.h deleted file mode 100644 index cf71d79f80d..00000000000 --- a/wpiutil/src/main/native/thirdparty/tcb_span/include/wpi/span.h +++ /dev/null @@ -1,415 +0,0 @@ - -/* -This is an implementation of C++20's std::span -http://www.open-std.org/jtc1/sc22/wg21/docs/papers/2019/n4820.pdf -*/ - -// Copyright Tristan Brindle 2018. -// Distributed under the Boost Software License, Version 1.0. -// (See accompanying file ../../LICENSE_1_0.txt or copy at -// https://www.boost.org/LICENSE_1_0.txt) - -#ifndef WPIUTIL_WPI_SPAN_HPP_INCLUDED -#define WPIUTIL_WPI_SPAN_HPP_INCLUDED - -#include -#include -#include -#include -#include -#if __cplusplus >= 202002L && __has_include() -#include -#endif - -namespace wpi { - -inline constexpr std::size_t dynamic_extent = SIZE_MAX; - -template -class span; - -namespace detail { - -template -struct span_storage { - constexpr span_storage() noexcept = default; - - constexpr span_storage(E* p_ptr, std::size_t /*unused*/) noexcept - : ptr(p_ptr) - {} - - E* ptr = nullptr; - static constexpr std::size_t size = S; -}; - -template -struct span_storage { - constexpr span_storage() noexcept = default; - - constexpr span_storage(E* p_ptr, std::size_t p_size) noexcept - : ptr(p_ptr), size(p_size) - {} - - E* ptr = nullptr; - std::size_t size = 0; -}; - -template -using uncvref_t = - typename std::remove_cv::type>::type; - -template -struct is_span : std::false_type {}; - -template -struct is_span> : std::true_type {}; - -template -struct is_std_array : std::false_type {}; - -template -struct is_std_array> : std::true_type {}; - -template -struct has_size_and_data : std::false_type {}; - -template -struct has_size_and_data())), - decltype(std::data(std::declval()))>> - : std::true_type {}; - -template > -struct is_container { - static constexpr bool value = - !is_span::value && !is_std_array::value && - !std::is_array::value && has_size_and_data::value; -}; - -template -using remove_pointer_t = typename std::remove_pointer::type; - -template -struct is_container_element_type_compatible : std::false_type {}; - -template -struct is_container_element_type_compatible< - T, E, - typename std::enable_if< - !std::is_same()))>::type, - void>::value>::type> - : std::is_convertible< - remove_pointer_t()))> (*)[], - E (*)[]> {}; - -template -struct is_complete : std::false_type {}; - -template -struct is_complete : std::true_type {}; - -} // namespace detail - -template -class span { - static_assert(std::is_object::value, - "A span's ElementType must be an object type (not a " - "reference type or void)"); - static_assert(detail::is_complete::value, - "A span's ElementType must be a complete type (not a forward " - "declaration)"); - static_assert(!std::is_abstract::value, - "A span's ElementType cannot be an abstract class type"); - - using storage_type = detail::span_storage; - -public: - // constants and types - using element_type = ElementType; - using value_type = typename std::remove_cv::type; - using size_type = std::size_t; - using difference_type = std::ptrdiff_t; - using pointer = element_type*; - using const_pointer = const element_type*; - using reference = element_type&; - using const_reference = const element_type&; - using iterator = pointer; - using reverse_iterator = std::reverse_iterator; - - static constexpr size_type extent = Extent; - - // [span.cons], span constructors, copy, assignment, and destructor - template < - std::size_t E = Extent, - typename std::enable_if<(E == dynamic_extent || E <= 0), int>::type = 0> - constexpr span() noexcept - {} - - constexpr span(pointer ptr, size_type count) - : storage_(ptr, count) - { - assert(extent == dynamic_extent || count == extent); - } - - constexpr span(pointer first_elem, pointer last_elem) - : storage_(first_elem, last_elem - first_elem) - { - assert(extent == dynamic_extent || - last_elem - first_elem == - static_cast(extent)); - } - - template ::value, - int>::type = 0> - constexpr span(element_type (&arr)[N]) noexcept : storage_(arr, N) - {} - - template &, ElementType>::value, - int>::type = 0> - constexpr span(std::array& arr) noexcept - : storage_(arr.data(), N) - {} - - template &, ElementType>::value, - int>::type = 0> - constexpr span(const std::array& arr) noexcept - : storage_(arr.data(), N) - {} - - template < - typename Container, std::size_t E = Extent, - typename std::enable_if< - E == dynamic_extent && detail::is_container::value && - detail::is_container_element_type_compatible< - Container&, ElementType>::value, - int>::type = 0> - constexpr span(Container& cont) - : storage_(std::data(cont), std::size(cont)) - {} - - template < - typename Container, std::size_t E = Extent, - typename std::enable_if< - E == dynamic_extent && detail::is_container::value && - detail::is_container_element_type_compatible< - const Container&, ElementType>::value, - int>::type = 0> - constexpr span(const Container& cont) - : storage_(std::data(cont), std::size(cont)) - {} - - constexpr span(const span& other) noexcept = default; - - template ::value, - int>::type = 0> - constexpr span(const span& other) noexcept - : storage_(other.data(), other.size()) - {} - -#ifdef __cpp_lib_span - constexpr span(std::span other) noexcept - : storage_(other.data(), other.size()) - {} -#endif - - ~span() noexcept = default; - - constexpr span& - operator=(const span& other) noexcept = default; - - // [span.sub], span subviews - template - constexpr span first() const - { - assert(Count <= size()); - return {data(), Count}; - } - - template - constexpr span last() const - { - assert(Count <= size()); - return {data() + (size() - Count), Count}; - } - - template - using subspan_return_t = - span; - - template - constexpr subspan_return_t subspan() const - { - assert(Offset <= size() && - (Count == dynamic_extent || Offset + Count <= size())); - return {data() + Offset, - Count != dynamic_extent ? Count : size() - Offset}; - } - - constexpr span - first(size_type count) const - { - assert(count <= size()); - return {data(), count}; - } - - constexpr span - last(size_type count) const - { - assert(count <= size()); - return {data() + (size() - count), count}; - } - - constexpr span - subspan(size_type offset, size_type count = dynamic_extent) const - { - assert(offset <= size() && - (count == dynamic_extent || offset + count <= size())); - return {data() + offset, - count == dynamic_extent ? size() - offset : count}; - } - - // [span.obs], span observers - constexpr size_type size() const noexcept { return storage_.size; } - - constexpr size_type size_bytes() const noexcept - { - return size() * sizeof(element_type); - } - - [[nodiscard]] constexpr bool empty() const noexcept - { - return size() == 0; - } - - // [span.elem], span element access - constexpr reference operator[](size_type idx) const - { - assert(idx < size()); - return *(data() + idx); - } - - constexpr reference front() const - { - assert(!empty()); - return *data(); - } - - constexpr reference back() const - { - assert(!empty()); - return *(data() + (size() - 1)); - } - - constexpr pointer data() const noexcept { return storage_.ptr; } - - // [span.iterators], span iterator support - constexpr iterator begin() const noexcept { return data(); } - - constexpr iterator end() const noexcept { return data() + size(); } - - constexpr reverse_iterator rbegin() const noexcept - { - return reverse_iterator(end()); - } - - constexpr reverse_iterator rend() const noexcept - { - return reverse_iterator(begin()); - } - -#ifdef __cpp_lib_span - constexpr operator auto() const { - return std::span < ElementType, - (Extent == dynamic_extent) - ? std::dynamic_extent - : Extent > (storage_.ptr, storage_.size); - } -#endif - -private: - storage_type storage_{}; -}; - -/* Deduction Guides */ -template -span(T (&)[N])->span; - -template -span(std::array&)->span; - -template -span(const std::array&)->span; - -template -span(Container&)->span; - -template -span(const Container&)->span; - -template -span -as_bytes(span s) noexcept -{ - return {reinterpret_cast(s.data()), s.size_bytes()}; -} - -template < - class ElementType, size_t Extent, - typename std::enable_if::value, int>::type = 0> -span -as_writable_bytes(span s) noexcept -{ - return {reinterpret_cast(s.data()), s.size_bytes()}; -} - -template -constexpr auto get(span s) -> decltype(s[N]) -{ - return s[N]; -} - -} // namespace wpi - -namespace std { - -template -class tuple_size> - : public integral_constant {}; - -template -class tuple_size>; // not defined - -template -class tuple_element> { -public: - static_assert(Extent != wpi::dynamic_extent && - I < Extent, - ""); - using type = ElementType; -}; - -} // end namespace std - -#endif // WPIUTIL_WPI_SPAN_HPP_INCLUDED diff --git a/wpiutil/src/test/native/cpp/json/unit-readme.cpp b/wpiutil/src/test/native/cpp/json/unit-readme.cpp index 14d2b1bb5f2..d9bb9e51607 100644 --- a/wpiutil/src/test/native/cpp/json/unit-readme.cpp +++ b/wpiutil/src/test/native/cpp/json/unit-readme.cpp @@ -200,7 +200,7 @@ TEST(JsonReadmeTest, OtherContainer) { std::vector c_vector {1, 2, 3, 4}; json j_vec(c_vector); - json j_vec2(wpi::span(c_vector.data(), c_vector.size())); + json j_vec2(std::span(c_vector.data(), c_vector.size())); // [1, 2, 3, 4] std::deque c_deque {1.2f, 2.3f, 3.4f, 5.6f}; diff --git a/wpiutil/src/test/native/cpp/llvm/ConvertUTFTest.cpp b/wpiutil/src/test/native/cpp/llvm/ConvertUTFTest.cpp index 8e0837c9af1..762682e4ded 100644 --- a/wpiutil/src/test/native/cpp/llvm/ConvertUTFTest.cpp +++ b/wpiutil/src/test/native/cpp/llvm/ConvertUTFTest.cpp @@ -18,7 +18,7 @@ using namespace wpi; TEST(ConvertUTFTest, ConvertUTF16LittleEndianToUTF8String) { // Src is the look of disapproval. alignas(UTF16) static const char Src[] = "\xff\xfe\xa0\x0c_\x00\xa0\x0c"; - span Ref(Src, sizeof(Src) - 1); + std::span Ref(Src, sizeof(Src) - 1); SmallString<20> Result; bool Success = convertUTF16ToUTF8String(Ref, Result); EXPECT_TRUE(Success); @@ -29,7 +29,7 @@ TEST(ConvertUTFTest, ConvertUTF16LittleEndianToUTF8String) { TEST(ConvertUTFTest, ConvertUTF16BigEndianToUTF8String) { // Src is the look of disapproval. alignas(UTF16) static const char Src[] = "\xfe\xff\x0c\xa0\x00_\x0c\xa0"; - span Ref(Src, sizeof(Src) - 1); + std::span Ref(Src, sizeof(Src) - 1); SmallString<20> Result; bool Success = convertUTF16ToUTF8String(Ref, Result); EXPECT_TRUE(Success); @@ -52,13 +52,13 @@ TEST(ConvertUTFTest, ConvertUTF8ToUTF16String) { TEST(ConvertUTFTest, OddLengthInput) { SmallString<20> Result; - bool Success = convertUTF16ToUTF8String(span("xxxxx", 5), Result); + bool Success = convertUTF16ToUTF8String(std::span("xxxxx", 5), Result); EXPECT_FALSE(Success); } TEST(ConvertUTFTest, Empty) { SmallString<20> Result; - bool Success = convertUTF16ToUTF8String(span(), Result); + bool Success = convertUTF16ToUTF8String(std::span(), Result); EXPECT_TRUE(Success); EXPECT_TRUE(std::string{Result}.empty()); } @@ -82,7 +82,7 @@ TEST(ConvertUTFTest, HasUTF16BOM) { TEST(ConvertUTFTest, UTF16WrappersForConvertUTF16ToUTF8String) { // Src is the look of disapproval. alignas(UTF16) static const char Src[] = "\xff\xfe\xa0\x0c_\x00\xa0\x0c"; - span SrcRef((const UTF16 *)Src, 4); + std::span SrcRef((const UTF16 *)Src, 4); SmallString<20> Result; bool Success = convertUTF16ToUTF8String(SrcRef, Result); EXPECT_TRUE(Success); diff --git a/wpiutil/src/test/native/cpp/llvm/SmallVectorTest.cpp b/wpiutil/src/test/native/cpp/llvm/SmallVectorTest.cpp index 66cd5c2d390..a60e6838852 100644 --- a/wpiutil/src/test/native/cpp/llvm/SmallVectorTest.cpp +++ b/wpiutil/src/test/native/cpp/llvm/SmallVectorTest.cpp @@ -11,7 +11,7 @@ //===----------------------------------------------------------------------===// #include "wpi/SmallVector.h" -#include "wpi/span.h" +#include #include "wpi/Compiler.h" #include "gtest/gtest.h" #include diff --git a/wpiutil/src/test/native/cpp/span/test_conversions.cpp b/wpiutil/src/test/native/cpp/span/test_conversions.cpp deleted file mode 100644 index fa111a770ee..00000000000 --- a/wpiutil/src/test/native/cpp/span/test_conversions.cpp +++ /dev/null @@ -1,46 +0,0 @@ -#if __has_include() -#include -#endif -#include "wpi/span.h" - -#include "gtest/gtest.h" - -void func1(wpi::span x) {} -#ifdef __cpp_lib_span -void func2(std::span x) {} -#endif - -void func4(wpi::span x) {} -#ifdef __cpp_lib_span -void func5(std::span x) {} -#endif - -TEST(Span, ConvertStdSpan) { - func1(wpi::span{}); - func1(wpi::span{}); -#ifdef __cpp_lib_span - func1(std::span{}); - func1(std::span{}); -#endif - -#ifdef __cpp_lib_span - func2(wpi::span{}); - func2(wpi::span{}); - func2(std::span{}); - func2(std::span{}); -#endif - - //func4(wpi::span{}); - func4(wpi::span{}); -#ifdef __cpp_lib_span - //func4(std::span{}); - func4(std::span{}); -#endif - -#ifdef __cpp_lib_span - //func5(wpi::span{}); - func5(wpi::span{}); - //func5(std::span{}); - func5(std::span{}); -#endif -} diff --git a/wpiutil/src/test/native/cpp/span/test_deduction_guides.cpp b/wpiutil/src/test/native/cpp/span/test_deduction_guides.cpp deleted file mode 100644 index 9851b5e9481..00000000000 --- a/wpiutil/src/test/native/cpp/span/test_deduction_guides.cpp +++ /dev/null @@ -1,98 +0,0 @@ - -#include "wpi/span.h" - -#include "gtest/gtest.h" - -#include - -using wpi::span; - -namespace { - -template -constexpr bool equal(R1&& r1, R2&& r2) -{ - auto first1 = std::begin(r1); - const auto last1 = std::end(r1); - auto first2 = std::begin(r2); - const auto last2 = std::end(r2); - - while (first1 != last1 && first2 != last2) { - if (*first1 != *first2) { - return false; - } - ++first1; - ++first2; - } - - return true; -} - -constexpr bool test_raw_array() -{ - int arr[] = {1, 2, 3}; - auto s = span{arr}; - static_assert(std::is_same_v>); - - return equal(arr, s); -} - -constexpr bool test_const_raw_array() -{ - constexpr int arr[] = {1, 2, 3}; - auto s = span{arr}; - static_assert(std::is_same_v>); - - return equal(arr, s); -} - -constexpr bool test_std_array() -{ - auto arr = std::array{1, 2, 3}; - auto s = span{arr}; - static_assert(std::is_same_v>); - - return equal(arr, s); -} - -constexpr bool test_const_std_array() -{ - const auto arr = std::array{1, 2, 3}; - auto s = span{arr}; - static_assert(std::is_same_v>); - - return equal(arr, s); -} - -bool test_vec() -{ - auto arr = std::vector{1, 2, 3}; - auto s = span{arr}; - static_assert(std::is_same_v>); - - return equal(arr, s); -} - -bool test_const_vec() -{ - const auto arr = std::vector{1, 2, 3}; - auto s = span{arr}; - static_assert(std::is_same_v>); - - return equal(arr, s); -} - -} - -TEST(Deduction, FromRawArrays) -{ - static_assert(test_raw_array()); - static_assert(test_const_raw_array()); - static_assert(test_std_array()); - static_assert(test_const_std_array()); - - ASSERT_TRUE(test_std_array()); - ASSERT_TRUE(test_const_std_array()); - ASSERT_TRUE(test_vec()); - ASSERT_TRUE(test_const_vec()); -} diff --git a/wpiutil/src/test/native/cpp/span/test_span.cpp b/wpiutil/src/test/native/cpp/span/test_span.cpp deleted file mode 100644 index 7cecfd0fa91..00000000000 --- a/wpiutil/src/test/native/cpp/span/test_span.cpp +++ /dev/null @@ -1,663 +0,0 @@ - -#include "wpi/span.h" - -#include -#include -#include -#include -#include - -#include "gtest/gtest.h" - -using wpi::span; - -struct base {}; -struct derived : base {}; - -TEST(Span, DefaultConstruction) -{ - static_assert(std::is_nothrow_default_constructible>::value, ""); - static_assert(std::is_nothrow_default_constructible>::value, - ""); - static_assert(!std::is_default_constructible>::value, ""); - - //SECTION("dynamic size") - { - constexpr span s{}; - static_assert(s.size() == 0, ""); - static_assert(s.data() == nullptr, ""); - // This causes an ICE on MSVC -#ifndef _MSC_VER - static_assert(s.begin() == s.end(), ""); -#else - ASSERT_EQ(s.begin(), s.end()); -#endif - } - - //SECTION("fixed size") - { - constexpr span s{}; - static_assert(s.size() == 0, ""); - static_assert(s.data() == nullptr, ""); -#ifndef _MSC_VER - static_assert(s.begin() == s.end(), ""); -#else - ASSERT_EQ(s.begin(), s.end()); -#endif - } -} - -TEST(Span, PointerLengthConstruction) -{ - static_assert(std::is_constructible, int*, int>::value, ""); - static_assert(std::is_constructible, int*, int>::value, ""); - static_assert( - std::is_constructible, const int*, int>::value, ""); - - static_assert(std::is_constructible, int*, int>::value, ""); - static_assert(std::is_constructible, int*, int>::value, - ""); - static_assert( - std::is_constructible, const int*, int>::value, ""); - - //SECTION("dynamic size") - { - int arr[] = {1, 2, 3}; - span s(arr, 3); - - ASSERT_EQ(s.size(), 3u); - ASSERT_EQ(s.data(), arr); - ASSERT_EQ(s.begin(), std::begin(arr)); - ASSERT_EQ(s.end(), std::end(arr)); - } - - //SECTION("fixed size") - { - int arr[] = {1, 2, 3}; - span s(arr, 3); - - ASSERT_EQ(s.size(), 3u); - ASSERT_EQ(s.data(), arr); - ASSERT_EQ(s.begin(), std::begin(arr)); - ASSERT_EQ(s.end(), std::end(arr)); - } -} - -TEST(Span, PointerPointerConstruction) -{ - static_assert(std::is_constructible, int*, int*>::value, ""); - static_assert(!std::is_constructible, float*, float*>::value, ""); - static_assert(std::is_constructible, int*, int*>::value, ""); - static_assert(!std::is_constructible, float*, float*>::value, - ""); - - //SECTION("dynamic size") - { - int arr[] = {1, 2, 3}; - span s{arr, arr + 3}; - ASSERT_EQ(s.size(), 3u); - ASSERT_EQ(s.data(), arr); - ASSERT_EQ(s.begin(), std::begin(arr)); - ASSERT_EQ(s.end(), std::end(arr)); - } - - //SECTION("fixed size") - { - int arr[] = {1, 2, 3}; - span s{arr, arr + 3}; - ASSERT_EQ(s.size(), 3u); - ASSERT_EQ(s.data(), arr); - ASSERT_EQ(s.begin(), std::begin(arr)); - ASSERT_EQ(s.end(), std::end(arr)); - } -} - -TEST(Span, CArrayConstruction) -{ - using int_array_t = int[3]; - using float_array_t = float[3]; - - static_assert(std::is_nothrow_constructible, int_array_t&>::value, - ""); - static_assert(!std::is_constructible, int_array_t const&>::value, - ""); - static_assert(!std::is_constructible, float_array_t>::value, ""); - - static_assert( - std::is_nothrow_constructible, int_array_t&>::value, - ""); - static_assert(std::is_nothrow_constructible, - int_array_t const&>::value, - ""); - static_assert(!std::is_constructible, float_array_t>::value, - ""); - - static_assert( - std::is_nothrow_constructible, int_array_t&>::value, ""); - static_assert( - !std::is_constructible, int_array_t const&>::value, ""); - static_assert(!std::is_constructible, float_array_t&>::value, - ""); - - static_assert( - std::is_nothrow_constructible, int_array_t&>::value, - ""); - static_assert(std::is_nothrow_constructible, - int_array_t const&>::value, - ""); - static_assert( - !std::is_constructible, float_array_t>::value, ""); - - static_assert(!std::is_constructible, int_array_t&>::value, - ""); - static_assert( - !std::is_constructible, int_array_t const&>::value, ""); - static_assert(!std::is_constructible, float_array_t&>::value, - ""); - - static_assert( - !std::is_constructible, int_array_t&>::value, ""); - static_assert( - !std::is_constructible, int_array_t const&>::value, - ""); - static_assert( - !std::is_constructible, float_array_t&>::value, ""); - - //SECTION("non-const, dynamic size") - { - int arr[] = {1, 2, 3}; - span s{arr}; - ASSERT_EQ(s.size(), 3u); - ASSERT_EQ(s.data(), arr); - ASSERT_EQ(s.begin(), std::begin(arr)); - ASSERT_EQ(s.end(), std::end(arr)); - } - - //SECTION("const, dynamic size") - { - int arr[] = {1, 2, 3}; - span s{arr}; - ASSERT_EQ(s.size(), 3u); - ASSERT_EQ(s.data(), arr); - ASSERT_EQ(s.begin(), std::begin(arr)); - ASSERT_EQ(s.end(), std::end(arr)); - } - - //SECTION("non-const, static size") - { - int arr[] = {1, 2, 3}; - span s{arr}; - ASSERT_EQ(s.size(), 3u); - ASSERT_EQ(s.data(), arr); - ASSERT_EQ(s.begin(), std::begin(arr)); - ASSERT_EQ(s.end(), std::end(arr)); - } - - //SECTION("const, dynamic size") - { - int arr[] = {1, 2, 3}; - span s{arr}; - ASSERT_EQ(s.size(), 3u); - ASSERT_EQ(s.data(), arr); - ASSERT_EQ(s.begin(), std::begin(arr)); - ASSERT_EQ(s.end(), std::end(arr)); - } -} - -TEST(Span, StdArrayConstruction) -{ - using int_array_t = std::array; - using float_array_t = std::array; - using zero_array_t = std::array; - - static_assert(std::is_nothrow_constructible, int_array_t&>::value, - ""); - static_assert(!std::is_constructible, int_array_t const&>::value, - ""); - static_assert(!std::is_constructible, float_array_t>::value, ""); - - static_assert( - std::is_nothrow_constructible, int_array_t&>::value, - ""); - static_assert(std::is_nothrow_constructible, - int_array_t const&>::value, - ""); - static_assert( - !std::is_constructible, float_array_t const&>::value, - ""); - - static_assert( - std::is_nothrow_constructible, int_array_t&>::value, ""); - static_assert( - !std::is_constructible, int_array_t const&>::value, ""); - static_assert(!std::is_constructible, float_array_t>::value, - ""); - - static_assert( - std::is_nothrow_constructible, int_array_t&>::value, - ""); - static_assert(std::is_nothrow_constructible, - int_array_t const&>::value, - ""); - static_assert( - !std::is_constructible, float_array_t const&>::value, - ""); - - static_assert(!std::is_constructible, int_array_t&>::value, - ""); - static_assert( - !std::is_constructible, int_array_t const&>::value, ""); - static_assert( - !std::is_constructible, float_array_t const&>::value, ""); - - static_assert( - !std::is_constructible, int_array_t&>::value, ""); - static_assert( - !std::is_constructible, int_array_t const&>::value, - ""); - static_assert( - !std::is_constructible, float_array_t&>::value, ""); - - static_assert(std::is_constructible, zero_array_t&>::value, ""); - static_assert(!std::is_constructible, const zero_array_t&>::value, - ""); - static_assert(std::is_constructible, zero_array_t&>::value, - ""); - static_assert( - std::is_constructible, const zero_array_t&>::value, ""); - - static_assert(std::is_constructible, zero_array_t&>::value, - ""); - static_assert( - !std::is_constructible, const zero_array_t&>::value, ""); - static_assert( - std::is_constructible, zero_array_t&>::value, ""); - static_assert( - std::is_constructible, const zero_array_t&>::value, - ""); - - //SECTION("non-const, dynamic size") - { - int_array_t arr = {1, 2, 3}; - span s{arr}; - ASSERT_EQ(s.size(), 3u); - ASSERT_EQ(s.data(), arr.data()); - ASSERT_EQ(s.begin(), arr.data()); - ASSERT_EQ(s.end(), arr.data() + 3); - } - - //SECTION("const, dynamic size") - { - int_array_t arr = {1, 2, 3}; - span s{arr}; - ASSERT_EQ(s.size(), 3u); - ASSERT_EQ(s.data(), arr.data()); - ASSERT_EQ(s.begin(), arr.data()); - ASSERT_EQ(s.end(), arr.data() + 3); - } - - //SECTION("non-const, static size") - { - int_array_t arr = {1, 2, 3}; - span s{arr}; - ASSERT_EQ(s.size(), 3u); - ASSERT_EQ(s.data(), arr.data()); - ASSERT_EQ(s.begin(), arr.data()); - ASSERT_EQ(s.end(), arr.data() + 3); - } - - //SECTION("const, dynamic size") - { - int_array_t arr = {1, 2, 3}; - span s{arr}; - ASSERT_EQ(s.size(), 3u); - ASSERT_EQ(s.data(), arr.data()); - ASSERT_EQ(s.begin(), arr.data()); - ASSERT_EQ(s.end(), arr.data() + 3); - } -} - -TEST(Span, ConstructionFromOtherContainers) -{ - using vec_t = std::vector; - using deque_t = std::deque; - - static_assert(std::is_constructible, vec_t&>::value, ""); - static_assert(!std::is_constructible, const vec_t&>::value, ""); - static_assert(!std::is_constructible, const deque_t&>::value, ""); - - static_assert(std::is_constructible, vec_t&>::value, ""); - static_assert(std::is_constructible, const vec_t&>::value, - ""); - static_assert( - !std::is_constructible, const deque_t&>::value, ""); - - static_assert(!std::is_constructible, vec_t&>::value, ""); - static_assert(!std::is_constructible, const vec_t&>::value, - ""); - static_assert(!std::is_constructible, const deque_t&>::value, - ""); - - static_assert(!std::is_constructible, vec_t&>::value, ""); - static_assert( - !std::is_constructible, const vec_t&>::value, ""); - static_assert( - !std::is_constructible, const deque_t&>::value, ""); - - // vector is not contiguous and cannot be converted to span - // Regression test for https://github.com/tcbrindle/span/issues/24 - static_assert( - !std::is_constructible, std::vector&>::value, ""); - static_assert(!std::is_constructible, - const std::vector&>::value, ""); - - //SECTION("non-const, dynamic size") - { - vec_t arr = {1, 2, 3}; - span s{arr}; - ASSERT_EQ(s.size(), 3u); - ASSERT_EQ(s.data(), arr.data()); - ASSERT_EQ(s.begin(), arr.data()); - ASSERT_EQ(s.end(), arr.data() + 3); - } - - //SECTION("const, dynamic size") - { - vec_t arr = {1, 2, 3}; - span s{arr}; - ASSERT_EQ(s.size(), 3u); - ASSERT_EQ(s.data(), arr.data()); - ASSERT_EQ(s.begin(), arr.data()); - ASSERT_EQ(s.end(), arr.data() + 3); - } - - //SECTION("non-const, static size") - { - std::array arr = {1, 2, 3}; - span s{arr}; - ASSERT_EQ(s.size(), 3u); - ASSERT_EQ(s.data(), arr.data()); - ASSERT_EQ(s.begin(), arr.data()); - ASSERT_EQ(s.end(), arr.data() + 3); - } - - //SECTION("const, dynamic size") - { - std::array arr = {1, 2, 3}; - span s{arr}; - ASSERT_EQ(s.size(), 3u); - ASSERT_EQ(s.data(), arr.data()); - ASSERT_EQ(s.begin(), arr.data()); - ASSERT_EQ(s.end(), arr.data() + 3); - } -} - -TEST(Span, ConstructionFromSpansOfDifferentSize) -{ - using zero_span = span; - using zero_const_span = span; - using big_span = span; - using big_const_span = span; - using dynamic_span = span; - using dynamic_const_span = span; - - static_assert(std::is_trivially_copyable::value, ""); - static_assert(std::is_trivially_move_constructible::value, ""); - static_assert(!std::is_constructible::value, - ""); - static_assert(!std::is_constructible::value, ""); - static_assert(!std::is_constructible::value, ""); - static_assert(!std::is_constructible::value, ""); - static_assert(!std::is_constructible::value, - ""); - - static_assert( - std::is_nothrow_constructible::value, ""); - static_assert(std::is_trivially_copyable::value, ""); - static_assert(std::is_trivially_move_constructible::value, - ""); - static_assert(!std::is_constructible::value, ""); - static_assert( - !std::is_constructible::value, ""); - static_assert(!std::is_constructible::value, - ""); - static_assert( - !std::is_constructible::value, ""); - - static_assert(!std::is_constructible::value, ""); - static_assert(!std::is_constructible::value, ""); - static_assert(std::is_trivially_copyable::value, ""); - static_assert(std::is_trivially_move_constructible::value, ""); - static_assert(!std::is_constructible::value, ""); - static_assert(!std::is_constructible::value, ""); - static_assert(!std::is_constructible::value, - ""); - - static_assert(!std::is_constructible::value, ""); - static_assert( - !std::is_constructible::value, ""); - static_assert(std::is_trivially_copyable::value, ""); - static_assert(std::is_trivially_move_constructible::value, - ""); - static_assert( - std::is_nothrow_constructible::value, ""); - static_assert(!std::is_constructible::value, - ""); - static_assert( - !std::is_constructible::value, ""); - - static_assert(std::is_nothrow_constructible::value, - ""); - static_assert(!std::is_constructible::value, - ""); - static_assert(std::is_nothrow_constructible::value, - ""); - static_assert(!std::is_constructible::value, - ""); - static_assert(std::is_trivially_copyable::value, ""); - static_assert(std::is_trivially_move_constructible::value, - ""); - static_assert( - !std::is_constructible::value, ""); - - static_assert( - std::is_nothrow_constructible::value, - ""); - static_assert(std::is_nothrow_constructible::value, - ""); - static_assert( - std::is_nothrow_constructible::value, ""); - static_assert(std::is_nothrow_constructible::value, - ""); - static_assert( - std::is_nothrow_constructible::value, - ""); - static_assert(std::is_trivially_copyable::value, ""); - static_assert( - std::is_trivially_move_constructible::value, ""); - - constexpr zero_const_span s0{}; - constexpr dynamic_const_span d{s0}; - - static_assert(d.size() == 0, ""); - static_assert(d.data() == nullptr, ""); -#ifndef _MSC_VER - static_assert(d.begin() == d.end(), ""); -#else - ASSERT_EQ(d.begin(), d.end()); -#endif -} - -TEST(Span, MemberSubviewOperations) -{ - //SECTION("first") - { - int arr[] = {1, 2, 3, 4, 5}; - span s{arr}; - auto f = s.first<3>(); - - static_assert(std::is_same>::value, ""); - ASSERT_EQ(f.size(), 3u); - ASSERT_EQ(f.data(), arr); - ASSERT_EQ(f.begin(), arr); - ASSERT_EQ(f.end(), arr + 3); - } - - //SECTION("last") - { - int arr[] = {1, 2, 3, 4, 5}; - span s{arr}; - auto l = s.last<3>(); - - static_assert(std::is_same>::value, ""); - ASSERT_EQ(l.size(), 3u); - ASSERT_EQ(l.data(), arr + 2); - ASSERT_EQ(l.begin(), arr + 2); - ASSERT_EQ(l.end(), std::end(arr)); - } - - //SECTION("subspan") - { - int arr[] = {1, 2, 3, 4, 5}; - span s{arr}; - auto ss = s.subspan<1, 2>(); - - static_assert(std::is_same>::value, ""); - ASSERT_EQ(ss.size(), 2u); - ASSERT_EQ(ss.data(), arr + 1); - ASSERT_EQ(ss.begin(), arr + 1); - ASSERT_EQ(ss.end(), arr + 1 + 2); - } - - //SECTION("first(n)") - { - int arr[] = {1, 2, 3, 4, 5}; - span s{arr}; - auto f = s.first(3); - - static_assert(std::is_same>::value, ""); - ASSERT_EQ(f.size(), 3u); - ASSERT_EQ(f.data(), arr); - ASSERT_EQ(f.begin(), arr); - ASSERT_EQ(f.end(), arr + 3); - } - - //SECTION("last(n)") - { - int arr[] = {1, 2, 3, 4, 5}; - span s{arr}; - auto l = s.last(3); - - static_assert(std::is_same>::value, ""); - ASSERT_EQ(l.size(), 3u); - ASSERT_EQ(l.data(), arr + 2); - ASSERT_EQ(l.begin(), arr + 2); - ASSERT_EQ(l.end(), std::end(arr)); - } - - //SECTION("subspan(n)") - { - int arr[] = {1, 2, 3, 4, 5}; - span s{arr}; - auto ss = s.subspan(1, 2); - - static_assert(std::is_same>::value, ""); - ASSERT_EQ(ss.size(), 2u); - ASSERT_EQ(ss.data(), arr + 1); - ASSERT_EQ(ss.begin(), arr + 1); - ASSERT_EQ(ss.end(), arr + 1 + 2); - } - - // TODO: Test all the dynamic subspan possibilities -} - -TEST(Span, Observers) -{ - // We already use this everywhere, but whatever - constexpr span empty{}; - static_assert(empty.size() == 0, ""); - static_assert(empty.empty(), ""); - - constexpr int arr[] = {1, 2, 3}; - static_assert(span{arr}.size() == 3, ""); - static_assert(!span{arr}.empty(), ""); -} - -TEST(Span, ElementAccess) -{ - constexpr int arr[] = {1, 2, 3}; - span s{arr}; - - ASSERT_EQ(s[0], arr[0]); - ASSERT_EQ(s[1], arr[1]); - ASSERT_EQ(s[2], arr[2]); -} - -TEST(Span, IteratorSupport) -{ - { - std::vector vec; - span s{vec}; - std::sort(s.begin(), s.end()); - ASSERT_TRUE(std::is_sorted(vec.cbegin(), vec.cend())); - } - - { - const std::vector vec{1, 2, 3}; - span s{vec}; - ASSERT_TRUE(std::equal(s.rbegin(), s.rend(), vec.crbegin())); - } -} - -TEST(Span, MakeSpan) -{ - { - int arr[3] = {1, 2, 3}; - auto s = wpi::span(arr); - static_assert(std::is_same>::value, ""); - ASSERT_EQ(s.data(), arr); - ASSERT_EQ(s.size(), 3u); - } - - { - const int arr[3] = {1, 2, 3}; - auto s = wpi::span(arr); - static_assert(std::is_same>::value, ""); - ASSERT_EQ(s.data(), arr); - ASSERT_EQ(s.size(), 3u); - } - - { - std::array arr = {1, 2, 3}; - auto s = wpi::span(arr); - static_assert(std::is_same>::value, ""); - ASSERT_EQ(s.data(), arr.data()); - ASSERT_EQ(s.size(), arr.size()); - } - - { - const std::array arr = {1, 2, 3}; - auto s = wpi::span(arr); - static_assert(std::is_same>::value, ""); - ASSERT_EQ(s.data(), arr.data()); - ASSERT_EQ(s.size(), 3u); - } - - { - std::vector arr = {1, 2, 3}; - auto s = wpi::span(arr); - static_assert(std::is_same>::value, ""); - ASSERT_EQ(s.data(), arr.data()); - ASSERT_EQ(s.size(), arr.size()); - } - - { - const std::vector arr = {1, 2, 3}; - auto s = wpi::span(arr); - static_assert(std::is_same>::value, ""); - ASSERT_EQ(s.data(), arr.data()); - ASSERT_EQ(s.size(), arr.size()); - } -} diff --git a/wpiutil/src/test/native/cpp/span/test_structured_bindings.cpp b/wpiutil/src/test/native/cpp/span/test_structured_bindings.cpp deleted file mode 100644 index 5ce29693bc2..00000000000 --- a/wpiutil/src/test/native/cpp/span/test_structured_bindings.cpp +++ /dev/null @@ -1,30 +0,0 @@ - -#include "wpi/span.h" - -#include "gtest/gtest.h" - -using static_span_t = wpi::span; -using dynamic_span_t = wpi::span; - -static_assert(std::tuple_size_v == static_span_t::extent); -static_assert(!wpi::detail::is_complete>::value); - -TEST(StructuredBindings, Test) -{ - // C++, why you no let me do constexpr structured bindings? - - int arr[] = {1, 2, 3}; - - auto& [a1, a2, a3] = arr; - auto&& [s1, s2, s3] = wpi::span(arr); - - ASSERT_EQ(a1, s1); - ASSERT_EQ(a2, s2); - ASSERT_EQ(a3, s3); - - a1 = 99; - ASSERT_EQ(s1, 99); - - s2 = 100; - ASSERT_EQ(a2, 100); -}