mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
Upgrade to C++20 (#4239)
* Use explicit this capture required by C++20 * Use C++20 span * Replace wpi::numbers with std::numbers * Fix C++20 clang-tidy warning false positive in fmt * Remove ciso646 include since C++20 removed that header * Fix global-buffer-overflow asan warnings in ntcore tests * Add DIOSetProxy constructor to HAL * Upgrade MSVC compiler to 2022 * Bump native-utils to 2023.2.7 (changes to std=c++20) Co-authored-by: Peter Johnson <johnson.peter@gmail.com>
This commit is contained in:
@@ -4,13 +4,12 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <span>
|
||||
#include <string>
|
||||
#include <string_view>
|
||||
#include <utility>
|
||||
#include <vector>
|
||||
|
||||
#include <wpi/span.h>
|
||||
|
||||
#include "ntcore_cpp.h"
|
||||
|
||||
namespace nt {
|
||||
@@ -20,7 +19,7 @@ class INetworkClient {
|
||||
virtual ~INetworkClient() = default;
|
||||
|
||||
virtual void SetServers(
|
||||
wpi::span<const std::pair<std::string, unsigned int>> servers) = 0;
|
||||
std::span<const std::pair<std::string, unsigned int>> servers) = 0;
|
||||
|
||||
virtual void StartDSClient(unsigned int port) = 0;
|
||||
virtual void StopDSClient() = 0;
|
||||
|
||||
@@ -98,7 +98,7 @@ struct TopicData {
|
||||
struct PubSubConfig : public PubSubOptions {
|
||||
PubSubConfig() = default;
|
||||
PubSubConfig(NT_Type type, std::string_view typeStr,
|
||||
wpi::span<const PubSubOption> options)
|
||||
std::span<const PubSubOption> 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<const std::string_view> prefixes,
|
||||
std::span<const std::string_view> 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<const std::string> prefixes,
|
||||
std::span<const std::string> prefixes,
|
||||
unsigned int eventMask)
|
||||
: handle{handle},
|
||||
poller{poller},
|
||||
@@ -385,7 +385,7 @@ struct LSImpl {
|
||||
std::unique_ptr<EntryData> RemoveEntry(NT_Entry entryHandle);
|
||||
|
||||
MultiSubscriberData* AddMultiSubscriber(
|
||||
wpi::span<const std::string_view> prefixes, const PubSubOptions& options);
|
||||
std::span<const std::string_view> prefixes, const PubSubOptions& options);
|
||||
std::unique_ptr<MultiSubscriberData> RemoveMultiSubscriber(
|
||||
NT_MultiSubscriber subHandle);
|
||||
|
||||
@@ -403,9 +403,9 @@ struct LSImpl {
|
||||
unsigned int eventMask);
|
||||
TopicListenerData* AddTopicListenerImpl(
|
||||
TopicListenerPollerData* poller,
|
||||
wpi::span<const std::string_view> prefixes, unsigned int eventMask);
|
||||
std::span<const std::string_view> prefixes, unsigned int eventMask);
|
||||
NT_TopicListener AddTopicListener(
|
||||
wpi::span<const std::string_view> prefixes, unsigned int mask,
|
||||
std::span<const std::string_view> prefixes, unsigned int mask,
|
||||
std::function<void(const TopicNotification&)> callback);
|
||||
NT_TopicListener AddTopicListenerHandle(TopicListenerPollerData* poller,
|
||||
NT_Handle handle, unsigned int mask);
|
||||
@@ -1053,7 +1053,7 @@ std::unique_ptr<EntryData> LSImpl::RemoveEntry(NT_Entry entryHandle) {
|
||||
}
|
||||
|
||||
MultiSubscriberData* LSImpl::AddMultiSubscriber(
|
||||
wpi::span<const std::string_view> prefixes, const PubSubOptions& options) {
|
||||
std::span<const std::string_view> 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<const std::string_view> prefixes,
|
||||
TopicListenerPollerData* poller, std::span<const std::string_view> 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<const std::string_view> prefixes, unsigned int mask,
|
||||
std::span<const std::string_view> prefixes, unsigned int mask,
|
||||
std::function<void(const TopicNotification&)> 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 <typename T, typename F>
|
||||
static void ForEachTopic(T& topics, std::string_view prefix,
|
||||
wpi::span<const std::string_view> types, F func) {
|
||||
std::span<const std::string_view> types, F func) {
|
||||
for (auto&& topic : topics) {
|
||||
if (!topic->Exists()) {
|
||||
continue;
|
||||
@@ -1674,7 +1674,7 @@ std::vector<NT_Topic> LocalStorage::GetTopics(std::string_view prefix,
|
||||
}
|
||||
|
||||
std::vector<NT_Topic> LocalStorage::GetTopics(
|
||||
std::string_view prefix, wpi::span<const std::string_view> types) {
|
||||
std::string_view prefix, std::span<const std::string_view> types) {
|
||||
std::scoped_lock lock(m_mutex);
|
||||
std::vector<NT_Topic> rv;
|
||||
ForEachTopic(m_impl->m_topics, prefix, types,
|
||||
@@ -1693,7 +1693,7 @@ std::vector<TopicInfo> LocalStorage::GetTopicInfo(std::string_view prefix,
|
||||
}
|
||||
|
||||
std::vector<TopicInfo> LocalStorage::GetTopicInfo(
|
||||
std::string_view prefix, wpi::span<const std::string_view> types) {
|
||||
std::string_view prefix, std::span<const std::string_view> types) {
|
||||
std::scoped_lock lock(m_mutex);
|
||||
std::vector<TopicInfo> 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<const PubSubOption> options) {
|
||||
std::span<const PubSubOption> 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<const std::string_view> prefixes,
|
||||
wpi::span<const PubSubOption> options) {
|
||||
std::span<const std::string_view> prefixes,
|
||||
std::span<const PubSubOption> 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<const PubSubOption> options) {
|
||||
std::span<const PubSubOption> 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<const PubSubOption> options) {
|
||||
std::span<const PubSubOption> options) {
|
||||
std::scoped_lock lock{m_mutex};
|
||||
|
||||
// Get the topic
|
||||
@@ -2038,7 +2038,7 @@ static T GetAtomicNumber(Value* value, U defaultValue) {
|
||||
}
|
||||
|
||||
template <typename T, typename U>
|
||||
static T GetAtomicNumberArray(Value* value, wpi::span<const U> defaultValue) {
|
||||
static T GetAtomicNumberArray(Value* value, std::span<const U> 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<const U> defaultValue) {
|
||||
|
||||
template <typename T, typename U>
|
||||
static T GetAtomicNumberArray(Value* value, wpi::SmallVectorImpl<U>& buf,
|
||||
wpi::span<const U> defaultValue) {
|
||||
std::span<const U> 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<U>& buf,
|
||||
} \
|
||||
\
|
||||
Timestamped##Name##Array LocalStorage::GetAtomic##Name##Array( \
|
||||
NT_Handle subentry, wpi::span<const dtype> defaultValue) { \
|
||||
NT_Handle subentry, std::span<const dtype> defaultValue) { \
|
||||
std::scoped_lock lock{m_mutex}; \
|
||||
return GetAtomicNumberArray<Timestamped##Name##Array>( \
|
||||
m_impl->GetSubEntryValue(subentry), defaultValue); \
|
||||
@@ -2091,7 +2091,7 @@ static T GetAtomicNumberArray(Value* value, wpi::SmallVectorImpl<U>& buf,
|
||||
\
|
||||
Timestamped##Name##ArrayView LocalStorage::GetAtomic##Name##Array( \
|
||||
NT_Handle subentry, wpi::SmallVectorImpl<dtype>& buf, \
|
||||
wpi::span<const dtype> defaultValue) { \
|
||||
std::span<const dtype> defaultValue) { \
|
||||
std::scoped_lock lock{m_mutex}; \
|
||||
return GetAtomicNumberArray<Timestamped##Name##ArrayView>( \
|
||||
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<const dtype> defaultValue) { \
|
||||
NT_Handle subentry, std::span<const dtype> 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<dtype>& buf, \
|
||||
wpi::span<const dtype> defaultValue) { \
|
||||
std::span<const dtype> 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<const std::string_view> prefixes, unsigned int mask,
|
||||
std::span<const std::string_view> prefixes, unsigned int mask,
|
||||
std::function<void(const TopicNotification&)> 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<const std::string_view> prefixes, unsigned int mask) {
|
||||
std::span<const std::string_view> 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;
|
||||
|
||||
@@ -8,13 +8,13 @@
|
||||
|
||||
#include <functional>
|
||||
#include <memory>
|
||||
#include <span>
|
||||
#include <string>
|
||||
#include <string_view>
|
||||
#include <utility>
|
||||
#include <vector>
|
||||
|
||||
#include <wpi/mutex.h>
|
||||
#include <wpi/span.h>
|
||||
|
||||
#include "net/NetworkInterface.h"
|
||||
#include "ntcore_cpp.h"
|
||||
@@ -50,12 +50,12 @@ class LocalStorage final : public net::ILocalStorage {
|
||||
|
||||
std::vector<NT_Topic> GetTopics(std::string_view prefix, unsigned int types);
|
||||
std::vector<NT_Topic> GetTopics(std::string_view prefix,
|
||||
wpi::span<const std::string_view> types);
|
||||
std::span<const std::string_view> types);
|
||||
|
||||
std::vector<TopicInfo> GetTopicInfo(std::string_view prefix,
|
||||
unsigned int types);
|
||||
std::vector<TopicInfo> GetTopicInfo(std::string_view prefix,
|
||||
wpi::span<const std::string_view> types);
|
||||
std::span<const std::string_view> 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<const PubSubOption> options);
|
||||
std::span<const PubSubOption> options);
|
||||
|
||||
void Unsubscribe(NT_Subscriber sub);
|
||||
|
||||
NT_MultiSubscriber SubscribeMultiple(
|
||||
wpi::span<const std::string_view> prefixes,
|
||||
wpi::span<const PubSubOption> options);
|
||||
std::span<const std::string_view> prefixes,
|
||||
std::span<const PubSubOption> 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<const PubSubOption> options);
|
||||
std::span<const PubSubOption> options);
|
||||
|
||||
void Unpublish(NT_Handle pubentry);
|
||||
|
||||
NT_Entry GetEntry(NT_Topic topic, NT_Type type, std::string_view typeStr,
|
||||
wpi::span<const PubSubOption> options);
|
||||
std::span<const PubSubOption> 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<const uint8_t> defaultValue);
|
||||
std::span<const uint8_t> defaultValue);
|
||||
TimestampedBooleanArray GetAtomicBooleanArray(
|
||||
NT_Handle subentry, wpi::span<const int> defaultValue);
|
||||
NT_Handle subentry, std::span<const int> defaultValue);
|
||||
TimestampedIntegerArray GetAtomicIntegerArray(
|
||||
NT_Handle subentry, wpi::span<const int64_t> defaultValue);
|
||||
NT_Handle subentry, std::span<const int64_t> defaultValue);
|
||||
TimestampedFloatArray GetAtomicFloatArray(
|
||||
NT_Handle subentry, wpi::span<const float> defaultValue);
|
||||
NT_Handle subentry, std::span<const float> defaultValue);
|
||||
TimestampedDoubleArray GetAtomicDoubleArray(
|
||||
NT_Handle subentry, wpi::span<const double> defaultValue);
|
||||
NT_Handle subentry, std::span<const double> defaultValue);
|
||||
TimestampedStringArray GetAtomicStringArray(
|
||||
NT_Handle subentry, wpi::span<const std::string> defaultValue);
|
||||
NT_Handle subentry, std::span<const std::string> defaultValue);
|
||||
|
||||
TimestampedStringView GetAtomicString(NT_Handle subentry,
|
||||
wpi::SmallVectorImpl<char>& buf,
|
||||
std::string_view defaultValue);
|
||||
TimestampedRawView GetAtomicRaw(NT_Handle subentry,
|
||||
wpi::SmallVectorImpl<uint8_t>& buf,
|
||||
wpi::span<const uint8_t> defaultValue);
|
||||
std::span<const uint8_t> defaultValue);
|
||||
TimestampedBooleanArrayView GetAtomicBooleanArray(
|
||||
NT_Handle subentry, wpi::SmallVectorImpl<int>& buf,
|
||||
wpi::span<const int> defaultValue);
|
||||
std::span<const int> defaultValue);
|
||||
TimestampedIntegerArrayView GetAtomicIntegerArray(
|
||||
NT_Handle subentry, wpi::SmallVectorImpl<int64_t>& buf,
|
||||
wpi::span<const int64_t> defaultValue);
|
||||
std::span<const int64_t> defaultValue);
|
||||
TimestampedFloatArrayView GetAtomicFloatArray(
|
||||
NT_Handle subentry, wpi::SmallVectorImpl<float>& buf,
|
||||
wpi::span<const float> defaultValue);
|
||||
std::span<const float> defaultValue);
|
||||
TimestampedDoubleArrayView GetAtomicDoubleArray(
|
||||
NT_Handle subentry, wpi::SmallVectorImpl<double>& buf,
|
||||
wpi::span<const double> defaultValue);
|
||||
std::span<const double> defaultValue);
|
||||
|
||||
std::vector<Value> ReadQueueValue(NT_Handle subentry);
|
||||
|
||||
@@ -193,7 +193,7 @@ class LocalStorage final : public net::ILocalStorage {
|
||||
//
|
||||
|
||||
NT_TopicListener AddTopicListener(
|
||||
wpi::span<const std::string_view> prefixes, unsigned int mask,
|
||||
std::span<const std::string_view> prefixes, unsigned int mask,
|
||||
std::function<void(const TopicNotification&)> 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<const std::string_view> prefixes,
|
||||
NT_TopicListenerPoller poller, std::span<const std::string_view> prefixes,
|
||||
unsigned int mask);
|
||||
NT_TopicListener AddPolledTopicListener(NT_TopicListenerPoller poller,
|
||||
NT_Handle handle, unsigned int mask);
|
||||
|
||||
@@ -48,7 +48,7 @@ class NCImpl {
|
||||
virtual ~NCImpl() = default;
|
||||
|
||||
// user-facing functions
|
||||
void SetServers(wpi::span<const std::pair<std::string, unsigned int>> servers,
|
||||
void SetServers(std::span<const std::pair<std::string, unsigned int>> 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<const std::pair<std::string, unsigned int>> servers,
|
||||
std::span<const std::pair<std::string, unsigned int>> servers,
|
||||
unsigned int defaultPort) {
|
||||
std::vector<std::pair<std::string, unsigned int>> 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<const uint8_t> data, bool) {
|
||||
ws.binary.connect([this](std::span<const uint8_t> data, bool) {
|
||||
m_clientImpl->ProcessIncomingBinary(data);
|
||||
});
|
||||
}
|
||||
@@ -463,7 +463,7 @@ NetworkClient::~NetworkClient() {
|
||||
}
|
||||
|
||||
void NetworkClient::SetServers(
|
||||
wpi::span<const std::pair<std::string, unsigned int>> servers) {
|
||||
std::span<const std::pair<std::string, unsigned int>> servers) {
|
||||
m_impl->SetServers(servers, NT_DEFAULT_PORT4);
|
||||
}
|
||||
|
||||
@@ -505,7 +505,7 @@ NetworkClient3::~NetworkClient3() {
|
||||
}
|
||||
|
||||
void NetworkClient3::SetServers(
|
||||
wpi::span<const std::pair<std::string, unsigned int>> servers) {
|
||||
std::span<const std::pair<std::string, unsigned int>> servers) {
|
||||
m_impl->SetServers(servers, NT_DEFAULT_PORT3);
|
||||
}
|
||||
|
||||
|
||||
@@ -5,6 +5,7 @@
|
||||
#pragma once
|
||||
|
||||
#include <memory>
|
||||
#include <span>
|
||||
#include <string>
|
||||
#include <string_view>
|
||||
#include <utility>
|
||||
@@ -31,7 +32,7 @@ class NetworkClient final : public INetworkClient {
|
||||
~NetworkClient() final;
|
||||
|
||||
void SetServers(
|
||||
wpi::span<const std::pair<std::string, unsigned int>> servers) final;
|
||||
std::span<const std::pair<std::string, unsigned int>> 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<const std::pair<std::string, unsigned int>> servers) final;
|
||||
std::span<const std::pair<std::string, unsigned int>> servers) final;
|
||||
|
||||
void StartDSClient(unsigned int port) final;
|
||||
void StopDSClient() final;
|
||||
|
||||
@@ -7,6 +7,7 @@
|
||||
#include <stdint.h>
|
||||
|
||||
#include <atomic>
|
||||
#include <span>
|
||||
#include <system_error>
|
||||
#include <vector>
|
||||
|
||||
@@ -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<const uint8_t> data, bool) {
|
||||
m_websocket->binary.connect([this](std::span<const uint8_t> 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};
|
||||
|
||||
@@ -8,7 +8,7 @@
|
||||
|
||||
using namespace nt;
|
||||
|
||||
nt::PubSubOptions::PubSubOptions(wpi::span<const PubSubOption> options) {
|
||||
nt::PubSubOptions::PubSubOptions(std::span<const PubSubOption> options) {
|
||||
for (auto&& option : options) {
|
||||
switch (option.type) {
|
||||
case NT_PUBSUB_PERIODIC:
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <wpi/span.h>
|
||||
#include <span>
|
||||
|
||||
#include "ntcore_cpp.h"
|
||||
|
||||
@@ -14,7 +14,7 @@ namespace nt {
|
||||
class PubSubOptions {
|
||||
public:
|
||||
PubSubOptions() = default;
|
||||
explicit PubSubOptions(wpi::span<const PubSubOption> options);
|
||||
explicit PubSubOptions(std::span<const PubSubOption> options);
|
||||
|
||||
double periodic = 0.1;
|
||||
size_t pollStorageSize = 1;
|
||||
|
||||
@@ -5,6 +5,7 @@
|
||||
#include <stdint.h>
|
||||
|
||||
#include <cstring>
|
||||
#include <span>
|
||||
|
||||
#include <wpi/MemAlloc.h>
|
||||
#include <wpi/timestamp.h>
|
||||
@@ -17,7 +18,7 @@ using namespace nt;
|
||||
|
||||
namespace {
|
||||
struct StringArrayStorage {
|
||||
explicit StringArrayStorage(wpi::span<const std::string> value)
|
||||
explicit StringArrayStorage(std::span<const std::string> 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<const bool> value, int64_t time) {
|
||||
Value Value::MakeBooleanArray(std::span<const bool> value, int64_t time) {
|
||||
Value val{NT_BOOLEAN_ARRAY, time, private_init{}};
|
||||
auto data = std::make_shared<std::vector<int>>(value.begin(), value.end());
|
||||
// data->reserve(value.size());
|
||||
@@ -79,7 +80,7 @@ Value Value::MakeBooleanArray(wpi::span<const bool> value, int64_t time) {
|
||||
return val;
|
||||
}
|
||||
|
||||
Value Value::MakeBooleanArray(wpi::span<const int> value, int64_t time) {
|
||||
Value Value::MakeBooleanArray(std::span<const int> value, int64_t time) {
|
||||
Value val{NT_BOOLEAN_ARRAY, time, private_init{}};
|
||||
auto data = std::make_shared<std::vector<int>>(value.begin(), value.end());
|
||||
val.m_val.data.arr_boolean.arr = data->data();
|
||||
@@ -88,7 +89,7 @@ Value Value::MakeBooleanArray(wpi::span<const int> value, int64_t time) {
|
||||
return val;
|
||||
}
|
||||
|
||||
Value Value::MakeIntegerArray(wpi::span<const int64_t> value, int64_t time) {
|
||||
Value Value::MakeIntegerArray(std::span<const int64_t> value, int64_t time) {
|
||||
Value val{NT_INTEGER_ARRAY, time, private_init{}};
|
||||
auto data =
|
||||
std::make_shared<std::vector<int64_t>>(value.begin(), value.end());
|
||||
@@ -98,7 +99,7 @@ Value Value::MakeIntegerArray(wpi::span<const int64_t> value, int64_t time) {
|
||||
return val;
|
||||
}
|
||||
|
||||
Value Value::MakeFloatArray(wpi::span<const float> value, int64_t time) {
|
||||
Value Value::MakeFloatArray(std::span<const float> value, int64_t time) {
|
||||
Value val{NT_FLOAT_ARRAY, time, private_init{}};
|
||||
auto data = std::make_shared<std::vector<float>>(value.begin(), value.end());
|
||||
val.m_val.data.arr_float.arr = data->data();
|
||||
@@ -107,7 +108,7 @@ Value Value::MakeFloatArray(wpi::span<const float> value, int64_t time) {
|
||||
return val;
|
||||
}
|
||||
|
||||
Value Value::MakeDoubleArray(wpi::span<const double> value, int64_t time) {
|
||||
Value Value::MakeDoubleArray(std::span<const double> value, int64_t time) {
|
||||
Value val{NT_DOUBLE_ARRAY, time, private_init{}};
|
||||
auto data = std::make_shared<std::vector<double>>(value.begin(), value.end());
|
||||
val.m_val.data.arr_double.arr = data->data();
|
||||
@@ -116,7 +117,7 @@ Value Value::MakeDoubleArray(wpi::span<const double> value, int64_t time) {
|
||||
return val;
|
||||
}
|
||||
|
||||
Value Value::MakeStringArray(wpi::span<const std::string> value, int64_t time) {
|
||||
Value Value::MakeStringArray(std::span<const std::string> value, int64_t time) {
|
||||
Value val{NT_STRING_ARRAY, time, private_init{}};
|
||||
auto data = std::make_shared<StringArrayStorage>(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<std::string> v;
|
||||
|
||||
@@ -120,7 +120,7 @@ JNIEXPORT void JNICALL JNI_OnUnload(JavaVM* vm, void* reserved) {
|
||||
// Conversions from Java objects to C++
|
||||
//
|
||||
|
||||
static wpi::span<const nt::PubSubOption> FromJavaPubSubOptions(
|
||||
static std::span<const nt::PubSubOption> FromJavaPubSubOptions(
|
||||
JNIEnv* env, jintArray optionTypes, jdoubleArray optionValues,
|
||||
wpi::SmallVectorImpl<nt::PubSubOption>& arr) {
|
||||
JIntArrayRef types{env, optionTypes};
|
||||
@@ -281,7 +281,7 @@ static jobject MakeJObject(JNIEnv* env, jobject inst,
|
||||
static_cast<jint>(notification.flags));
|
||||
}
|
||||
|
||||
static jobjectArray MakeJObject(JNIEnv* env, wpi::span<const nt::Value> arr) {
|
||||
static jobjectArray MakeJObject(JNIEnv* env, std::span<const nt::Value> arr) {
|
||||
jobjectArray jarr = env->NewObjectArray(arr.size(), valueCls, nullptr);
|
||||
if (!jarr) {
|
||||
return nullptr;
|
||||
@@ -295,7 +295,7 @@ static jobjectArray MakeJObject(JNIEnv* env, wpi::span<const nt::Value> arr) {
|
||||
|
||||
static jobjectArray MakeJObject(
|
||||
JNIEnv* env, jobject inst,
|
||||
wpi::span<const nt::ConnectionNotification> arr) {
|
||||
std::span<const nt::ConnectionNotification> 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<const nt::LogMessage> arr) {
|
||||
std::span<const nt::LogMessage> 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<const nt::TopicNotification> arr) {
|
||||
std::span<const nt::TopicNotification> 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<const nt::ValueNotification> arr) {
|
||||
std::span<const nt::ValueNotification> arr) {
|
||||
jobjectArray jarr =
|
||||
env->NewObjectArray(arr.size(), valueNotificationCls, nullptr);
|
||||
if (!jarr) {
|
||||
|
||||
@@ -52,9 +52,9 @@ class CImpl : public ServerMessageHandler {
|
||||
CImpl(uint64_t curTimeMs, int inst, WireConnection& wire, wpi::Logger& logger,
|
||||
std::function<void(uint32_t repeatMs)> setPeriodic);
|
||||
|
||||
void ProcessIncomingBinary(wpi::span<const uint8_t> data);
|
||||
void ProcessIncomingBinary(std::span<const uint8_t> data);
|
||||
void HandleLocal(std::vector<ClientMessage>&& msgs);
|
||||
void SendOutgoing(wpi::span<const ClientMessage> msgs);
|
||||
void SendOutgoing(std::span<const ClientMessage> 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<const uint8_t> data) {
|
||||
void CImpl::ProcessIncomingBinary(std::span<const uint8_t> 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<const uint8_t> data) {
|
||||
void ClientImpl::ProcessIncomingBinary(std::span<const uint8_t> 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<const std::string> prefixes,
|
||||
std::span<const std::string> prefixes,
|
||||
const PubSubOptions& options) {
|
||||
WPI_DEBUG4(m_client.m_impl->m_logger, "StartupSubscribe({})", subHandle);
|
||||
WireEncodeSubscribe(m_textWriter.Add(), Handle{subHandle}.GetIndex(),
|
||||
|
||||
@@ -8,12 +8,11 @@
|
||||
|
||||
#include <functional>
|
||||
#include <memory>
|
||||
#include <span>
|
||||
#include <string>
|
||||
#include <string_view>
|
||||
#include <vector>
|
||||
|
||||
#include <wpi/span.h>
|
||||
|
||||
#include "NetworkInterface.h"
|
||||
#include "WireConnection.h"
|
||||
|
||||
@@ -42,7 +41,7 @@ class ClientImpl {
|
||||
~ClientImpl();
|
||||
|
||||
void ProcessIncomingText(std::string_view data);
|
||||
void ProcessIncomingBinary(wpi::span<const uint8_t> data);
|
||||
void ProcessIncomingBinary(std::span<const uint8_t> data);
|
||||
void HandleLocal(std::vector<ClientMessage>&& 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<const std::string> prefixes,
|
||||
void Subscribe(NT_Subscriber subHandle, std::span<const std::string> prefixes,
|
||||
const PubSubOptions& options) final;
|
||||
void SetValue(NT_Publisher pubHandle, const Value& value) final;
|
||||
|
||||
|
||||
@@ -4,11 +4,10 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <span>
|
||||
#include <string>
|
||||
#include <string_view>
|
||||
|
||||
#include <wpi/span.h>
|
||||
|
||||
#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<const std::string> topicNames,
|
||||
std::span<const std::string> topicNames,
|
||||
const PubSubOptions& options) = 0;
|
||||
virtual void SetValue(NT_Publisher pubHandle, const Value& value) = 0;
|
||||
};
|
||||
|
||||
@@ -4,6 +4,7 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <span>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
@@ -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<const std::string> topicNames,
|
||||
std::span<const std::string> topicNames,
|
||||
const PubSubOptions& options) final;
|
||||
void Unsubscribe(NT_Subscriber subHandle) final;
|
||||
void SetValue(NT_Publisher pubHandle, const Value& value) final;
|
||||
|
||||
@@ -4,6 +4,7 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <span>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
@@ -55,7 +56,7 @@ inline void NetworkLoopQueue::SetProperties(NT_Topic topicHandle,
|
||||
}
|
||||
|
||||
inline void NetworkLoopQueue::Subscribe(NT_Subscriber subHandle,
|
||||
wpi::span<const std::string> topicNames,
|
||||
std::span<const std::string> topicNames,
|
||||
const PubSubOptions& options) {
|
||||
std::scoped_lock lock{m_mutex};
|
||||
m_queue.emplace_back(ClientMessage{SubscribeMsg{
|
||||
|
||||
@@ -91,7 +91,7 @@ class ClientData {
|
||||
virtual ~ClientData() = default;
|
||||
|
||||
virtual void ProcessIncomingText(std::string_view data) = 0;
|
||||
virtual void ProcessIncomingBinary(wpi::span<const uint8_t> data) = 0;
|
||||
virtual void ProcessIncomingBinary(std::span<const uint8_t> 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<const std::string> topicNames,
|
||||
void ClientSubscribe(int64_t subuid, std::span<const std::string> 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<const uint8_t> data) final {}
|
||||
void ProcessIncomingBinary(std::span<const uint8_t> data) final {}
|
||||
|
||||
void SendValue(TopicData* topic, const Value& value, SendMode mode) final;
|
||||
void SendAnnounce(TopicData* topic, std::optional<int64_t> pubuid) final;
|
||||
@@ -178,7 +178,7 @@ class ClientDataLocal final : public ClientData4Base {
|
||||
void SendOutgoing(uint64_t curTimeMs) final {}
|
||||
void Flush() final {}
|
||||
|
||||
void HandleLocal(wpi::span<const ClientMessage> msgs);
|
||||
void HandleLocal(std::span<const ClientMessage> 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<const uint8_t> data) final;
|
||||
void ProcessIncomingBinary(std::span<const uint8_t> data) final;
|
||||
|
||||
void SendValue(TopicData* topic, const Value& value, SendMode mode) final;
|
||||
void SendAnnounce(TopicData* topic, std::optional<int64_t> 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<const uint8_t> data) final;
|
||||
void ProcessIncomingBinary(std::span<const uint8_t> data) final;
|
||||
|
||||
void SendValue(TopicData* topic, const Value& value, SendMode mode) final;
|
||||
void SendAnnounce(TopicData* topic, std::optional<int64_t> 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<const uint8_t> params) final {}
|
||||
std::span<const uint8_t> params) final {}
|
||||
void RpcResponse(unsigned int id, unsigned int uid,
|
||||
wpi::span<const uint8_t> result) final {}
|
||||
std::span<const uint8_t> result) final {}
|
||||
|
||||
ServerImpl::Connected3Func m_connected;
|
||||
net3::WireConnection3& m_wire;
|
||||
@@ -350,7 +350,7 @@ struct PublisherData {
|
||||
};
|
||||
|
||||
struct SubscriberData {
|
||||
SubscriberData(ClientData* client, wpi::span<const std::string> topicNames,
|
||||
SubscriberData(ClientData* client, std::span<const std::string> topicNames,
|
||||
int64_t subuid, const PubSubOptions& options)
|
||||
: client{client},
|
||||
topicNames{topicNames.begin(), topicNames.end()},
|
||||
@@ -362,7 +362,7 @@ struct SubscriberData {
|
||||
}
|
||||
}
|
||||
|
||||
void Update(wpi::span<const std::string> topicNames_,
|
||||
void Update(std::span<const std::string> 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<const std::string> topicNames,
|
||||
std::span<const std::string> 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<const ClientMessage> msgs) {
|
||||
void ClientDataLocal::HandleLocal(std::span<const ClientMessage> 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<const uint8_t> data) {
|
||||
void ClientData4::ProcessIncomingBinary(std::span<const uint8_t> data) {
|
||||
for (;;) {
|
||||
if (data.empty()) {
|
||||
break;
|
||||
@@ -947,7 +947,7 @@ bool ClientData3::TopicData3::UpdateFlags(TopicData* topic) {
|
||||
return updated;
|
||||
}
|
||||
|
||||
void ClientData3::ProcessIncomingBinary(wpi::span<const uint8_t> data) {
|
||||
void ClientData3::ProcessIncomingBinary(std::span<const uint8_t> 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<SubscriberData>(
|
||||
this, wpi::span<const std::string>{{prefix}}, 0, options);
|
||||
this, std::span<const std::string>{{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<const ClientMessage> msgs) {
|
||||
void ServerImpl::HandleLocal(std::span<const ClientMessage> 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<const uint8_t> data) {
|
||||
std::span<const uint8_t> 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<const std::string> topicNames,
|
||||
std::span<const std::string> topicNames,
|
||||
const PubSubOptions& options) {
|
||||
m_server.m_impl->m_localClient->ClientSubscribe(subHandle, topicNames,
|
||||
options);
|
||||
|
||||
@@ -8,12 +8,11 @@
|
||||
|
||||
#include <functional>
|
||||
#include <memory>
|
||||
#include <span>
|
||||
#include <string>
|
||||
#include <string_view>
|
||||
#include <vector>
|
||||
|
||||
#include <wpi/span.h>
|
||||
|
||||
#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<const ClientMessage> msgs);
|
||||
void HandleLocal(std::span<const ClientMessage> msgs);
|
||||
void SetLocal(LocalInterface* local);
|
||||
|
||||
void ProcessIncomingText(int clientId, std::string_view data);
|
||||
void ProcessIncomingBinary(int clientId, wpi::span<const uint8_t> data);
|
||||
void ProcessIncomingBinary(int clientId, std::span<const uint8_t> 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<const std::string> topicNames,
|
||||
std::span<const std::string> topicNames,
|
||||
const PubSubOptions& options) final;
|
||||
void SetValue(NT_Publisher pubHandle, const Value& value) final;
|
||||
|
||||
|
||||
@@ -4,6 +4,8 @@
|
||||
|
||||
#include "WebSocketConnection.h"
|
||||
|
||||
#include <span>
|
||||
|
||||
#include <wpi/SpanExtras.h>
|
||||
#include <wpinet/WebSocket.h>
|
||||
|
||||
@@ -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});
|
||||
}
|
||||
|
||||
|
||||
@@ -418,7 +418,7 @@ void nt::net::WireDecodeText(std::string_view in, ServerMessageHandler& out,
|
||||
::WireDecodeTextImpl(in, out, logger);
|
||||
}
|
||||
|
||||
bool nt::net::WireDecodeBinary(wpi::span<const uint8_t>* in, int64_t* outId,
|
||||
bool nt::net::WireDecodeBinary(std::span<const uint8_t>* in, int64_t* outId,
|
||||
Value* outValue, std::string* error,
|
||||
int64_t localTimeOffset) {
|
||||
mpack_reader_t reader;
|
||||
|
||||
@@ -7,11 +7,10 @@
|
||||
#include <stdint.h>
|
||||
|
||||
#include <optional>
|
||||
#include <span>
|
||||
#include <string>
|
||||
#include <string_view>
|
||||
|
||||
#include <wpi/span.h>
|
||||
|
||||
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<const std::string> topicNames,
|
||||
std::span<const std::string> 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<const uint8_t>* in, int64_t* outId,
|
||||
bool WireDecodeBinary(std::span<const uint8_t>* in, int64_t* outId,
|
||||
Value* outValue, std::string* error,
|
||||
int64_t localTimeOffset);
|
||||
|
||||
|
||||
@@ -56,7 +56,7 @@ void nt::net::WireEncodeSetProperties(wpi::raw_ostream& os,
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
static void EncodePrefixes(wpi::raw_ostream& os, wpi::span<const T> topicNames,
|
||||
static void EncodePrefixes(wpi::raw_ostream& os, std::span<const T> topicNames,
|
||||
wpi::json::serializer& s) {
|
||||
os << '[';
|
||||
bool first = true;
|
||||
@@ -75,7 +75,7 @@ static void EncodePrefixes(wpi::raw_ostream& os, wpi::span<const T> topicNames,
|
||||
|
||||
template <typename T>
|
||||
static void WireEncodeSubscribeImpl(wpi::raw_ostream& os, int64_t subuid,
|
||||
wpi::span<const T> topicNames,
|
||||
std::span<const T> 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<const std::string_view> topicNames,
|
||||
std::span<const std::string_view> topicNames,
|
||||
const PubSubOptions& options) {
|
||||
WireEncodeSubscribeImpl(os, subuid, topicNames, options);
|
||||
}
|
||||
|
||||
void nt::net::WireEncodeSubscribe(wpi::raw_ostream& os, int64_t subuid,
|
||||
wpi::span<const std::string> topicNames,
|
||||
std::span<const std::string> topicNames,
|
||||
const PubSubOptions& options) {
|
||||
WireEncodeSubscribeImpl(os, subuid, topicNames, options);
|
||||
}
|
||||
|
||||
@@ -5,11 +5,10 @@
|
||||
#pragma once
|
||||
|
||||
#include <optional>
|
||||
#include <span>
|
||||
#include <string>
|
||||
#include <string_view>
|
||||
|
||||
#include <wpi/span.h>
|
||||
|
||||
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<const std::string_view> topicNames,
|
||||
std::span<const std::string_view> topicNames,
|
||||
const PubSubOptions& options);
|
||||
void WireEncodeSubscribe(wpi::raw_ostream& os, int64_t subuid,
|
||||
wpi::span<const std::string> topicNames,
|
||||
std::span<const std::string> topicNames,
|
||||
const PubSubOptions& options);
|
||||
void WireEncodeUnsubscribe(wpi::raw_ostream& os, int64_t subuid);
|
||||
|
||||
|
||||
@@ -89,8 +89,8 @@ class CImpl : public MessageHandler3 {
|
||||
wpi::Logger& logger,
|
||||
std::function<void(uint32_t repeatMs)> setPeriodic);
|
||||
|
||||
void ProcessIncoming(wpi::span<const uint8_t> data);
|
||||
void HandleLocal(wpi::span<const net::ClientMessage> msgs);
|
||||
void ProcessIncoming(std::span<const uint8_t> data);
|
||||
void HandleLocal(std::span<const net::ClientMessage> 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<const uint8_t> params) final {}
|
||||
std::span<const uint8_t> params) final {}
|
||||
void RpcResponse(unsigned int id, unsigned int uid,
|
||||
wpi::span<const uint8_t> result) final {}
|
||||
std::span<const uint8_t> 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<const uint8_t> data) {
|
||||
void CImpl::ProcessIncoming(std::span<const uint8_t> data) {
|
||||
DEBUG4("received {} bytes", data.size());
|
||||
if (!m_decoder.Execute(&data)) {
|
||||
m_wire.Disconnect(m_decoder.GetError());
|
||||
}
|
||||
}
|
||||
|
||||
void CImpl::HandleLocal(wpi::span<const net::ClientMessage> msgs) {
|
||||
void CImpl::HandleLocal(std::span<const net::ClientMessage> msgs) {
|
||||
for (const auto& elem : msgs) { // NOLINT
|
||||
// common case is value
|
||||
if (auto msg = std::get_if<net::ClientValueMsg>(&elem.contents)) {
|
||||
@@ -624,11 +624,11 @@ void ClientImpl3::Start(std::string_view selfId,
|
||||
m_impl->m_state = CImpl::kStateHelloSent;
|
||||
}
|
||||
|
||||
void ClientImpl3::ProcessIncoming(wpi::span<const uint8_t> data) {
|
||||
void ClientImpl3::ProcessIncoming(std::span<const uint8_t> data) {
|
||||
m_impl->ProcessIncoming(data);
|
||||
}
|
||||
|
||||
void ClientImpl3::HandleLocal(wpi::span<const net::ClientMessage> msgs) {
|
||||
void ClientImpl3::HandleLocal(std::span<const net::ClientMessage> 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<const std::string> prefixes,
|
||||
std::span<const std::string> prefixes,
|
||||
const PubSubOptions& options) {
|
||||
// NT3 ignores subscribes, so no action required
|
||||
}
|
||||
|
||||
@@ -8,11 +8,10 @@
|
||||
|
||||
#include <functional>
|
||||
#include <memory>
|
||||
#include <span>
|
||||
#include <string>
|
||||
#include <string_view>
|
||||
|
||||
#include <wpi/span.h>
|
||||
|
||||
#include "net/NetworkInterface.h"
|
||||
|
||||
namespace wpi {
|
||||
@@ -39,8 +38,8 @@ class ClientImpl3 {
|
||||
~ClientImpl3();
|
||||
|
||||
void Start(std::string_view selfId, std::function<void()> succeeded);
|
||||
void ProcessIncoming(wpi::span<const uint8_t> data);
|
||||
void HandleLocal(wpi::span<const net::ClientMessage> msgs);
|
||||
void ProcessIncoming(std::span<const uint8_t> data);
|
||||
void HandleLocal(std::span<const net::ClientMessage> 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<const std::string> prefixes,
|
||||
void Subscribe(NT_Subscriber subHandle, std::span<const std::string> prefixes,
|
||||
const PubSubOptions& options) final;
|
||||
void SetValue(NT_Publisher pubHandle, const Value& value) final;
|
||||
|
||||
|
||||
@@ -6,6 +6,7 @@
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <span>
|
||||
#include <string>
|
||||
|
||||
#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<const uint8_t> bytes() const {
|
||||
std::span<const uint8_t> bytes() const {
|
||||
return {reinterpret_cast<const uint8_t*>(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<const uint8_t> params) {
|
||||
std::span<const uint8_t> params) {
|
||||
Message3 msg{kExecuteRpc, {}};
|
||||
msg.m_str.assign(reinterpret_cast<const char*>(params.data()),
|
||||
params.size());
|
||||
@@ -132,7 +133,7 @@ class Message3 {
|
||||
return msg;
|
||||
}
|
||||
static Message3 RpcResponse(unsigned int id, unsigned int uid,
|
||||
wpi::span<const uint8_t> result) {
|
||||
std::span<const uint8_t> result) {
|
||||
Message3 msg{kRpcResponse, {}};
|
||||
msg.m_str.assign(reinterpret_cast<const char*>(result.data()),
|
||||
result.size());
|
||||
|
||||
@@ -23,10 +23,10 @@ namespace {
|
||||
|
||||
class SimpleValueReader {
|
||||
public:
|
||||
std::optional<uint16_t> Read16(wpi::span<const uint8_t>* in);
|
||||
std::optional<uint32_t> Read32(wpi::span<const uint8_t>* in);
|
||||
std::optional<uint64_t> Read64(wpi::span<const uint8_t>* in);
|
||||
std::optional<double> ReadDouble(wpi::span<const uint8_t>* in);
|
||||
std::optional<uint16_t> Read16(std::span<const uint8_t>* in);
|
||||
std::optional<uint32_t> Read32(std::span<const uint8_t>* in);
|
||||
std::optional<uint64_t> Read64(std::span<const uint8_t>* in);
|
||||
std::optional<double> ReadDouble(std::span<const uint8_t>* 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<const uint8_t>* in);
|
||||
void Execute(std::span<const uint8_t>* in);
|
||||
|
||||
std::nullopt_t EmitError(std::string_view msg) {
|
||||
m_state = kError;
|
||||
@@ -131,22 +131,22 @@ struct WDImpl {
|
||||
return std::nullopt;
|
||||
}
|
||||
|
||||
std::optional<std::string> ReadString(wpi::span<const uint8_t>* in);
|
||||
std::optional<std::vector<uint8_t>> ReadRaw(wpi::span<const uint8_t>* in);
|
||||
std::optional<NT_Type> ReadType(wpi::span<const uint8_t>* in);
|
||||
std::optional<Value> ReadValue(wpi::span<const uint8_t>* in);
|
||||
std::optional<std::string> ReadString(std::span<const uint8_t>* in);
|
||||
std::optional<std::vector<uint8_t>> ReadRaw(std::span<const uint8_t>* in);
|
||||
std::optional<NT_Type> ReadType(std::span<const uint8_t>* in);
|
||||
std::optional<Value> ReadValue(std::span<const uint8_t>* in);
|
||||
};
|
||||
|
||||
} // namespace
|
||||
|
||||
static uint8_t Read8(wpi::span<const uint8_t>* in) {
|
||||
static uint8_t Read8(std::span<const uint8_t>* in) {
|
||||
uint8_t val = in->front();
|
||||
*in = wpi::drop_front(*in);
|
||||
return val;
|
||||
}
|
||||
|
||||
std::optional<uint16_t> SimpleValueReader::Read16(
|
||||
wpi::span<const uint8_t>* in) {
|
||||
std::span<const uint8_t>* in) {
|
||||
while (!in->empty()) {
|
||||
m_value <<= 8;
|
||||
m_value |= in->front() & 0xff;
|
||||
@@ -162,7 +162,7 @@ std::optional<uint16_t> SimpleValueReader::Read16(
|
||||
}
|
||||
|
||||
std::optional<uint32_t> SimpleValueReader::Read32(
|
||||
wpi::span<const uint8_t>* in) {
|
||||
std::span<const uint8_t>* in) {
|
||||
while (!in->empty()) {
|
||||
m_value <<= 8;
|
||||
m_value |= in->front() & 0xff;
|
||||
@@ -178,7 +178,7 @@ std::optional<uint32_t> SimpleValueReader::Read32(
|
||||
}
|
||||
|
||||
std::optional<uint64_t> SimpleValueReader::Read64(
|
||||
wpi::span<const uint8_t>* in) {
|
||||
std::span<const uint8_t>* in) {
|
||||
while (!in->empty()) {
|
||||
m_value <<= 8;
|
||||
m_value |= in->front() & 0xff;
|
||||
@@ -194,7 +194,7 @@ std::optional<uint64_t> SimpleValueReader::Read64(
|
||||
}
|
||||
|
||||
std::optional<double> SimpleValueReader::ReadDouble(
|
||||
wpi::span<const uint8_t>* in) {
|
||||
std::span<const uint8_t>* in) {
|
||||
if (auto val = Read64(in)) {
|
||||
return wpi::BitsToDouble(val.value());
|
||||
} else {
|
||||
@@ -202,7 +202,7 @@ std::optional<double> SimpleValueReader::ReadDouble(
|
||||
}
|
||||
}
|
||||
|
||||
void WDImpl::Execute(wpi::span<const uint8_t>* in) {
|
||||
void WDImpl::Execute(std::span<const uint8_t>* in) {
|
||||
while (!in->empty()) {
|
||||
switch (m_state) {
|
||||
case kStart: {
|
||||
@@ -417,7 +417,7 @@ void WDImpl::Execute(wpi::span<const uint8_t>* in) {
|
||||
}
|
||||
}
|
||||
|
||||
std::optional<std::string> WDImpl::ReadString(wpi::span<const uint8_t>* in) {
|
||||
std::optional<std::string> WDImpl::ReadString(std::span<const uint8_t>* in) {
|
||||
// string length
|
||||
if (!m_stringReader.len) {
|
||||
if (auto val = m_ulebReader.ReadOne(in)) {
|
||||
@@ -443,7 +443,7 @@ std::optional<std::string> WDImpl::ReadString(wpi::span<const uint8_t>* in) {
|
||||
}
|
||||
|
||||
std::optional<std::vector<uint8_t>> WDImpl::ReadRaw(
|
||||
wpi::span<const uint8_t>* in) {
|
||||
std::span<const uint8_t>* in) {
|
||||
// string length
|
||||
if (!m_rawReader.len) {
|
||||
if (auto val = m_ulebReader.ReadOne(in)) {
|
||||
@@ -468,7 +468,7 @@ std::optional<std::vector<uint8_t>> WDImpl::ReadRaw(
|
||||
return std::nullopt;
|
||||
}
|
||||
|
||||
std::optional<NT_Type> WDImpl::ReadType(wpi::span<const uint8_t>* in) {
|
||||
std::optional<NT_Type> WDImpl::ReadType(std::span<const uint8_t>* in) {
|
||||
// Convert from byte value to enum
|
||||
switch (Read8(in)) {
|
||||
case Message3::kBoolean:
|
||||
@@ -492,7 +492,7 @@ std::optional<NT_Type> WDImpl::ReadType(wpi::span<const uint8_t>* in) {
|
||||
}
|
||||
}
|
||||
|
||||
std::optional<Value> WDImpl::ReadValue(wpi::span<const uint8_t>* in) {
|
||||
std::optional<Value> WDImpl::ReadValue(std::span<const uint8_t>* 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<const uint8_t>* in) {
|
||||
bool WireDecoder3::Execute(std::span<const uint8_t>* in) {
|
||||
m_impl->Execute(in);
|
||||
return m_impl->m_state != Impl::kError;
|
||||
}
|
||||
|
||||
@@ -7,10 +7,9 @@
|
||||
#include <stdint.h>
|
||||
|
||||
#include <memory>
|
||||
#include <span>
|
||||
#include <string>
|
||||
|
||||
#include <wpi/span.h>
|
||||
|
||||
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<const uint8_t> params) = 0;
|
||||
std::span<const uint8_t> params) = 0;
|
||||
virtual void RpcResponse(unsigned int id, unsigned int uid,
|
||||
wpi::span<const uint8_t> result) = 0;
|
||||
std::span<const uint8_t> 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<const uint8_t>* in);
|
||||
bool Execute(std::span<const uint8_t>* in);
|
||||
|
||||
void SetError(std::string_view message);
|
||||
std::string GetError() const;
|
||||
|
||||
@@ -8,7 +8,6 @@
|
||||
#include <wpi/SmallVector.h>
|
||||
#include <wpi/leb128.h>
|
||||
#include <wpi/raw_ostream.h>
|
||||
#include <wpi/span.h>
|
||||
|
||||
#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<const uint8_t>{{static_cast<uint8_t>((val >> 8) & 0xff),
|
||||
os << std::span<const uint8_t>{{static_cast<uint8_t>((val >> 8) & 0xff),
|
||||
static_cast<uint8_t>(val & 0xff)}};
|
||||
}
|
||||
|
||||
static void Write32(wpi::raw_ostream& os, uint32_t val) {
|
||||
os << wpi::span<const uint8_t>{{static_cast<uint8_t>((val >> 24) & 0xff),
|
||||
os << std::span<const uint8_t>{{static_cast<uint8_t>((val >> 24) & 0xff),
|
||||
static_cast<uint8_t>((val >> 16) & 0xff),
|
||||
static_cast<uint8_t>((val >> 8) & 0xff),
|
||||
static_cast<uint8_t>(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<const uint8_t>{{static_cast<uint8_t>((v >> 56) & 0xff),
|
||||
os << std::span<const uint8_t>{{static_cast<uint8_t>((v >> 56) & 0xff),
|
||||
static_cast<uint8_t>((v >> 48) & 0xff),
|
||||
static_cast<uint8_t>((v >> 40) & 0xff),
|
||||
static_cast<uint8_t>((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<const uint8_t> str) {
|
||||
static void WriteRaw(wpi::raw_ostream& os, std::span<const uint8_t> 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<const uint8_t> params) {
|
||||
std::span<const uint8_t> 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<const uint8_t> result) {
|
||||
std::span<const uint8_t> result) {
|
||||
Write8(os, Message3::kRpcResponse);
|
||||
Write16(os, id);
|
||||
Write16(os, uid);
|
||||
|
||||
@@ -6,10 +6,9 @@
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <span>
|
||||
#include <string_view>
|
||||
|
||||
#include <wpi/span.h>
|
||||
|
||||
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<const uint8_t> params);
|
||||
unsigned int uid, std::span<const uint8_t> params);
|
||||
void WireEncodeRpcResponse(wpi::raw_ostream& os, unsigned int id,
|
||||
unsigned int uid, wpi::span<const uint8_t> result);
|
||||
unsigned int uid, std::span<const uint8_t> result);
|
||||
|
||||
bool WireEncode(wpi::raw_ostream& os, const Message3& msg);
|
||||
|
||||
|
||||
@@ -287,62 +287,62 @@ bool NetworkTable::GetBoolean(std::string_view key, bool defaultValue) const {
|
||||
}
|
||||
|
||||
bool NetworkTable::PutBooleanArray(std::string_view key,
|
||||
wpi::span<const int> value) {
|
||||
std::span<const int> value) {
|
||||
return GetEntry(key).SetBooleanArray(value);
|
||||
}
|
||||
|
||||
bool NetworkTable::SetDefaultBooleanArray(std::string_view key,
|
||||
wpi::span<const int> defaultValue) {
|
||||
std::span<const int> defaultValue) {
|
||||
return GetEntry(key).SetDefaultBooleanArray(defaultValue);
|
||||
}
|
||||
|
||||
std::vector<int> NetworkTable::GetBooleanArray(
|
||||
std::string_view key, wpi::span<const int> defaultValue) const {
|
||||
std::string_view key, std::span<const int> defaultValue) const {
|
||||
return GetEntry(key).GetBooleanArray(defaultValue);
|
||||
}
|
||||
|
||||
bool NetworkTable::PutNumberArray(std::string_view key,
|
||||
wpi::span<const double> value) {
|
||||
std::span<const double> value) {
|
||||
return GetEntry(key).SetDoubleArray(value);
|
||||
}
|
||||
|
||||
bool NetworkTable::SetDefaultNumberArray(std::string_view key,
|
||||
wpi::span<const double> defaultValue) {
|
||||
std::span<const double> defaultValue) {
|
||||
return GetEntry(key).SetDefaultDoubleArray(defaultValue);
|
||||
}
|
||||
|
||||
std::vector<double> NetworkTable::GetNumberArray(
|
||||
std::string_view key, wpi::span<const double> defaultValue) const {
|
||||
std::string_view key, std::span<const double> defaultValue) const {
|
||||
return GetEntry(key).GetDoubleArray(defaultValue);
|
||||
}
|
||||
|
||||
bool NetworkTable::PutStringArray(std::string_view key,
|
||||
wpi::span<const std::string> value) {
|
||||
std::span<const std::string> value) {
|
||||
return GetEntry(key).SetStringArray(value);
|
||||
}
|
||||
|
||||
bool NetworkTable::SetDefaultStringArray(
|
||||
std::string_view key, wpi::span<const std::string> defaultValue) {
|
||||
std::string_view key, std::span<const std::string> defaultValue) {
|
||||
return GetEntry(key).SetDefaultStringArray(defaultValue);
|
||||
}
|
||||
|
||||
std::vector<std::string> NetworkTable::GetStringArray(
|
||||
std::string_view key, wpi::span<const std::string> defaultValue) const {
|
||||
std::string_view key, std::span<const std::string> defaultValue) const {
|
||||
return GetEntry(key).GetStringArray(defaultValue);
|
||||
}
|
||||
|
||||
bool NetworkTable::PutRaw(std::string_view key,
|
||||
wpi::span<const uint8_t> value) {
|
||||
std::span<const uint8_t> value) {
|
||||
return GetEntry(key).SetRaw(value);
|
||||
}
|
||||
|
||||
bool NetworkTable::SetDefaultRaw(std::string_view key,
|
||||
wpi::span<const uint8_t> defaultValue) {
|
||||
std::span<const uint8_t> defaultValue) {
|
||||
return GetEntry(key).SetDefaultRaw(defaultValue);
|
||||
}
|
||||
|
||||
std::vector<uint8_t> NetworkTable::GetRaw(
|
||||
std::string_view key, wpi::span<const uint8_t> defaultValue) const {
|
||||
std::string_view key, std::span<const uint8_t> defaultValue) const {
|
||||
return GetEntry(key).GetRaw(defaultValue);
|
||||
}
|
||||
|
||||
|
||||
@@ -90,7 +90,7 @@ std::shared_ptr<NetworkTable> NetworkTableInstance::GetTable(
|
||||
}
|
||||
}
|
||||
|
||||
void NetworkTableInstance::SetServer(wpi::span<const std::string_view> servers,
|
||||
void NetworkTableInstance::SetServer(std::span<const std::string_view> servers,
|
||||
unsigned int port) {
|
||||
std::vector<std::pair<std::string_view, unsigned int>> serversArr;
|
||||
serversArr.reserve(servers.size());
|
||||
|
||||
@@ -23,36 +23,36 @@ wpi::json Topic::GetProperties() const {
|
||||
}
|
||||
|
||||
GenericSubscriber Topic::GenericSubscribe(
|
||||
wpi::span<const PubSubOption> options) {
|
||||
std::span<const PubSubOption> options) {
|
||||
return GenericSubscribe("", options);
|
||||
}
|
||||
|
||||
GenericSubscriber Topic::GenericSubscribe(
|
||||
std::string_view typeString, wpi::span<const PubSubOption> options) {
|
||||
std::string_view typeString, std::span<const PubSubOption> options) {
|
||||
return GenericSubscriber{::nt::Subscribe(
|
||||
m_handle, ::nt::GetTypeFromString(typeString), typeString, options)};
|
||||
}
|
||||
|
||||
GenericPublisher Topic::GenericPublish(std::string_view typeString,
|
||||
wpi::span<const PubSubOption> options) {
|
||||
std::span<const PubSubOption> 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<const PubSubOption> options) {
|
||||
std::span<const PubSubOption> options) {
|
||||
return GenericPublisher{::nt::PublishEx(m_handle,
|
||||
::nt::GetTypeFromString(typeString),
|
||||
typeString, properties, options)};
|
||||
}
|
||||
|
||||
GenericEntry Topic::GetGenericEntry(wpi::span<const PubSubOption> options) {
|
||||
GenericEntry Topic::GetGenericEntry(std::span<const PubSubOption> options) {
|
||||
return GetGenericEntry("", options);
|
||||
}
|
||||
|
||||
GenericEntry Topic::GetGenericEntry(std::string_view typeString,
|
||||
wpi::span<const PubSubOption> options) {
|
||||
std::span<const PubSubOption> options) {
|
||||
return GenericEntry{::nt::GetEntry(
|
||||
m_handle, ::nt::GetTypeFromString(typeString), typeString, options)};
|
||||
}
|
||||
|
||||
@@ -157,7 +157,7 @@ std::vector<NT_Topic> GetTopics(NT_Inst inst, std::string_view prefix,
|
||||
}
|
||||
|
||||
std::vector<NT_Topic> GetTopics(NT_Inst inst, std::string_view prefix,
|
||||
wpi::span<const std::string_view> types) {
|
||||
std::span<const std::string_view> types) {
|
||||
if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
|
||||
return ii->localStorage.GetTopics(prefix, types);
|
||||
} else {
|
||||
@@ -175,7 +175,7 @@ std::vector<TopicInfo> GetTopicInfo(NT_Inst inst, std::string_view prefix,
|
||||
}
|
||||
|
||||
std::vector<TopicInfo> GetTopicInfo(NT_Inst inst, std::string_view prefix,
|
||||
wpi::span<const std::string_view> types) {
|
||||
std::span<const std::string_view> 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<const PubSubOption> options) {
|
||||
std::span<const PubSubOption> 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<const PubSubOption> options) {
|
||||
std::span<const PubSubOption> 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<const PubSubOption> options) {
|
||||
std::span<const PubSubOption> 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<const PubSubOption> options) {
|
||||
std::span<const PubSubOption> 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<const std::string_view> prefixes,
|
||||
wpi::span<const PubSubOption> options) {
|
||||
std::span<const std::string_view> prefixes,
|
||||
std::span<const PubSubOption> 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<const std::string_view> prefixes, unsigned int mask,
|
||||
NT_Inst inst, std::span<const std::string_view> prefixes, unsigned int mask,
|
||||
std::function<void(const TopicNotification&)> 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<const std::string_view> prefixes,
|
||||
NT_TopicListenerPoller poller, std::span<const std::string_view> 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<const std::pair<std::string_view, unsigned int>> servers) {
|
||||
std::span<const std::pair<std::string_view, unsigned int>> servers) {
|
||||
if (auto ii = InstanceImpl::GetTyped(inst, Handle::kInstance)) {
|
||||
if (auto client = ii->GetClient()) {
|
||||
std::vector<std::pair<std::string, unsigned int>> serversCopy;
|
||||
|
||||
Reference in New Issue
Block a user