mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
Include .h from .inc/.inl files (NFC) (#3017)
This helps both IDEs and linting tools. Also add some missing braces.
This commit is contained in:
@@ -7,6 +7,8 @@
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
#include "cameraserver/CameraServer.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
template <typename T>
|
||||
@@ -20,8 +22,9 @@ inline cs::AxisCamera CameraServer::AddAxisCamera(
|
||||
const wpi::Twine& name, std::initializer_list<T> hosts) {
|
||||
std::vector<std::string> vec;
|
||||
vec.reserve(hosts.size());
|
||||
for (const auto& host : hosts)
|
||||
for (const auto& host : hosts) {
|
||||
vec.emplace_back(host);
|
||||
}
|
||||
return AddAxisCamera(name, vec);
|
||||
}
|
||||
|
||||
|
||||
@@ -4,6 +4,8 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "vision/VisionRunner.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
/**
|
||||
|
||||
@@ -9,6 +9,8 @@
|
||||
#include <utility>
|
||||
#include <vector>
|
||||
|
||||
#include "cscore_oo.h"
|
||||
|
||||
namespace cs {
|
||||
|
||||
inline std::string VideoProperty::GetName() const {
|
||||
@@ -69,15 +71,16 @@ inline std::vector<std::string> VideoProperty::GetChoices() const {
|
||||
|
||||
inline VideoProperty::VideoProperty(CS_Property handle) : m_handle(handle) {
|
||||
m_status = 0;
|
||||
if (handle == 0)
|
||||
if (handle == 0) {
|
||||
m_kind = kNone;
|
||||
else
|
||||
} else {
|
||||
m_kind =
|
||||
static_cast<Kind>(static_cast<int>(GetPropertyKind(handle, &m_status)));
|
||||
}
|
||||
}
|
||||
|
||||
inline VideoProperty::VideoProperty(CS_Property handle, Kind kind)
|
||||
: m_status(0), m_handle(handle), m_kind(kind) {}
|
||||
: m_handle(handle), m_kind(kind) {}
|
||||
|
||||
inline VideoSource::VideoSource(const VideoSource& source)
|
||||
: m_handle(source.m_handle == 0 ? 0
|
||||
@@ -94,8 +97,9 @@ inline VideoSource& VideoSource::operator=(VideoSource other) noexcept {
|
||||
|
||||
inline VideoSource::~VideoSource() {
|
||||
m_status = 0;
|
||||
if (m_handle != 0)
|
||||
if (m_handle != 0) {
|
||||
ReleaseSource(m_handle, &m_status);
|
||||
}
|
||||
}
|
||||
|
||||
inline VideoSource::Kind VideoSource::GetKind() const {
|
||||
@@ -310,8 +314,9 @@ inline HttpCamera::HttpCamera(const wpi::Twine& name,
|
||||
HttpCameraKind kind) {
|
||||
std::vector<std::string> vec;
|
||||
vec.reserve(urls.size());
|
||||
for (const auto& url : urls)
|
||||
for (const auto& url : urls) {
|
||||
vec.emplace_back(url);
|
||||
}
|
||||
m_handle = CreateHttpCamera(
|
||||
name, vec, static_cast<CS_HttpCameraKind>(static_cast<int>(kind)),
|
||||
&m_status);
|
||||
@@ -332,8 +337,9 @@ template <typename T>
|
||||
inline void HttpCamera::SetUrls(std::initializer_list<T> urls) {
|
||||
std::vector<std::string> vec;
|
||||
vec.reserve(urls.size());
|
||||
for (const auto& url : urls)
|
||||
for (const auto& url : urls) {
|
||||
vec.emplace_back(url);
|
||||
}
|
||||
m_status = 0;
|
||||
::cs::SetHttpCameraUrls(m_handle, vec, &m_status);
|
||||
}
|
||||
@@ -351,8 +357,9 @@ inline std::vector<std::string> AxisCamera::HostToUrl(
|
||||
wpi::ArrayRef<std::string> hosts) {
|
||||
std::vector<std::string> rv;
|
||||
rv.reserve(hosts.size());
|
||||
for (const auto& host : hosts)
|
||||
for (const auto& host : hosts) {
|
||||
rv.emplace_back(HostToUrl(wpi::StringRef{host}));
|
||||
}
|
||||
return rv;
|
||||
}
|
||||
|
||||
@@ -361,8 +368,9 @@ inline std::vector<std::string> AxisCamera::HostToUrl(
|
||||
std::initializer_list<T> hosts) {
|
||||
std::vector<std::string> rv;
|
||||
rv.reserve(hosts.size());
|
||||
for (const auto& host : hosts)
|
||||
for (const auto& host : hosts) {
|
||||
rv.emplace_back(HostToUrl(wpi::StringRef{host}));
|
||||
}
|
||||
return rv;
|
||||
}
|
||||
|
||||
@@ -460,8 +468,9 @@ inline void ImageSource::SetEnumPropertyChoices(
|
||||
const VideoProperty& property, std::initializer_list<T> choices) {
|
||||
std::vector<std::string> vec;
|
||||
vec.reserve(choices.size());
|
||||
for (const auto& choice : choices)
|
||||
for (const auto& choice : choices) {
|
||||
vec.emplace_back(choice);
|
||||
}
|
||||
m_status = 0;
|
||||
SetSourceEnumPropertyChoices(m_handle, property.m_handle, vec, &m_status);
|
||||
}
|
||||
@@ -480,8 +489,9 @@ inline VideoSink& VideoSink::operator=(VideoSink other) noexcept {
|
||||
|
||||
inline VideoSink::~VideoSink() {
|
||||
m_status = 0;
|
||||
if (m_handle != 0)
|
||||
if (m_handle != 0) {
|
||||
ReleaseSink(m_handle, &m_status);
|
||||
}
|
||||
}
|
||||
|
||||
inline VideoSink::Kind VideoSink::GetKind() const {
|
||||
@@ -506,10 +516,11 @@ inline VideoProperty VideoSink::GetProperty(const wpi::Twine& name) {
|
||||
|
||||
inline void VideoSink::SetSource(VideoSource source) {
|
||||
m_status = 0;
|
||||
if (!source)
|
||||
if (!source) {
|
||||
SetSinkSource(m_handle, 0, &m_status);
|
||||
else
|
||||
} else {
|
||||
SetSinkSource(m_handle, source.m_handle, &m_status);
|
||||
}
|
||||
}
|
||||
|
||||
inline VideoSource VideoSink::GetSource() const {
|
||||
@@ -630,8 +641,9 @@ inline VideoListener& VideoListener::operator=(VideoListener&& other) noexcept {
|
||||
|
||||
inline VideoListener::~VideoListener() {
|
||||
CS_Status status = 0;
|
||||
if (m_handle != 0)
|
||||
if (m_handle != 0) {
|
||||
RemoveListener(m_handle, &status);
|
||||
}
|
||||
}
|
||||
|
||||
} // namespace cs
|
||||
|
||||
@@ -6,6 +6,8 @@
|
||||
|
||||
#include <utility>
|
||||
|
||||
#include "glass/Provider.h"
|
||||
|
||||
namespace glass {
|
||||
|
||||
template <typename Functions>
|
||||
@@ -17,11 +19,13 @@ void Provider<Functions>::GlobalInit() {
|
||||
template <typename Functions>
|
||||
void Provider<Functions>::ShowDefault(wpi::StringRef name) {
|
||||
auto win = GetWindow(name);
|
||||
if (win)
|
||||
if (win) {
|
||||
return;
|
||||
}
|
||||
auto it = FindViewEntry(name);
|
||||
if (it == m_viewEntries.end() || (*it)->name != name)
|
||||
if (it == m_viewEntries.end() || (*it)->name != name) {
|
||||
return;
|
||||
}
|
||||
this->Show(it->get(), (*it)->window);
|
||||
}
|
||||
|
||||
@@ -38,8 +42,9 @@ void Provider<Functions>::RegisterModel(wpi::StringRef name, ExistsFunc exists,
|
||||
CreateModelFunc createModel) {
|
||||
auto it = FindModelEntry(name);
|
||||
// ignore if exists
|
||||
if (it != m_modelEntries.end() && (*it)->name == name)
|
||||
if (it != m_modelEntries.end() && (*it)->name == name) {
|
||||
return;
|
||||
}
|
||||
// insert in sorted location
|
||||
m_modelEntries.emplace(
|
||||
it, MakeModelEntry(name, std::move(exists), std::move(createModel)));
|
||||
@@ -52,13 +57,15 @@ void Provider<Functions>::RegisterView(wpi::StringRef name,
|
||||
CreateViewFunc createView) {
|
||||
// find model; if model doesn't exist, ignore
|
||||
auto modelIt = FindModelEntry(modelName);
|
||||
if (modelIt == m_modelEntries.end() || (*modelIt)->name != modelName)
|
||||
if (modelIt == m_modelEntries.end() || (*modelIt)->name != modelName) {
|
||||
return;
|
||||
}
|
||||
|
||||
auto viewIt = FindViewEntry(name);
|
||||
// ignore if exists
|
||||
if (viewIt != m_viewEntries.end() && (*viewIt)->name == name)
|
||||
if (viewIt != m_viewEntries.end() && (*viewIt)->name == name) {
|
||||
return;
|
||||
}
|
||||
// insert in sorted location
|
||||
m_viewEntries.emplace(viewIt,
|
||||
MakeViewEntry(name, modelIt->get(), std::move(exists),
|
||||
@@ -69,8 +76,9 @@ template <typename Functions>
|
||||
void Provider<Functions>::Update() {
|
||||
// update entries
|
||||
for (auto&& entry : m_modelEntries) {
|
||||
if (entry->model)
|
||||
if (entry->model) {
|
||||
entry->model->Update();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -6,13 +6,16 @@
|
||||
|
||||
#include <wpi/StringRef.h>
|
||||
|
||||
#include "glass/support/IniSaver.h"
|
||||
|
||||
namespace glass {
|
||||
|
||||
template <typename Info>
|
||||
void* IniSaver<Info>::IniReadOpen(const char* name) {
|
||||
int num;
|
||||
if (wpi::StringRef{name}.getAsInteger(10, num))
|
||||
if (wpi::StringRef{name}.getAsInteger(10, num)) {
|
||||
return nullptr;
|
||||
}
|
||||
return &m_map[num];
|
||||
}
|
||||
|
||||
|
||||
@@ -6,6 +6,8 @@
|
||||
|
||||
#include <wpi/StringRef.h>
|
||||
|
||||
#include "glass/support/IniSaverString.h"
|
||||
|
||||
namespace glass {
|
||||
|
||||
template <typename Info>
|
||||
|
||||
@@ -6,15 +6,19 @@
|
||||
|
||||
#include <wpi/StringRef.h>
|
||||
|
||||
#include "glass/support/IniSaverVector.h"
|
||||
|
||||
namespace glass {
|
||||
|
||||
template <typename Info>
|
||||
void* IniSaverVector<Info>::IniReadOpen(const char* name) {
|
||||
unsigned int num;
|
||||
if (wpi::StringRef{name}.getAsInteger(10, num))
|
||||
if (wpi::StringRef{name}.getAsInteger(10, num)) {
|
||||
return nullptr;
|
||||
if (num >= this->size())
|
||||
}
|
||||
if (num >= this->size()) {
|
||||
this->resize(num + 1);
|
||||
}
|
||||
return &(*this)[num];
|
||||
}
|
||||
|
||||
|
||||
@@ -9,6 +9,8 @@
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
#include "networktables/NetworkTableEntry.h"
|
||||
|
||||
namespace nt {
|
||||
|
||||
inline NetworkTableEntry::NetworkTableEntry() {}
|
||||
@@ -50,37 +52,42 @@ inline std::shared_ptr<Value> NetworkTableEntry::GetValue() const {
|
||||
|
||||
inline bool NetworkTableEntry::GetBoolean(bool defaultValue) const {
|
||||
auto value = GetEntryValue(m_handle);
|
||||
if (!value || value->type() != NT_BOOLEAN)
|
||||
if (!value || value->type() != NT_BOOLEAN) {
|
||||
return defaultValue;
|
||||
}
|
||||
return value->GetBoolean();
|
||||
}
|
||||
|
||||
inline double NetworkTableEntry::GetDouble(double defaultValue) const {
|
||||
auto value = GetEntryValue(m_handle);
|
||||
if (!value || value->type() != NT_DOUBLE)
|
||||
if (!value || value->type() != NT_DOUBLE) {
|
||||
return defaultValue;
|
||||
}
|
||||
return value->GetDouble();
|
||||
}
|
||||
|
||||
inline std::string NetworkTableEntry::GetString(StringRef defaultValue) const {
|
||||
auto value = GetEntryValue(m_handle);
|
||||
if (!value || value->type() != NT_STRING)
|
||||
if (!value || value->type() != NT_STRING) {
|
||||
return defaultValue;
|
||||
}
|
||||
return value->GetString();
|
||||
}
|
||||
|
||||
inline std::string NetworkTableEntry::GetRaw(StringRef defaultValue) const {
|
||||
auto value = GetEntryValue(m_handle);
|
||||
if (!value || value->type() != NT_RAW)
|
||||
if (!value || value->type() != NT_RAW) {
|
||||
return defaultValue;
|
||||
}
|
||||
return value->GetString();
|
||||
}
|
||||
|
||||
inline std::vector<int> NetworkTableEntry::GetBooleanArray(
|
||||
ArrayRef<int> defaultValue) const {
|
||||
auto value = GetEntryValue(m_handle);
|
||||
if (!value || value->type() != NT_BOOLEAN_ARRAY)
|
||||
if (!value || value->type() != NT_BOOLEAN_ARRAY) {
|
||||
return defaultValue;
|
||||
}
|
||||
return value->GetBooleanArray();
|
||||
}
|
||||
|
||||
@@ -93,8 +100,9 @@ inline std::vector<int> NetworkTableEntry::GetBooleanArray(
|
||||
inline std::vector<double> NetworkTableEntry::GetDoubleArray(
|
||||
ArrayRef<double> defaultValue) const {
|
||||
auto value = GetEntryValue(m_handle);
|
||||
if (!value || value->type() != NT_DOUBLE_ARRAY)
|
||||
if (!value || value->type() != NT_DOUBLE_ARRAY) {
|
||||
return defaultValue;
|
||||
}
|
||||
return value->GetDoubleArray();
|
||||
}
|
||||
|
||||
@@ -107,8 +115,9 @@ inline std::vector<double> NetworkTableEntry::GetDoubleArray(
|
||||
inline std::vector<std::string> NetworkTableEntry::GetStringArray(
|
||||
ArrayRef<std::string> defaultValue) const {
|
||||
auto value = GetEntryValue(m_handle);
|
||||
if (!value || value->type() != NT_STRING_ARRAY)
|
||||
if (!value || value->type() != NT_STRING_ARRAY) {
|
||||
return defaultValue;
|
||||
}
|
||||
return value->GetStringArray();
|
||||
}
|
||||
|
||||
|
||||
@@ -8,6 +8,8 @@
|
||||
#include <utility>
|
||||
#include <vector>
|
||||
|
||||
#include "networktables/NetworkTableInstance.h"
|
||||
|
||||
namespace nt {
|
||||
|
||||
inline NetworkTableInstance::NetworkTableInstance() noexcept {}
|
||||
@@ -24,8 +26,9 @@ inline NetworkTableInstance NetworkTableInstance::Create() {
|
||||
}
|
||||
|
||||
inline void NetworkTableInstance::Destroy(NetworkTableInstance inst) {
|
||||
if (inst.m_handle != 0)
|
||||
if (inst.m_handle != 0) {
|
||||
DestroyInstance(inst.m_handle);
|
||||
}
|
||||
}
|
||||
|
||||
inline NT_Inst NetworkTableInstance::GetHandle() const {
|
||||
@@ -39,8 +42,9 @@ inline NetworkTableEntry NetworkTableInstance::GetEntry(const Twine& name) {
|
||||
inline std::vector<NetworkTableEntry> NetworkTableInstance::GetEntries(
|
||||
const Twine& prefix, unsigned int types) {
|
||||
std::vector<NetworkTableEntry> entries;
|
||||
for (auto entry : ::nt::GetEntries(m_handle, prefix, types))
|
||||
for (auto entry : ::nt::GetEntries(m_handle, prefix, types)) {
|
||||
entries.emplace_back(entry);
|
||||
}
|
||||
return entries;
|
||||
}
|
||||
|
||||
|
||||
@@ -8,6 +8,7 @@
|
||||
#include <string>
|
||||
#include <utility>
|
||||
|
||||
#include "networktables/RpcCall.h"
|
||||
#include "ntcore_cpp.h"
|
||||
|
||||
namespace nt {
|
||||
@@ -18,8 +19,9 @@ inline RpcCall::RpcCall(RpcCall&& other) noexcept : RpcCall() {
|
||||
|
||||
inline RpcCall::~RpcCall() {
|
||||
// automatically cancel result if user didn't request it
|
||||
if (m_call != 0)
|
||||
if (m_call != 0) {
|
||||
CancelResult();
|
||||
}
|
||||
}
|
||||
|
||||
inline bool RpcCall::GetResult(std::string* result) {
|
||||
|
||||
@@ -61,6 +61,6 @@ template <typename T>
|
||||
void CreateSingleProvider(const std::string& key,
|
||||
WSRegisterFunc webRegisterFunc);
|
||||
|
||||
#include "WSHalProviders.inl"
|
||||
|
||||
} // namespace wpilibws
|
||||
|
||||
#include "WSHalProviders.inl"
|
||||
|
||||
@@ -8,6 +8,10 @@
|
||||
#include <string>
|
||||
#include <utility>
|
||||
|
||||
#include "WSHalProviders.h"
|
||||
|
||||
namespace wpilibws {
|
||||
|
||||
template <typename T>
|
||||
void CreateProviders(const std::string& prefix, int numChannels,
|
||||
WSRegisterFunc webRegisterFunc) {
|
||||
@@ -24,3 +28,5 @@ void CreateSingleProvider(const std::string& key,
|
||||
auto ptr = std::make_unique<T>(key, key);
|
||||
webRegisterFunc(key, std::move(ptr));
|
||||
}
|
||||
|
||||
} // namespace wpilibws
|
||||
|
||||
@@ -5,6 +5,9 @@
|
||||
#pragma once
|
||||
|
||||
#include <memory>
|
||||
#include <utility>
|
||||
|
||||
#include "frc2/command/SwerveControllerCommand.h"
|
||||
|
||||
namespace frc2 {
|
||||
|
||||
@@ -17,11 +20,11 @@ SwerveControllerCommand<NumModules>::SwerveControllerCommand(
|
||||
std::function<frc::Rotation2d()> desiredRotation,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: m_trajectory(trajectory),
|
||||
m_pose(pose),
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_kinematics(kinematics),
|
||||
m_controller(xController, yController, thetaController),
|
||||
m_desiredRotation(desiredRotation),
|
||||
m_desiredRotation(std::move(desiredRotation)),
|
||||
m_outputStates(output) {
|
||||
this->AddRequirements(requirements);
|
||||
}
|
||||
@@ -34,8 +37,8 @@ SwerveControllerCommand<NumModules>::SwerveControllerCommand(
|
||||
frc::ProfiledPIDController<units::radians> thetaController,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
: m_trajectory(trajectory),
|
||||
m_pose(pose),
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_kinematics(kinematics),
|
||||
m_controller(xController, yController, thetaController),
|
||||
m_outputStates(output) {
|
||||
@@ -54,11 +57,11 @@ SwerveControllerCommand<NumModules>::SwerveControllerCommand(
|
||||
std::function<frc::Rotation2d()> desiredRotation,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
|
||||
wpi::ArrayRef<Subsystem*> requirements)
|
||||
: m_trajectory(trajectory),
|
||||
m_pose(pose),
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_kinematics(kinematics),
|
||||
m_controller(xController, yController, thetaController),
|
||||
m_desiredRotation(desiredRotation),
|
||||
m_desiredRotation(std::move(desiredRotation)),
|
||||
m_outputStates(output) {
|
||||
this->AddRequirements(requirements);
|
||||
}
|
||||
@@ -71,8 +74,8 @@ SwerveControllerCommand<NumModules>::SwerveControllerCommand(
|
||||
frc::ProfiledPIDController<units::radians> thetaController,
|
||||
std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
|
||||
wpi::ArrayRef<Subsystem*> requirements)
|
||||
: m_trajectory(trajectory),
|
||||
m_pose(pose),
|
||||
: m_trajectory(std::move(trajectory)),
|
||||
m_pose(std::move(pose)),
|
||||
m_kinematics(kinematics),
|
||||
m_controller(xController, yController, thetaController),
|
||||
m_outputStates(output) {
|
||||
|
||||
@@ -7,6 +7,8 @@
|
||||
#include <functional>
|
||||
#include <vector>
|
||||
|
||||
#include "frc/SpeedControllerGroup.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
template <class... SpeedControllers>
|
||||
|
||||
@@ -7,6 +7,8 @@
|
||||
#include <memory>
|
||||
#include <string>
|
||||
|
||||
#include "frc/shuffleboard/ShuffleboardComponent.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
template <typename Derived>
|
||||
|
||||
@@ -12,6 +12,8 @@
|
||||
|
||||
#include <wpi/StringRef.h>
|
||||
|
||||
#include "frc/smartdashboard/SendableChooser.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
template <class T>
|
||||
@@ -31,8 +33,9 @@ auto SendableChooser<T>::GetSelected()
|
||||
std::string selected = m_defaultChoice;
|
||||
{
|
||||
std::scoped_lock lock(m_mutex);
|
||||
if (m_haveSelected)
|
||||
if (m_haveSelected) {
|
||||
selected = m_selected;
|
||||
}
|
||||
}
|
||||
if (selected.empty()) {
|
||||
return decltype(_unwrap_smart_ptr(m_choices[""])){};
|
||||
@@ -86,8 +89,9 @@ void SendableChooser<T>::InitSendable(SendableBuilder& builder) {
|
||||
std::scoped_lock lock(m_mutex);
|
||||
m_haveSelected = true;
|
||||
m_selected = val;
|
||||
for (auto& entry : m_activeEntries)
|
||||
for (auto& entry : m_activeEntries) {
|
||||
entry.SetString(val);
|
||||
}
|
||||
});
|
||||
}
|
||||
|
||||
|
||||
@@ -6,6 +6,7 @@
|
||||
|
||||
#include <algorithm>
|
||||
|
||||
#include "frc/kinematics/SwerveDriveKinematics.h"
|
||||
#include "units/math.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
@@ -4,6 +4,7 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "frc/kinematics/SwerveDriveOdometry.h"
|
||||
#include "wpimath/MathShared.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
@@ -6,6 +6,7 @@
|
||||
|
||||
#include <algorithm>
|
||||
|
||||
#include "frc/trajectory/TrapezoidProfile.h"
|
||||
#include "units/math.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
@@ -4,6 +4,7 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "frc/trajectory/constraint/SwerveDriveKinematicsConstraint.h"
|
||||
#include "units/math.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
@@ -7,6 +7,8 @@
|
||||
|
||||
#include <utility>
|
||||
|
||||
#include "wpi/HttpUtil.h"
|
||||
|
||||
namespace wpi {
|
||||
|
||||
inline HttpPathRef HttpPath::drop_front(size_t n) const {
|
||||
@@ -17,10 +19,12 @@ template <typename T>
|
||||
HttpRequest::HttpRequest(const HttpLocation& loc, const T& extraParams)
|
||||
: host{loc.host}, port{loc.port} {
|
||||
StringMap<StringRef> params;
|
||||
for (const auto& p : loc.params)
|
||||
for (const auto& p : loc.params) {
|
||||
params.insert(std::make_pair(GetFirst(p), GetSecond(p)));
|
||||
for (const auto& p : extraParams)
|
||||
}
|
||||
for (const auto& p : extraParams) {
|
||||
params.insert(std::make_pair(GetFirst(p), GetSecond(p)));
|
||||
}
|
||||
SetPath(loc.path, params);
|
||||
SetAuth(loc);
|
||||
}
|
||||
|
||||
@@ -7,6 +7,8 @@
|
||||
|
||||
#include <memory>
|
||||
|
||||
#include "wpi/HttpWebSocketServerConnection.h"
|
||||
|
||||
namespace wpi {
|
||||
|
||||
template <typename Derived>
|
||||
@@ -22,8 +24,9 @@ HttpWebSocketServerConnection<Derived>::HttpWebSocketServerConnection(
|
||||
StringRef protocol = m_helper.MatchProtocol(protocols).second;
|
||||
|
||||
// Check that the upgrade is valid
|
||||
if (!IsValidWsUpgrade(protocol))
|
||||
if (!IsValidWsUpgrade(protocol)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// Disconnect HttpServerConnection header reader
|
||||
m_dataConn.disconnect();
|
||||
|
||||
@@ -6,6 +6,8 @@
|
||||
|
||||
#include <algorithm>
|
||||
|
||||
#include "wpi/circular_buffer.h"
|
||||
|
||||
namespace wpi {
|
||||
|
||||
template <class T>
|
||||
|
||||
Reference in New Issue
Block a user